#include <ProjectedDynamics.h>
|
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, NDOF > | inertia_matrix_t |
|
typedef Eigen::Matrix< Scalar, 6, 1 > | ForceVector_t |
|
typedef Eigen::Matrix< Scalar, CONTROL_DIM, NDOF > | selection_matrix_t |
|
typedef RBDDataMap< Eigen::Vector3d, NEE > | EE_contact_forces_t |
|
typedef RBDDataMap< bool, NEE > | EE_in_contact_t |
|
typedef RBDState< NJOINTS, Scalar > | RBDState_t |
|
typedef RBDAcceleration< NJOINTS, Scalar > | RBDAcceleration_t |
|
typedef JointState< NJOINTS, Scalar > | JointState_t |
|
typedef JointAcceleration< NJOINTS, Scalar > | JointAcceleration_t |
|
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > | MatrixXs |
|
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > | VectorXs |
|
|
| 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) |
|
◆ g_coordinate_vector_t
template<class RBD, size_t NEE>
◆ control_vector_t
template<class RBD, size_t NEE>
◆ joint_vector_t
template<class RBD, size_t NEE>
◆ inertia_matrix_t
template<class RBD, size_t NEE>
◆ ForceVector_t
template<class RBD, size_t NEE>
◆ selection_matrix_t
template<class RBD, size_t NEE>
◆ EE_contact_forces_t
template<class RBD, size_t NEE>
◆ EE_in_contact_t
template<class RBD, size_t NEE>
◆ RBDState_t
template<class RBD, size_t NEE>
◆ RBDAcceleration_t
template<class RBD, size_t NEE>
◆ JointState_t
template<class RBD, size_t NEE>
◆ JointAcceleration_t
template<class RBD, size_t NEE>
◆ MatrixXs
template<class RBD, size_t NEE>
◆ VectorXs
template<class RBD, size_t NEE>
◆ ProjectedDynamics()
template<class RBD , size_t NEE>
The Constructor.
- Parameters
-
[in] | kyn | Robot Kinematics |
[in] | ee_inc | The EE Boolean Data Map with the end effectors in contact |
References ct::rbd::RBDState< NJOINTS, SCALAR >::baseLocalAngularVelocity(), ct::rbd::RBDState< NJOINTS, SCALAR >::basePose(), ct::rbd::RBDState< NJOINTS, SCALAR >::baseVelocities(), ct::rbd::tpl::RigidBodyPose< SCALAR >::computeGravityB6D(), ct::rbd::JointState< NJOINTS, SCALAR >::getPositions(), ct::rbd::tpl::RigidBodyVelocities< SCALAR >::getVector(), ct::rbd::JointState< NJOINTS, SCALAR >::getVelocities(), ct::rbd::RBDState< NJOINTS, SCALAR >::joints(), ct::rbd::ProjectedDynamics< RBD, NEE >::setContactConfiguration(), ct::rbd::RBDAcceleration< NJOINTS, SCALAR >::toCoordinateAcceleration(), ct::rbd::RBDState< NJOINTS, SCALAR >::toCoordinateVelocity(), u, and x.
◆ ~ProjectedDynamics()
template<class RBD, size_t NEE>
◆ setContactConfiguration()
template<class RBD, size_t NEE>
◆ getContactConfiguration()
template<class RBD, size_t NEE>
get the End Effector contact configuration
- Parameters
-
[out] | eeinc | The EE Boolean Data Map of the contact configuration |
◆ ProjectedForwardDynamics()
template<class RBD, size_t NEE>
◆ getContactForcesInBase() [1/2]
template<class RBD, size_t NEE>
◆ getContactForcesInBase() [2/2]
template<class RBD, size_t NEE>
◆ ProjectedInverseDynamics()
template<class RBD, size_t NEE>
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>
◆ Scalar
template<class RBD, size_t NEE>
◆ NJOINTS
template<class RBD, size_t NEE>
◆ CONTROL_DIM
template<class RBD, size_t NEE>
◆ NDOF
template<class RBD, size_t NEE>
◆ MAX_JAC_SIZE
template<class RBD, size_t NEE>
The documentation for this class was generated from the following file: