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

#include <ProjectedDynamics.h>

Public Types

typedef Eigen::Matrix< Scalar, NDOF, 1 > g_coordinate_vector_t
 
typedef Eigen::Matrix< Scalar, CONTROL_DIM, 1 > control_vector_t
 
typedef Eigen::Matrix< Scalar, NJOINTS, 1 > joint_vector_t
 
typedef Eigen::Matrix< Scalar, NDOF, NDOFinertia_matrix_t
 
typedef Eigen::Matrix< Scalar, 6, 1 > ForceVector_t
 
typedef Eigen::Matrix< Scalar, CONTROL_DIM, NDOFselection_matrix_t
 
typedef RBDDataMap< Eigen::Vector3d, NEE > EE_contact_forces_t
 
typedef RBDDataMap< bool, NEE > EE_in_contact_t
 
typedef RBDState< NJOINTS, ScalarRBDState_t
 
typedef RBDAcceleration< NJOINTS, ScalarRBDAcceleration_t
 
typedef JointState< NJOINTS, ScalarJointState_t
 
typedef JointAcceleration< NJOINTS, ScalarJointAcceleration_t
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > MatrixXs
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXs
 

Public Member Functions

 ProjectedDynamics (const std::shared_ptr< Kinematics< RBD, NEE >> kyn, const EE_in_contact_t ee_inc=EE_in_contact_t(false))
 The Constructor. More...
 
 ~ProjectedDynamics ()
 
void setContactConfiguration (const EE_in_contact_t &eeinc)
 set the End Effector contact configuration More...
 
void getContactConfiguration (EE_in_contact_t &eeinc)
 get the End Effector contact configuration More...
 
void ProjectedForwardDynamics (const RBDState_t &x, const control_vector_t &u, RBDAcceleration_t &qdd)
 Computes the forward dynamics in the constraint consistent subspace of the current contact configuration param[in] x The RBD state param[in] u The control vector param[out] qdd The RBD acceleration. More...
 
void getContactForcesInBase (EE_contact_forces_t &lambda)
 compute contact forces from last dynamics call More...
 
void getContactForcesInBase (const RBDState_t &x, const control_vector_t &u, EE_contact_forces_t &lambda)
 compute contact forces at current state and control input More...
 
void ProjectedInverseDynamics (const RBDState_t &x, const RBDAcceleration_t &qdd, control_vector_t &u)
 Computes the Inverse Dynamics in the constraint consistent subspace of the current contact configuration param[in] x The RBD state param[in] qdd The RBD Acceleration param[out] u The control vector. More...
 
void ProjectedInverseDynamicsNoGravity (const RBDState_t &x, const RBDAcceleration_t &qdd, control_vector_t &u)
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef RBD::SCALAR Scalar
 

Static Public Attributes

static const size_t NJOINTS = RBD::NJOINTS
 
static const size_t CONTROL_DIM = RBD::NJOINTS
 
static const size_t NDOF = RBDState<NJOINTS, Scalar>::NDOF
 
static const size_t MAX_JAC_SIZE = 3 * NEE
 

Member Typedef Documentation

◆ g_coordinate_vector_t

template<class RBD, size_t NEE>
typedef Eigen::Matrix<Scalar, NDOF, 1> ct::rbd::ProjectedDynamics< RBD, NEE >::g_coordinate_vector_t

◆ control_vector_t

template<class RBD, size_t NEE>
typedef Eigen::Matrix<Scalar, CONTROL_DIM, 1> ct::rbd::ProjectedDynamics< RBD, NEE >::control_vector_t

◆ joint_vector_t

template<class RBD, size_t NEE>
typedef Eigen::Matrix<Scalar, NJOINTS, 1> ct::rbd::ProjectedDynamics< RBD, NEE >::joint_vector_t

◆ inertia_matrix_t

template<class RBD, size_t NEE>
typedef Eigen::Matrix<Scalar, NDOF, NDOF> ct::rbd::ProjectedDynamics< RBD, NEE >::inertia_matrix_t

◆ ForceVector_t

template<class RBD, size_t NEE>
typedef Eigen::Matrix<Scalar, 6, 1> ct::rbd::ProjectedDynamics< RBD, NEE >::ForceVector_t

◆ selection_matrix_t

template<class RBD, size_t NEE>
typedef Eigen::Matrix<Scalar, CONTROL_DIM, NDOF> ct::rbd::ProjectedDynamics< RBD, NEE >::selection_matrix_t

◆ EE_contact_forces_t

template<class RBD, size_t NEE>
typedef RBDDataMap<Eigen::Vector3d, NEE> ct::rbd::ProjectedDynamics< RBD, NEE >::EE_contact_forces_t

◆ EE_in_contact_t

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

◆ RBDState_t

template<class RBD, size_t NEE>
typedef RBDState<NJOINTS, Scalar> ct::rbd::ProjectedDynamics< RBD, NEE >::RBDState_t

◆ RBDAcceleration_t

template<class RBD, size_t NEE>
typedef RBDAcceleration<NJOINTS, Scalar> ct::rbd::ProjectedDynamics< RBD, NEE >::RBDAcceleration_t

◆ JointState_t

template<class RBD, size_t NEE>
typedef JointState<NJOINTS, Scalar> ct::rbd::ProjectedDynamics< RBD, NEE >::JointState_t

◆ JointAcceleration_t

template<class RBD, size_t NEE>
typedef JointAcceleration<NJOINTS, Scalar> ct::rbd::ProjectedDynamics< RBD, NEE >::JointAcceleration_t

◆ MatrixXs

template<class RBD, size_t NEE>
typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> ct::rbd::ProjectedDynamics< RBD, NEE >::MatrixXs

◆ VectorXs

template<class RBD, size_t NEE>
typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1> ct::rbd::ProjectedDynamics< RBD, NEE >::VectorXs

Constructor & Destructor Documentation

◆ ProjectedDynamics()

◆ ~ProjectedDynamics()

template<class RBD, size_t NEE>
ct::rbd::ProjectedDynamics< RBD, NEE >::~ProjectedDynamics ( )
inline

Member Function Documentation

◆ setContactConfiguration()

template<class RBD, size_t NEE>
void ct::rbd::ProjectedDynamics< RBD, NEE >::setContactConfiguration ( const EE_in_contact_t eeinc)
inline

set the End Effector contact configuration

Parameters
[in]eeincThe EE Boolean Data Map of the contact configuration

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

◆ getContactConfiguration()

template<class RBD, size_t NEE>
void ct::rbd::ProjectedDynamics< RBD, NEE >::getContactConfiguration ( EE_in_contact_t eeinc)
inline

get the End Effector contact configuration

Parameters
[out]eeincThe EE Boolean Data Map of the contact configuration

◆ ProjectedForwardDynamics()

template<class RBD, size_t NEE>
void ct::rbd::ProjectedDynamics< RBD, NEE >::ProjectedForwardDynamics ( const RBDState_t x,
const control_vector_t u,
RBDAcceleration_t qdd 
)
inline

Computes the forward dynamics in the constraint consistent subspace of the current contact configuration param[in] x The RBD state param[in] u The control vector param[out] qdd The RBD acceleration.

References ct::rbd::RBDAcceleration< NJOINTS, SCALAR >::base(), ct::rbd::tpl::RigidBodyAcceleration< SCALAR >::fromVector6d(), and ct::rbd::RBDAcceleration< NJOINTS, SCALAR >::joints().

◆ getContactForcesInBase() [1/2]

template<class RBD, size_t NEE>
void ct::rbd::ProjectedDynamics< RBD, NEE >::getContactForcesInBase ( EE_contact_forces_t lambda)
inline

compute contact forces from last dynamics call

Referenced by ct::rbd::ProjectedDynamics< RBD, NEE >::getContactForcesInBase().

◆ getContactForcesInBase() [2/2]

template<class RBD, size_t NEE>
void ct::rbd::ProjectedDynamics< RBD, NEE >::getContactForcesInBase ( const RBDState_t x,
const control_vector_t u,
EE_contact_forces_t lambda 
)
inline

compute contact forces at current state and control input

References ct::rbd::ProjectedDynamics< RBD, NEE >::getContactForcesInBase().

◆ ProjectedInverseDynamics()

template<class RBD, size_t NEE>
void ct::rbd::ProjectedDynamics< RBD, NEE >::ProjectedInverseDynamics ( const RBDState_t x,
const RBDAcceleration_t qdd,
control_vector_t u 
)
inline

Computes the Inverse Dynamics in the constraint consistent subspace of the current contact configuration param[in] x The RBD state param[in] qdd The RBD Acceleration param[out] u The control vector.

◆ ProjectedInverseDynamicsNoGravity()

template<class RBD, size_t NEE>
void ct::rbd::ProjectedDynamics< RBD, NEE >::ProjectedInverseDynamicsNoGravity ( const RBDState_t x,
const RBDAcceleration_t qdd,
control_vector_t u 
)
inline

Member Data Documentation

◆ Scalar

template<class RBD, size_t NEE>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef RBD::SCALAR ct::rbd::ProjectedDynamics< RBD, NEE >::Scalar

◆ NJOINTS

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

◆ CONTROL_DIM

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

◆ NDOF

template<class RBD, size_t NEE>
const size_t ct::rbd::ProjectedDynamics< RBD, NEE >::NDOF = RBDState<NJOINTS, Scalar>::NDOF
static

◆ MAX_JAC_SIZE

template<class RBD, size_t NEE>
const size_t ct::rbd::ProjectedDynamics< RBD, NEE >::MAX_JAC_SIZE = 3 * NEE
static

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