|
typedef RBDTrait::S | SCALAR |
|
typedef RBDTrait | TRAIT |
|
typedef U | UTILS |
|
typedef RobCoGenContainer< RBDTrait, LinkDataMapT, UTILS > | specialized_t |
|
typedef std::shared_ptr< specialized_t > | Ptr_t |
|
typedef RBDTrait::HomogeneousTransforms | HomogeneousTransforms |
|
typedef RBDTrait::MotionTransforms | MotionTransforms |
|
typedef RBDTrait::ForceTransforms | ForceTransforms |
|
typedef RBDTrait::Jacobians | Jacobians |
|
typedef RBDTrait::InertiaProperties | InertiaProperties |
|
typedef RBDTrait::JSIM | JSIM |
|
typedef RBDTrait::FwdDynEngine | ForwardDynamics |
|
typedef RBDTrait::InvDynEngine | InverseDynamics |
|
typedef RBDTrait::LinkID | LinkIdentifiers |
|
typedef LinkDataMapT< Eigen::Matrix< SCALAR, 6, 1 > > | LinkForceMap |
|
typedef Eigen::Matrix< SCALAR, 4, 4 > | HomogeneousTransform |
|
typedef Eigen::Matrix< SCALAR, 6, 6 > | ForceTransform |
|
typedef Eigen::Matrix< SCALAR, 6, NJOINTS > | Jacobian |
|
typedef Eigen::Matrix< SCALAR, 3, 3 > | Matrix3Tpl |
|
typedef kindr::Position< SCALAR, 3 > | Position3Tpl |
|
typedef Eigen::Matrix< SCALAR, 3, 1 > | Vector3Tpl |
|
using | RigidBodyPoseTpl = tpl::RigidBodyPose< SCALAR > |
|
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | RobCoGenContainer () |
|
HomogeneousTransforms & | homogeneousTransforms () |
|
const HomogeneousTransforms & | homogeneousTransforms () const |
|
MotionTransforms & | motionTransforms () |
|
const MotionTransforms & | motionTransforms () const |
|
ForceTransforms & | forceTransforms () |
|
const ForceTransforms & | forceTransforms () const |
|
Jacobians & | jacobians () |
|
const Jacobians & | jacobians () const |
|
InertiaProperties & | inertiaProperties () |
|
const InertiaProperties & | inertiaProperties () const |
|
JSIM & | jSim () |
|
const JSIM & | jSim () const |
|
ForwardDynamics & | forwardDynamics () |
|
const ForwardDynamics & | forwardDynamics () const |
|
InverseDynamics & | inverseDynamics () |
|
const InverseDynamics & | inverseDynamics () const |
|
HomogeneousTransform | getHomogeneousTransformBaseLinkById (size_t linkId, const typename JointState< NJOINTS, SCALAR >::Position &jointPosition) |
| Get a homogeneous transformation from link to base provided a link id. More...
|
|
ForceTransform | getForceTransformLinkBaseById (size_t linkId, const typename JointState< NJOINTS, SCALAR >::Position &jointPosition) |
| Get a force transformation from link to base provided a link id. More...
|
|
HomogeneousTransform | getHomogeneousTransformBaseEEById (size_t eeId, const typename JointState< NJOINTS, SCALAR >::Position &jointPosition) |
| Get a homogeneous transformation from base to an endeffector provided an endeffector id. More...
|
|
Jacobian | getJacobianBaseEEbyId (size_t eeId, const typename JointState< NJOINTS, SCALAR >::Position &jointPosition) |
| Get the end-effector Jacobian expressed in the base frame. More...
|
|
Position3Tpl | getEEPositionInBase (size_t eeId, const typename JointState< NJOINTS, SCALAR >::Position &jointPosition) |
| Get a force transformation from base to an endeffector provided an endeffector id. More...
|
|
RigidBodyPoseTpl | getEEPoseInBase (size_t eeId, const typename JointState< NJOINTS, SCALAR >::Position &jointPosition, typename RigidBodyPoseTpl::STORAGE_TYPE storage=RigidBodyPoseTpl::EULER) |
| Get the endeffector pose expressed in the base frame. More...
|
|
Matrix3Tpl | getEERotInBase (size_t eeId, const typename JointState< NJOINTS, SCALAR >::Position &jointPosition) |
|
template<class RBDTrait, template< typename > class LinkDataMapT, class U>
class ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >
Container class containing all robcogen classes.
template<class RBDTrait, template< typename > class LinkDataMapT, class U>
Get a homogeneous transformation from link to base provided a link id.
The homogeneous transform takes a quantity expressed in the link frame and transforms it into the base frame, i.e. where is the transform you obtain from this function.
- Parameters
-
linkId | link id |
position | joint positions (angles) |
- Returns
- Homogeneous transformation from link to base
References ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::homogeneousTransforms().
template<class RBDTrait, template< typename > class LinkDataMapT, class U>
Get a force transformation from link to base provided a link id.
The force transform takes a torque-force vector expressed in the base frame and transforms it into the link frame, i.e. where is the transform you obtain from this function.
- Parameters
-
linkId | link id |
position | joint positions (angles) |
- Returns
- Force transformation from link to base
References ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::forceTransforms().
template<class RBDTrait, template< typename > class LinkDataMapT, class U>
Get a homogeneous transformation from base to an endeffector provided an endeffector id.
The homogeneous transform converts a quantity expressed in the base and converts it to the end-effector frame, i.e. The endeffector frame corresponds to the convention used when creating the RobCoGen code.
- Parameters
-
eeId | End-effector ID |
jointPosition | Joint angles/positions |
- Returns
- Homogeneous transformation from base to endeffector
References ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::homogeneousTransforms().
Referenced by ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::getEEPoseInBase(), ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::getEEPositionInBase(), and ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::getEERotInBase().
template<class RBDTrait, template< typename > class LinkDataMapT, class U>
Get a force transformation from base to an endeffector provided an endeffector id.
The force transform converts a torque-force vector expressed in the base and converts it to the end-effector frame, i.e. The endeffector frame corresponds to the convention used when creating the RobCoGen code.
- Parameters
-
eeId | End-effector ID |
jointPosition | Joint angles/positions |
- Returns
- Homogeneous transformation from base to endeffector
Get the endeffector position expressed in the base frame
- Parameters
-
eeId | endeffector ID |
jointPosition | current joint position |
- Returns
- position of the endeffector expressed in the base frame
References ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::getHomogeneousTransformBaseEEById().