- 3.0.2 rigid body dynamics module.
ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS > Class Template Reference

A floating base rigid body system that uses forward dynamics. The input vector is assumed to consist of joint torques and end-effector forces expressed in the world. More...

#include <FloatingBaseFDSystem.h>

Inheritance diagram for ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >:
ct::rbd::RBDSystem< RBDDynamics, QUAT_INTEGRATION > ct::core::SymplecticSystem< RBDDynamics::NSTATE/2+QUAT_INTEGRATION, RBDDynamics::NSTATE/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR > ct::core::ControlledSystem< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR > ct::core::System< STATE_DIM, SCALAR >

Public Types

using Dynamics = RBDDynamics
 
using Kinematics = typename RBDDynamics::Kinematics_t
 
typedef RBDDynamics::SCALAR SCALAR
 
typedef core::StateVector< STATE_DIM, SCALARStateVector
 
typedef core::ControlVector< CONTROL_DIM, SCALARControlVector
 
typedef core::SymplecticSystem< RBDDynamics::NSTATE/2+QUAT_INTEGRATION, RBDDynamics::NSTATE/2, CONTROL_DIM, SCALARBase
 
using ContactModel = ct::rbd::EEContactModel< Kinematics >
 
- Public Types inherited from ct::core::SymplecticSystem< RBDDynamics::NSTATE/2+QUAT_INTEGRATION, RBDDynamics::NSTATE/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR >
typedef Base::time_t time_t
 
- Public Types inherited from ct::core::ControlledSystem< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR >
typedef std::shared_ptr< ControlledSystem< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR > > Ptr
 
typedef Base::time_t time_t
 
- Public Types inherited from ct::core::System< STATE_DIM, SCALAR >
typedef SCALAR time_t
 

Public Member Functions

 FloatingBaseFDSystem ()
 
 FloatingBaseFDSystem (const FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS > &other)
 
virtual ~FloatingBaseFDSystem ()
 
virtual FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS > * clone () const override
 
virtual RBDDynamics & dynamics () override
 
virtual const RBDDynamics & dynamics () const override
 
void setContactModel (const std::shared_ptr< ContactModel > &contactModel)
 
virtual void computePdot (const StateVector &x, const core::StateVector< RBDDynamics::NSTATE/2, SCALAR > &v, const ControlVector &control, core::StateVector< RBDDynamics::NSTATE/2+QUAT_INTEGRATION, SCALAR > &pDot) override
 
virtual void computeVdot (const StateVector &x, const core::StateVector< RBDDynamics::NSTATE/2+QUAT_INTEGRATION, SCALAR > &p, const ControlVector &control, core::StateVector< RBDDynamics::NSTATE/2, SCALAR > &vDot) override
 
void mapEndeffectorForcesToLinkForces (const typename RBDDynamics::RBDState_t &state, const std::array< typename Kinematics::EEForceLinear, N_EE > &eeForcesW, typename RBDDynamics::ExtLinkForces_t &linkForces)
 
RBDDynamics::RBDState_t RBDStateFromVector (const core::StateVector< STATE_DIM, SCALAR > &state)
 
template<bool T>
RBDDynamics::RBDState_t RBDStateFromVectorImpl (const core::StateVector< STATE_DIM, SCALAR > &state, typename std::enable_if< T, bool >::type=true)
 
template<bool T>
RBDDynamics::RBDState_t RBDStateFromVectorImpl (const core::StateVector< STATE_DIM, SCALAR > &state, typename std::enable_if<!T, bool >::type=true)
 
template<bool T>
core::StateVector< STATE_DIM, SCALARtoStateDerivative (const typename RBDDynamics::RBDAcceleration_t &acceleration, const typename RBDDynamics::RBDState_t &state, typename std::enable_if< T, bool >::type=true)
 
template<bool T>
core::StateVector< STATE_DIM, SCALARtoStateDerivative (const typename RBDDynamics::RBDAcceleration_t &acceleration, const typename RBDDynamics::RBDState_t &state, typename std::enable_if<!T, bool >::type=true)
 
template<bool T>
core::StateVector< STATE_DIM, SCALARtoStateVector (const typename RBDDynamics::RBDState_t &state, typename std::enable_if< T, bool >::type=true)
 
template<bool T>
core::StateVector< STATE_DIM, SCALARtoStateVector (const typename RBDDynamics::RBDState_t &state, typename std::enable_if<!T, bool >::type=true)
 
- Public Member Functions inherited from ct::rbd::RBDSystem< RBDDynamics, QUAT_INTEGRATION >
 RBDSystem ()=default
 
virtual ~RBDSystem ()=default
 
- Public Member Functions inherited from ct::core::SymplecticSystem< RBDDynamics::NSTATE/2+QUAT_INTEGRATION, RBDDynamics::NSTATE/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR >
 SymplecticSystem (const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL)
 
 SymplecticSystem (std::shared_ptr< ct::core::Controller< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR >> controller, const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL)
 
 SymplecticSystem (const SymplecticSystem &arg)
 
virtual ~SymplecticSystem ()
 
virtual bool isSymplectic () const override
 
virtual void computeControlledDynamics (const StateVector< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::SCALAR > &state, const time_t &t, const ControlVector< RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR > &control, StateVector< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::SCALAR > &derivative) override
 
void computePdot (const StateVector< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::SCALAR > &x, const StateVector< RBDDynamics::NSTATE/2, RBDDynamics::SCALAR > &v, StateVector< RBDDynamics::NSTATE/2+QUAT_INTEGRATION, RBDDynamics::SCALAR > &pDot)
 
virtual void computePdot (const StateVector< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::SCALAR > &x, const StateVector< RBDDynamics::NSTATE/2, RBDDynamics::SCALAR > &v, const ControlVector< RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR > &control, StateVector< RBDDynamics::NSTATE/2+QUAT_INTEGRATION, RBDDynamics::SCALAR > &pDot)=0
 
void computeVdot (const StateVector< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::SCALAR > &x, const StateVector< RBDDynamics::NSTATE/2+QUAT_INTEGRATION, RBDDynamics::SCALAR > &p, StateVector< RBDDynamics::NSTATE/2, RBDDynamics::SCALAR > &vDot)
 
virtual void computeVdot (const StateVector< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::SCALAR > &x, const StateVector< RBDDynamics::NSTATE/2+QUAT_INTEGRATION, RBDDynamics::SCALAR > &p, const ControlVector< RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR > &control, StateVector< RBDDynamics::NSTATE/2, RBDDynamics::SCALAR > &vDot)=0
 
- Public Member Functions inherited from ct::core::ControlledSystem< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR >
 ControlledSystem (const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL)
 
 ControlledSystem (std::shared_ptr< ct::core::Controller< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR >> controller, const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL)
 
 ControlledSystem (const ControlledSystem &arg)
 
virtual ~ControlledSystem ()
 
void setController (const std::shared_ptr< Controller< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR >> &controller)
 
void getController (std::shared_ptr< Controller< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR >> &controller) const
 
std::shared_ptr< Controller< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR > > getController ()
 
virtual void computeDynamics (const StateVector< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::SCALAR > &state, const time_t &t, StateVector< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::SCALAR > &derivative) override
 
ControlVector< RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALARgetLastControlAction ()
 
- Public Member Functions inherited from ct::core::System< STATE_DIM, SCALAR >
 System (const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL)
 
 System (const System &other)
 
virtual ~System ()
 
virtual void computeDynamics (const StateVector< STATE_DIM, SCALAR > &state, const time_t &t, StateVector< STATE_DIM, SCALAR > &derivative)=0
 
SYSTEM_TYPE getType () const
 

Static Public Attributes

static const size_t N_EE = RBDDynamics::N_EE
 
static const size_t STATE_DIM = RBDDynamics::NSTATE + QUAT_INTEGRATION
 
static const size_t CONTROL_DIM = RBDDynamics::NJOINTS + EE_ARE_CONTROL_INPUTS * N_EE * 3
 

Additional Inherited Members

- Public Attributes inherited from ct::core::SymplecticSystem< RBDDynamics::NSTATE/2+QUAT_INTEGRATION, RBDDynamics::NSTATE/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef ControlledSystem< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALARBase
 
- Public Attributes inherited from ct::core::ControlledSystem< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef System< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::SCALARBase
 
- Public Attributes inherited from ct::core::System< STATE_DIM, SCALAR >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef SCALAR S
 
- Protected Attributes inherited from ct::core::ControlledSystem< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR >
std::shared_ptr< Controller< RBDDynamics::NSTATE/2+QUAT_INTEGRATION+RBDDynamics::NSTATE/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR > > controller_
 
ControlVector< RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALARcontrolAction_
 
- Protected Attributes inherited from ct::core::System< STATE_DIM, SCALAR >
SYSTEM_TYPE type_
 

Detailed Description

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
class ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >

A floating base rigid body system that uses forward dynamics. The input vector is assumed to consist of joint torques and end-effector forces expressed in the world.

Member Typedef Documentation

◆ Dynamics

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
using ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::Dynamics = RBDDynamics

◆ Kinematics

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
using ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::Kinematics = typename RBDDynamics::Kinematics_t

◆ SCALAR

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
typedef RBDDynamics::SCALAR ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::SCALAR

◆ StateVector

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
typedef core::StateVector<STATE_DIM, SCALAR> ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::StateVector

◆ ControlVector

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
typedef core::ControlVector<CONTROL_DIM, SCALAR> ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::ControlVector

◆ Base

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
typedef core:: SymplecticSystem<RBDDynamics::NSTATE / 2 + QUAT_INTEGRATION, RBDDynamics::NSTATE / 2, CONTROL_DIM, SCALAR> ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::Base

◆ ContactModel

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
using ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::ContactModel = ct::rbd::EEContactModel<Kinematics>

Constructor & Destructor Documentation

◆ FloatingBaseFDSystem() [1/2]

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::FloatingBaseFDSystem ( )
inline

◆ FloatingBaseFDSystem() [2/2]

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::FloatingBaseFDSystem ( const FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS > &  other)
inline

◆ ~FloatingBaseFDSystem()

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
virtual ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::~FloatingBaseFDSystem ( )
inlinevirtual

Member Function Documentation

◆ clone()

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
virtual FloatingBaseFDSystem<RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS>* ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::clone ( ) const
inlineoverridevirtual

◆ dynamics() [1/2]

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
virtual RBDDynamics& ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::dynamics ( )
inlineoverridevirtual

◆ dynamics() [2/2]

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
virtual const RBDDynamics& ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::dynamics ( ) const
inlineoverridevirtual

◆ setContactModel()

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
void ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::setContactModel ( const std::shared_ptr< ContactModel > &  contactModel)
inline

◆ computePdot()

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
virtual void ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::computePdot ( const StateVector x,
const core::StateVector< RBDDynamics::NSTATE/2, SCALAR > &  v,
const ControlVector control,
core::StateVector< RBDDynamics::NSTATE/2+QUAT_INTEGRATION, SCALAR > &  pDot 
)
inlineoverridevirtual

◆ computeVdot()

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
virtual void ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::computeVdot ( const StateVector x,
const core::StateVector< RBDDynamics::NSTATE/2+QUAT_INTEGRATION, SCALAR > &  p,
const ControlVector control,
core::StateVector< RBDDynamics::NSTATE/2, SCALAR > &  vDot 
)
inlineoverridevirtual

◆ mapEndeffectorForcesToLinkForces()

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
void ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::mapEndeffectorForcesToLinkForces ( const typename RBDDynamics::RBDState_t &  state,
const std::array< typename Kinematics::EEForceLinear, N_EE > &  eeForcesW,
typename RBDDynamics::ExtLinkForces_t linkForces 
)
inline

Maps the end-effector forces expressed in the world to the link frame as required by robcogen. The link forces are transformed from world frame to the link frame. The according momentum is added.

Parameters
staterobot state
controlend-effector forces expressed in the world
linkForcesforces acting on the link expressed in the link frame

References i, and ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::N_EE.

Referenced by ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::computeVdot().

◆ RBDStateFromVector()

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
RBDDynamics::RBDState_t ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::RBDStateFromVector ( const core::StateVector< STATE_DIM, SCALAR > &  state)
inline

◆ RBDStateFromVectorImpl() [1/2]

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
template<bool T>
RBDDynamics::RBDState_t ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::RBDStateFromVectorImpl ( const core::StateVector< STATE_DIM, SCALAR > &  state,
typename std::enable_if< T, bool >::type  = true 
)
inline

References x.

◆ RBDStateFromVectorImpl() [2/2]

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
template<bool T>
RBDDynamics::RBDState_t ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::RBDStateFromVectorImpl ( const core::StateVector< STATE_DIM, SCALAR > &  state,
typename std::enable_if<!T, bool >::type  = true 
)
inline

References x.

◆ toStateDerivative() [1/2]

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
template<bool T>
core::StateVector<STATE_DIM, SCALAR> ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::toStateDerivative ( const typename RBDDynamics::RBDAcceleration_t &  acceleration,
const typename RBDDynamics::RBDState_t &  state,
typename std::enable_if< T, bool >::type  = true 
)
inline

◆ toStateDerivative() [2/2]

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
template<bool T>
core::StateVector<STATE_DIM, SCALAR> ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::toStateDerivative ( const typename RBDDynamics::RBDAcceleration_t &  acceleration,
const typename RBDDynamics::RBDState_t &  state,
typename std::enable_if<!T, bool >::type  = true 
)
inline

◆ toStateVector() [1/2]

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
template<bool T>
core::StateVector<STATE_DIM, SCALAR> ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::toStateVector ( const typename RBDDynamics::RBDState_t &  state,
typename std::enable_if< T, bool >::type  = true 
)
inline

◆ toStateVector() [2/2]

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
template<bool T>
core::StateVector<STATE_DIM, SCALAR> ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::toStateVector ( const typename RBDDynamics::RBDState_t &  state,
typename std::enable_if<!T, bool >::type  = true 
)
inline

Member Data Documentation

◆ N_EE

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
const size_t ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::N_EE = RBDDynamics::N_EE
static

◆ STATE_DIM

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
const size_t ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::STATE_DIM = RBDDynamics::NSTATE + QUAT_INTEGRATION
static

Referenced by TEST().

◆ CONTROL_DIM

template<class RBDDynamics, bool QUAT_INTEGRATION = false, bool EE_ARE_CONTROL_INPUTS = false>
const size_t ct::rbd::FloatingBaseFDSystem< RBDDynamics, QUAT_INTEGRATION, EE_ARE_CONTROL_INPUTS >::CONTROL_DIM = RBDDynamics::NJOINTS + EE_ARE_CONTROL_INPUTS * N_EE * 3
static

Referenced by TEST().


The documentation for this class was generated from the following file: