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

A fix base rigid body system that uses forward dynamics. More...

#include <FixBaseFDSystemSymplectic.h>

Inheritance diagram for ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >:
ct::rbd::RBDSystem< RBDDynamics, false > ct::core::SymplecticSystem< RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR > ct::core::ControlledSystem< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/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 SCALAR = typename RBDDynamics::SCALAR
 
using Base = core::SymplecticSystem< STATE_DIM/2, STATE_DIM/2, CONTROL_DIM, SCALAR >
 
using ActuatorDynamics_t = ActuatorDynamicsSymplectic< RBDDynamics::NJOINTS, ACT_STATE_DIM, SCALAR >
 
using state_vector_full_t = core::StateVector< STATE_DIM, SCALAR >
 
using control_vector_full_t = core::ControlVector< CONTROL_DIM, SCALAR >
 
using state_vector_rbd_t = core::StateVector< RBDDynamics::NSTATE, SCALAR >
 
using state_vector_act_t = core::StateVector< ACTUATOR_STATE_DIM, SCALAR >
 
using p_vector_full_t = core::StateVector< STATE_DIM/2, SCALAR >
 
using v_vector_full_t = core::StateVector< STATE_DIM/2, SCALAR >
 
using p_vector_rbd_t = core::StateVector< RBDDynamics::NSTATE/2, SCALAR >
 
using v_vector_rbd_t = core::StateVector< RBDDynamics::NSTATE/2, SCALAR >
 
using p_vector_act_t = core::StateVector< ACTUATOR_STATE_DIM/2, SCALAR >
 
using v_vector_act_t = core::StateVector< ACTUATOR_STATE_DIM/2, SCALAR >
 
- Public Types inherited from ct::core::SymplecticSystem< RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::NJOINTS+ACT_STATE_DIM/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::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR >
typedef std::shared_ptr< ControlledSystem< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/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

 FixBaseFDSystemSymplectic ()
 constructor More...
 
 FixBaseFDSystemSymplectic (std::shared_ptr< ActuatorDynamics_t > actuatorDynamics)
 constructor including actuator dynamics More...
 
 FixBaseFDSystemSymplectic (const FixBaseFDSystemSymplectic &arg)
 copy constructor More...
 
virtual ~FixBaseFDSystemSymplectic ()
 destructor More...
 
virtual RBDDynamics & dynamics () override
 get dynamics More...
 
virtual const RBDDynamics & dynamics () const override
 get dynamics (const) More...
 
virtual void computePdot (const state_vector_full_t &x, const v_vector_full_t &v, const control_vector_full_t &controlIn, p_vector_full_t &pDot) override
 compute position derivatives, for both RBD system and actuator dynamics, if applicable More...
 
ACTUATOR_DYNAMICS_ENABLED computeActuatorPdot (const typename RBDDynamics::JointState_t &jState, const state_vector_full_t &x, const v_vector_full_t &v, const control_vector_full_t &controlIn, p_vector_full_t &pDot)
 
ACTUATOR_DYNAMICS_DISABLED computeActuatorPdot (const typename RBDDynamics::JointState_t &jState, const state_vector_full_t &x, const v_vector_full_t &v, const control_vector_full_t &controlIn, p_vector_full_t &pDot)
 
virtual void computeVdot (const state_vector_full_t &x, const p_vector_full_t &p, const control_vector_full_t &controlIn, v_vector_full_t &vDot) override
 compute velocity derivatives, for both RBD system and actuator dynamics More...
 
ACTUATOR_DYNAMICS_ENABLED computeActuatorVdot (const typename RBDDynamics::JointState_t &jState, const state_vector_full_t &x, const p_vector_full_t &p, const control_vector_full_t &controlIn, v_vector_full_t &vDot, control_vector_full_t &controlOut)
 
ACTUATOR_DYNAMICS_DISABLED computeActuatorVdot (const typename RBDDynamics::JointState_t &jState, const state_vector_full_t &x, const p_vector_full_t &p, const control_vector_full_t &controlIn, v_vector_full_t &vDot, control_vector_full_t &controlOut)
 
virtual FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS > * clone () const override
 deep cloning More...
 
- Public Member Functions inherited from ct::rbd::RBDSystem< RBDDynamics, false >
 RBDSystem ()=default
 
virtual ~RBDSystem ()=default
 
- Public Member Functions inherited from ct::core::SymplecticSystem< RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::NJOINTS+ACT_STATE_DIM/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::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/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::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/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::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &derivative) override
 
void computePdot (const StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &x, const StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &v, StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &pDot)
 
virtual void computePdot (const StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &x, const StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &v, const ControlVector< RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR > &control, StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &pDot)=0
 
void computeVdot (const StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &x, const StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &p, StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &vDot)
 
virtual void computeVdot (const StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &x, const StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &p, const ControlVector< RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR > &control, StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &vDot)=0
 
- Public Member Functions inherited from ct::core::ControlledSystem< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/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::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/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::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR >> &controller)
 
void getController (std::shared_ptr< Controller< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR >> &controller) const
 
std::shared_ptr< Controller< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR > > getController ()
 
virtual void computeDynamics (const StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &state, const time_t &t, StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/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 Member Functions

static const RBDDynamics::JointState_t jointStateFromVector (const state_vector_full_t &x_full)
 full vector to ct JointState More...
 
static const RBDDynamics::RBDState_t RBDStateFromVector (const state_vector_full_t &x_full, const tpl::RigidBodyPose< SCALAR > &basePose=tpl::RigidBodyPose< SCALAR >())
 transform control systems state vector to a RBDState More...
 
static const state_vector_rbd_t rbdStateFromVector (const state_vector_full_t &x_full)
 transform control systems state vector to a RBDState More...
 
static const state_vector_act_t actuatorStateFromVector (const state_vector_full_t &state)
 transform control systems state vector to the pure actuator state More...
 
static const state_vector_full_t toFullState (const state_vector_rbd_t &x_rbd, const state_vector_act_t &x_act=state_vector_act_t::Zero())
 transform from "reduced" to full coordinates including actuator dynamics More...
 

Static Public Attributes

static EIGEN_MAKE_ALIGNED_OPERATOR_NEW const size_t N_EE = RBDDynamics::N_EE
 
static const size_t STATE_DIM = RBDDynamics::NSTATE + ACT_STATE_DIM
 
static const size_t CONTROL_DIM
 
static const size_t ACTUATOR_STATE_DIM = ACT_STATE_DIM
 
static const size_t NJOINTS = RBDDynamics::NJOINTS
 

Additional Inherited Members

- Public Attributes inherited from ct::core::SymplecticSystem< RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef ControlledSystem< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALARBase
 
- Public Attributes inherited from ct::core::ControlledSystem< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef System< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/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::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR >
std::shared_ptr< Controller< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/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, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
class ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >

A fix base rigid body system that uses forward dynamics.

A fix base rigid body system that uses forward dynamics. The control input vector is assumed to consist of

  • joint torques and
  • end effector forces expressed in the world frame

The state vectors of the pure RBD system and the actuator dynamics are split such that the overall system can be considered symplectic. The state vector therefore reads as

\[ ( \theta_{joints}^\top p_{act}^\top \dot \theta{joints}^\top v_{act}^\top )^\top \]

Warning
Make sure the actuator dynamics can be written as a symplectic system in case of using a symplectic integrator.

Member Typedef Documentation

◆ Dynamics

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
using ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::Dynamics = RBDDynamics

◆ SCALAR

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
using ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::SCALAR = typename RBDDynamics::SCALAR

◆ Base

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
using ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::Base = core::SymplecticSystem<STATE_DIM / 2, STATE_DIM / 2, CONTROL_DIM, SCALAR>

◆ ActuatorDynamics_t

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
using ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::ActuatorDynamics_t = ActuatorDynamicsSymplectic<RBDDynamics::NJOINTS, ACT_STATE_DIM, SCALAR>

◆ state_vector_full_t

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
using ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::state_vector_full_t = core::StateVector<STATE_DIM, SCALAR>

◆ control_vector_full_t

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
using ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::control_vector_full_t = core::ControlVector<CONTROL_DIM, SCALAR>

◆ state_vector_rbd_t

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
using ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::state_vector_rbd_t = core::StateVector<RBDDynamics::NSTATE, SCALAR>

◆ state_vector_act_t

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
using ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::state_vector_act_t = core::StateVector<ACTUATOR_STATE_DIM, SCALAR>

◆ p_vector_full_t

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
using ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::p_vector_full_t = core::StateVector<STATE_DIM / 2, SCALAR>

◆ v_vector_full_t

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
using ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::v_vector_full_t = core::StateVector<STATE_DIM / 2, SCALAR>

◆ p_vector_rbd_t

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
using ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::p_vector_rbd_t = core::StateVector<RBDDynamics::NSTATE / 2, SCALAR>

◆ v_vector_rbd_t

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
using ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::v_vector_rbd_t = core::StateVector<RBDDynamics::NSTATE / 2, SCALAR>

◆ p_vector_act_t

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
using ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::p_vector_act_t = core::StateVector<ACTUATOR_STATE_DIM / 2, SCALAR>

◆ v_vector_act_t

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
using ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::v_vector_act_t = core::StateVector<ACTUATOR_STATE_DIM / 2, SCALAR>

Constructor & Destructor Documentation

◆ FixBaseFDSystemSymplectic() [1/3]

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::FixBaseFDSystemSymplectic ( )
inline

constructor

References SECOND_ORDER.

◆ FixBaseFDSystemSymplectic() [2/3]

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::FixBaseFDSystemSymplectic ( std::shared_ptr< ActuatorDynamics_t actuatorDynamics)
inline

constructor including actuator dynamics

References SECOND_ORDER.

◆ FixBaseFDSystemSymplectic() [3/3]

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::FixBaseFDSystemSymplectic ( const FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS > &  arg)
inline

copy constructor

Parameters
arginstance of FixBaseFDSystemSymplectic to be copied.
Note
takes care of explicitly cloning actuatorDynamics, if existent

◆ ~FixBaseFDSystemSymplectic()

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
virtual ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::~FixBaseFDSystemSymplectic ( )
inlinevirtual

destructor

Member Function Documentation

◆ dynamics() [1/2]

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
virtual RBDDynamics& ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::dynamics ( )
inlineoverridevirtual

get dynamics

Implements ct::rbd::RBDSystem< RBDDynamics, false >.

◆ dynamics() [2/2]

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
virtual const RBDDynamics& ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::dynamics ( ) const
inlineoverridevirtual

get dynamics (const)

Implements ct::rbd::RBDSystem< RBDDynamics, false >.

◆ computePdot()

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
virtual void ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::computePdot ( const state_vector_full_t x,
const v_vector_full_t v,
const control_vector_full_t controlIn,
p_vector_full_t pDot 
)
inlineoverridevirtual

compute position derivatives, for both RBD system and actuator dynamics, if applicable

References ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::jointStateFromVector().

◆ computeActuatorPdot() [1/2]

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
ACTUATOR_DYNAMICS_ENABLED ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::computeActuatorPdot ( const typename RBDDynamics::JointState_t &  jState,
const state_vector_full_t x,
const v_vector_full_t v,
const control_vector_full_t controlIn,
p_vector_full_t pDot 
)
inline

◆ computeActuatorPdot() [2/2]

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
ACTUATOR_DYNAMICS_DISABLED ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::computeActuatorPdot ( const typename RBDDynamics::JointState_t &  jState,
const state_vector_full_t x,
const v_vector_full_t v,
const control_vector_full_t controlIn,
p_vector_full_t pDot 
)
inline

◆ computeVdot()

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
virtual void ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::computeVdot ( const state_vector_full_t x,
const p_vector_full_t p,
const control_vector_full_t controlIn,
v_vector_full_t vDot 
)
inlineoverridevirtual

compute velocity derivatives, for both RBD system and actuator dynamics

References i, and ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::jointStateFromVector().

◆ computeActuatorVdot() [1/2]

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
ACTUATOR_DYNAMICS_ENABLED ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::computeActuatorVdot ( const typename RBDDynamics::JointState_t &  jState,
const state_vector_full_t x,
const p_vector_full_t p,
const control_vector_full_t controlIn,
v_vector_full_t vDot,
control_vector_full_t controlOut 
)
inline

◆ computeActuatorVdot() [2/2]

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
ACTUATOR_DYNAMICS_DISABLED ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::computeActuatorVdot ( const typename RBDDynamics::JointState_t &  jState,
const state_vector_full_t x,
const p_vector_full_t p,
const control_vector_full_t controlIn,
v_vector_full_t vDot,
control_vector_full_t controlOut 
)
inline

◆ clone()

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
virtual FixBaseFDSystemSymplectic<RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS>* ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::clone ( ) const
inlineoverridevirtual

◆ jointStateFromVector()

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
static const RBDDynamics::JointState_t ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::jointStateFromVector ( const state_vector_full_t x_full)
inlinestatic

◆ RBDStateFromVector()

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
static const RBDDynamics::RBDState_t ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::RBDStateFromVector ( const state_vector_full_t x_full,
const tpl::RigidBodyPose< SCALAR > &  basePose = tpl::RigidBodyPose<SCALAR>() 
)
inlinestatic

◆ rbdStateFromVector()

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
static const state_vector_rbd_t ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::rbdStateFromVector ( const state_vector_full_t x_full)
inlinestatic

transform control systems state vector to a RBDState

◆ actuatorStateFromVector()

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
static const state_vector_act_t ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::actuatorStateFromVector ( const state_vector_full_t state)
inlinestatic

transform control systems state vector to the pure actuator state

◆ toFullState()

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
static const state_vector_full_t ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::toFullState ( const state_vector_rbd_t x_rbd,
const state_vector_act_t x_act = state_vector_act_t::Zero() 
)
inlinestatic

transform from "reduced" to full coordinates including actuator dynamics

References ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::NJOINTS.

Member Data Documentation

◆ N_EE

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW const size_t ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::N_EE = RBDDynamics::N_EE
static

◆ STATE_DIM

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
const size_t ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::STATE_DIM = RBDDynamics::NSTATE + ACT_STATE_DIM
static

◆ CONTROL_DIM

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
const size_t ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::CONTROL_DIM
static
Initial value:
=
RBDDynamics::NJOINTS + EE_ARE_CONTROL_INPUTS * RBDDynamics::N_EE * 3

◆ ACTUATOR_STATE_DIM

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
const size_t ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::ACTUATOR_STATE_DIM = ACT_STATE_DIM
static

◆ NJOINTS

template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
const size_t ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::NJOINTS = RBDDynamics::NJOINTS
static

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