- 3.0.2 rigid body dynamics module.
ct::rbd::Dynamics< RBD, NEE > Class Template Reference

This class implements the equations of motion of a Rigid Body System. More...

#include <Dynamics.h>

Public Types

typedef ROBCOGEN::SCALAR SCALAR
 
typedef Eigen::Matrix< SCALAR, NJOINTS, 1 > control_vector_t
 
typedef Eigen::Matrix< SCALAR, NSTATE, 1 > state_vector_t
 
typedef Eigen::Matrix< SCALAR, 6, 1 > Vector6d_t
 
typedef Vector6d_t ForceVector_t
 
typedef RBDState< NJOINTS, SCALARRBDState_t
 
typedef RBDAcceleration< NJOINTS, SCALARRBDAcceleration_t
 
typedef JointState< NJOINTS, SCALARJointState_t
 
typedef JointAcceleration< NJOINTS, SCALARJointAcceleration_t
 
typedef tpl::RigidBodyAcceleration< SCALARRigidBodyAcceleration_t
 
typedef SelectionMatrix< NJOINTS, NSTATE/2, SCALARSelectionMatrix_t
 
typedef RBD::LinkForceMap ExtLinkForces_t
 
typedef RBDDataMap< bool, NEE > EE_in_contact_t
 
typedef Kinematics< RBD, NEE > Kinematics_t
 

Public Member Functions

 Dynamics (typename Kinematics_t::Ptr_t kinematics=typename Kinematics_t::Ptr_t(new Kinematics_t()))
 The constructor. More...
 
 Dynamics (const Dynamics &other)
 
virtual ~Dynamics ()
 
ENABLE_FIX_BASE FixBaseForwardDynamics (const JointState_t &x, const control_vector_t &u, ExtLinkForces_t &force, JointAcceleration_t &qdd)
 Compute forward dynamics of a fixed-base RBD system under external forces. More...
 
ENABLE_FIX_BASE FixBaseForwardDynamics (const JointState_t &x, const control_vector_t &u, JointAcceleration_t &qdd)
 Compute forward dynamics of a fixed-base RBD system, NO contact forces forces. More...
 
ENABLE_FIX_BASE FixBaseID (const JointState_t &x, const JointAcceleration_t &qdd, const ExtLinkForces_t &force, control_vector_t &u)
 Computes Inverse dynamics of a fixed-base system under external forces. More...
 
ENABLE_FIX_BASE FixBaseID (const JointState_t &x, const JointAcceleration_t &qdd, control_vector_t &u)
 Computes Inverse dynamics of a fixed-base system without external forces. More...
 
ENABLE_FLOAT_BASE FloatingBaseForwardDynamics (const RBDState_t &x, const control_vector_t &u, const ExtLinkForces_t &link_forces, RBDAcceleration_t &xd)
 Compute forward dynamics for an floating-base RBD system under external forces. More...
 
ENABLE_FLOAT_BASE FloatingBaseID (const RBDState_t &x, const JointAcceleration_t &qdd, const ExtLinkForces_t &force, control_vector_t &u, RigidBodyAcceleration_t &base_a)
 Computes Inverse dynamics of a floating-base system under external forces. More...
 
ENABLE_FLOAT_BASE FloatingBaseFullyActuatedID (const RBDState_t &x, const RigidBodyAcceleration_t &base_ac, const JointAcceleration_t &qdd, const ExtLinkForces_t &force, ForceVector_t &base_w, control_vector_t &u)
 Computes the inverse dynamics of a floating-base fully-actuated system. More...
 
ENABLE_FLOAT_BASE ProjectedForwardDynamics (const EE_in_contact_t &ee_contact, const RBDState_t &x, const control_vector_t &u, RBDAcceleration_t &rbd_a)
 Computes Projected Forward Dynamics of a floating-base system with contact constraints. More...
 
ENABLE_FLOAT_BASE ProjectedInverseDynamics (const EE_in_contact_t &ee_contact, const RBDState_t &x, const RBDAcceleration_t &rbd_a, control_vector_t &u)
 
ENABLE_FLOAT_BASE ProjectedInverseDynamicsNoGravity (const EE_in_contact_t &ee_contact, const RBDState_t &x, const RBDAcceleration_t &rbd_a, control_vector_t &u)
 
Kinematics_tkinematics ()
 
const Kinematics_tkinematics () const
 
Kinematics_t::Ptr_tkinematicsPtr ()
 
const Kinematics_t::Ptr_tkinematicsPtr () const
 
SelectionMatrix_tS ()
 
const SelectionMatrix_tS () const
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef RBD ROBCOGEN
 

Static Public Attributes

static const bool FB = ROBCOGEN::TRAIT::floating_base
 
static const size_t NJOINTS = RBD::NJOINTS
 
static const size_t NLINKS = RBD::NLINKS
 
static const size_t NSTATE = FB * RBDState<NJOINTS, SCALAR>::NSTATE + (1 - FB) * 2 * NJOINTS
 
static const size_t N_EE = NEE
 

Detailed Description

template<class RBD, size_t NEE>
class ct::rbd::Dynamics< RBD, NEE >

This class implements the equations of motion of a Rigid Body System.

Template Parameters
RBDThe rbd container class
NEEThe number of endeffectors

Member Typedef Documentation

◆ SCALAR

template<class RBD, size_t NEE>
typedef ROBCOGEN::SCALAR ct::rbd::Dynamics< RBD, NEE >::SCALAR

◆ control_vector_t

template<class RBD, size_t NEE>
typedef Eigen::Matrix<SCALAR, NJOINTS, 1> ct::rbd::Dynamics< RBD, NEE >::control_vector_t

◆ state_vector_t

template<class RBD, size_t NEE>
typedef Eigen::Matrix<SCALAR, NSTATE, 1> ct::rbd::Dynamics< RBD, NEE >::state_vector_t

◆ Vector6d_t

template<class RBD, size_t NEE>
typedef Eigen::Matrix<SCALAR, 6, 1> ct::rbd::Dynamics< RBD, NEE >::Vector6d_t

◆ ForceVector_t

template<class RBD, size_t NEE>
typedef Vector6d_t ct::rbd::Dynamics< RBD, NEE >::ForceVector_t

◆ RBDState_t

template<class RBD, size_t NEE>
typedef RBDState<NJOINTS, SCALAR> ct::rbd::Dynamics< RBD, NEE >::RBDState_t

◆ RBDAcceleration_t

template<class RBD, size_t NEE>
typedef RBDAcceleration<NJOINTS, SCALAR> ct::rbd::Dynamics< RBD, NEE >::RBDAcceleration_t

◆ JointState_t

template<class RBD, size_t NEE>
typedef JointState<NJOINTS, SCALAR> ct::rbd::Dynamics< RBD, NEE >::JointState_t

◆ JointAcceleration_t

template<class RBD, size_t NEE>
typedef JointAcceleration<NJOINTS, SCALAR> ct::rbd::Dynamics< RBD, NEE >::JointAcceleration_t

◆ RigidBodyAcceleration_t

template<class RBD, size_t NEE>
typedef tpl::RigidBodyAcceleration<SCALAR> ct::rbd::Dynamics< RBD, NEE >::RigidBodyAcceleration_t

◆ SelectionMatrix_t

template<class RBD, size_t NEE>
typedef SelectionMatrix<NJOINTS, NSTATE / 2, SCALAR> ct::rbd::Dynamics< RBD, NEE >::SelectionMatrix_t

◆ ExtLinkForces_t

template<class RBD, size_t NEE>
typedef RBD::LinkForceMap ct::rbd::Dynamics< RBD, NEE >::ExtLinkForces_t

◆ EE_in_contact_t

template<class RBD, size_t NEE>
typedef RBDDataMap<bool, NEE> ct::rbd::Dynamics< RBD, NEE >::EE_in_contact_t

◆ Kinematics_t

template<class RBD, size_t NEE>
typedef Kinematics<RBD, NEE> ct::rbd::Dynamics< RBD, NEE >::Kinematics_t

Constructor & Destructor Documentation

◆ Dynamics() [1/2]

template<class RBD, size_t NEE>
ct::rbd::Dynamics< RBD, NEE >::Dynamics ( typename Kinematics_t::Ptr_t  kinematics = typename Kinematics_t::Ptr_t(new Kinematics_t()))
inline

The constructor.

Parameters
[in]kinematicsThe kinematics of the RBD

◆ Dynamics() [2/2]

template<class RBD, size_t NEE>
ct::rbd::Dynamics< RBD, NEE >::Dynamics ( const Dynamics< RBD, NEE > &  other)
inline

◆ ~Dynamics()

template<class RBD, size_t NEE>
virtual ct::rbd::Dynamics< RBD, NEE >::~Dynamics ( )
inlinevirtual

Member Function Documentation

◆ FixBaseForwardDynamics() [1/2]

template<class RBD , size_t NEE>
ENABLE_FIX_BASE_IMPL ct::rbd::Dynamics< RBD, NEE >::FixBaseForwardDynamics ( const JointState_t x,
const control_vector_t u,
ExtLinkForces_t force,
JointAcceleration_t qdd 
)

Compute forward dynamics of a fixed-base RBD system under external forces.

Parameters
[in]xThe JointState state
[in]uThe control vector
[in]forceThe external forces vector
[out]qddThe joints acceleration

References ct::rbd::JointAcceleration< NJOINTS, SCALAR >::getAcceleration(), ct::rbd::JointState< NJOINTS, SCALAR >::getPositions(), and ct::rbd::JointState< NJOINTS, SCALAR >::getVelocities().

Referenced by ct::rbd::Dynamics< RBD, NEE >::FixBaseForwardDynamics(), and ct::rbd::Dynamics< RBD, NEE >::~Dynamics().

◆ FixBaseForwardDynamics() [2/2]

template<class RBD, size_t NEE>
ENABLE_FIX_BASE ct::rbd::Dynamics< RBD, NEE >::FixBaseForwardDynamics ( const JointState_t x,
const control_vector_t u,
JointAcceleration_t qdd 
)
inline

◆ FixBaseID() [1/2]

template<class RBD , size_t NEE>
ENABLE_FIX_BASE_IMPL ct::rbd::Dynamics< RBD, NEE >::FixBaseID ( const JointState_t x,
const JointAcceleration_t qdd,
const ExtLinkForces_t force,
control_vector_t u 
)

Computes Inverse dynamics of a fixed-base system under external forces.

Parameters
[in]xthe current state of the robot
[in]qddthe Joints acceleration
[in]forcethe external forces vector
[out]uThe control vector

References ct::rbd::JointAcceleration< NJOINTS, SCALAR >::getAcceleration(), ct::rbd::JointState< NJOINTS, SCALAR >::getPositions(), and ct::rbd::JointState< NJOINTS, SCALAR >::getVelocities().

Referenced by ct::rbd::Dynamics< RBD, NEE >::FixBaseForwardDynamics().

◆ FixBaseID() [2/2]

template<class RBD , size_t NEE>
ENABLE_FIX_BASE_IMPL ct::rbd::Dynamics< RBD, NEE >::FixBaseID ( const JointState_t x,
const JointAcceleration_t qdd,
control_vector_t u 
)

Computes Inverse dynamics of a fixed-base system without external forces.

Parameters
[in]xthe current state of the robot
[in]qddthe Joints acceleration
[out]uThe control vector

References ct::rbd::JointAcceleration< NJOINTS, SCALAR >::getAcceleration(), ct::rbd::JointState< NJOINTS, SCALAR >::getPositions(), and ct::rbd::JointState< NJOINTS, SCALAR >::getVelocities().

◆ FloatingBaseForwardDynamics()

template<class RBD , size_t NEE>
ENABLE_FLOAT_BASE_IMPL ct::rbd::Dynamics< RBD, NEE >::FloatingBaseForwardDynamics ( const RBDState_t x,
const control_vector_t u,
const ExtLinkForces_t link_forces,
RBDAcceleration_t xd 
)

◆ FloatingBaseID()

template<class RBD , size_t NEE>
ENABLE_FLOAT_BASE_IMPL ct::rbd::Dynamics< RBD, NEE >::FloatingBaseID ( const RBDState_t x,
const JointAcceleration_t qdd,
const ExtLinkForces_t force,
control_vector_t u,
RigidBodyAcceleration_t base_a 
)

Computes Inverse dynamics of a floating-base system under external forces.

Parameters
[in]xthe RBDstate
[in]qddthe joints acceleration
[in]forcethe external forces vector
[out]uThe control vector
[out]base_aThe base state derivative

References ct::rbd::RBDState< NJOINTS, SCALAR >::basePose(), ct::rbd::RBDState< NJOINTS, SCALAR >::baseVelocities(), ct::rbd::tpl::RigidBodyPose< SCALAR >::computeGravityB6D(), ct::rbd::tpl::RigidBodyAcceleration< SCALAR >::fromVector6d(), ct::rbd::JointAcceleration< NJOINTS, SCALAR >::getAcceleration(), and ct::rbd::RBDState< NJOINTS, SCALAR >::joints().

Referenced by ct::rbd::Dynamics< RBD, NEE >::FixBaseForwardDynamics().

◆ FloatingBaseFullyActuatedID()

template<class RBD , size_t NEE>
ENABLE_FLOAT_BASE_IMPL ct::rbd::Dynamics< RBD, NEE >::FloatingBaseFullyActuatedID ( const RBDState_t x,
const RigidBodyAcceleration_t base_ac,
const JointAcceleration_t qdd,
const ExtLinkForces_t force,
ForceVector_t base_w,
control_vector_t u 
)

Computes the inverse dynamics of a floating-base fully-actuated system.

Parameters
[in]xThe RBDState
[in]base_aThe base acceleration
[in]qddThe joint acceleration
[in]forceThe external forces vector
[out]base_wThe base wrench
[out]uThe control vector

References ct::rbd::RBDState< NJOINTS, SCALAR >::basePose(), ct::rbd::RBDState< NJOINTS, SCALAR >::baseVelocities(), ct::rbd::tpl::RigidBodyPose< SCALAR >::computeGravityB6D(), ct::rbd::JointAcceleration< NJOINTS, SCALAR >::getAcceleration(), and ct::rbd::RBDState< NJOINTS, SCALAR >::joints().

Referenced by ct::rbd::Dynamics< RBD, NEE >::FixBaseForwardDynamics().

◆ ProjectedForwardDynamics()

template<class RBD, size_t NEE>
ENABLE_FLOAT_BASE ct::rbd::Dynamics< RBD, NEE >::ProjectedForwardDynamics ( const EE_in_contact_t ee_contact,
const RBDState_t x,
const control_vector_t u,
RBDAcceleration_t rbd_a 
)
inline

Computes Projected Forward Dynamics of a floating-base system with contact constraints.

Parameters
[in]ee_contactthe EE contact configuration (EEDataMap<bool>)
[in]xthe RBD state
[in]uthe control vector
[out]rbd_athe RBD acceleration

◆ ProjectedInverseDynamics()

template<class RBD, size_t NEE>
ENABLE_FLOAT_BASE ct::rbd::Dynamics< RBD, NEE >::ProjectedInverseDynamics ( const EE_in_contact_t ee_contact,
const RBDState_t x,
const RBDAcceleration_t rbd_a,
control_vector_t u 
)
inline

◆ ProjectedInverseDynamicsNoGravity()

template<class RBD, size_t NEE>
ENABLE_FLOAT_BASE ct::rbd::Dynamics< RBD, NEE >::ProjectedInverseDynamicsNoGravity ( const EE_in_contact_t ee_contact,
const RBDState_t x,
const RBDAcceleration_t rbd_a,
control_vector_t u 
)
inline

◆ kinematics() [1/2]

template<class RBD, size_t NEE>
Kinematics_t& ct::rbd::Dynamics< RBD, NEE >::kinematics ( )
inline

◆ kinematics() [2/2]

template<class RBD, size_t NEE>
const Kinematics_t& ct::rbd::Dynamics< RBD, NEE >::kinematics ( ) const
inline

◆ kinematicsPtr() [1/2]

template<class RBD, size_t NEE>
Kinematics_t::Ptr_t& ct::rbd::Dynamics< RBD, NEE >::kinematicsPtr ( )
inline

◆ kinematicsPtr() [2/2]

template<class RBD, size_t NEE>
const Kinematics_t::Ptr_t& ct::rbd::Dynamics< RBD, NEE >::kinematicsPtr ( ) const
inline

◆ S() [1/2]

template<class RBD, size_t NEE>
SelectionMatrix_t& ct::rbd::Dynamics< RBD, NEE >::S ( )
inline

◆ S() [2/2]

template<class RBD, size_t NEE>
const SelectionMatrix_t& ct::rbd::Dynamics< RBD, NEE >::S ( ) const
inline

Member Data Documentation

◆ ROBCOGEN

template<class RBD, size_t NEE>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef RBD ct::rbd::Dynamics< RBD, NEE >::ROBCOGEN

◆ FB

template<class RBD, size_t NEE>
const bool ct::rbd::Dynamics< RBD, NEE >::FB = ROBCOGEN::TRAIT::floating_base
static

◆ NJOINTS

template<class RBD, size_t NEE>
const size_t ct::rbd::Dynamics< RBD, NEE >::NJOINTS = RBD::NJOINTS
static

◆ NLINKS

template<class RBD, size_t NEE>
const size_t ct::rbd::Dynamics< RBD, NEE >::NLINKS = RBD::NLINKS
static

◆ NSTATE

template<class RBD, size_t NEE>
const size_t ct::rbd::Dynamics< RBD, NEE >::NSTATE = FB * RBDState<NJOINTS, SCALAR>::NSTATE + (1 - FB) * 2 * NJOINTS
static

◆ N_EE

template<class RBD, size_t NEE>
const size_t ct::rbd::Dynamics< RBD, NEE >::N_EE = NEE
static

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