- 3.0.2 rigid body dynamics module.
ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U > Class Template Reference

Container class containing all robcogen classes. More...

#include <RobCoGenContainer.h>

Public Types

typedef RBDTrait::S SCALAR
 
typedef RBDTrait TRAIT
 
typedef U UTILS
 
typedef RobCoGenContainer< RBDTrait, LinkDataMapT, UTILSspecialized_t
 
typedef std::shared_ptr< specialized_tPtr_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, NJOINTSJacobian
 
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 >
 

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW RobCoGenContainer ()
 
HomogeneousTransformshomogeneousTransforms ()
 
const HomogeneousTransformshomogeneousTransforms () const
 
MotionTransformsmotionTransforms ()
 
const MotionTransformsmotionTransforms () const
 
ForceTransformsforceTransforms ()
 
const ForceTransformsforceTransforms () const
 
Jacobiansjacobians ()
 
const Jacobiansjacobians () const
 
InertiaPropertiesinertiaProperties ()
 
const InertiaPropertiesinertiaProperties () const
 
JSIMjSim ()
 
const JSIMjSim () const
 
ForwardDynamicsforwardDynamics ()
 
const ForwardDynamicsforwardDynamics () const
 
InverseDynamicsinverseDynamics ()
 
const InverseDynamicsinverseDynamics () 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)
 

Static Public Attributes

static const size_t NJOINTS = RBDTrait::joints_count
 
static const size_t NLINKS = RBDTrait::links_count
 

Detailed Description

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
class ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >

Container class containing all robcogen classes.

Member Typedef Documentation

◆ SCALAR

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef RBDTrait::S ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::SCALAR

◆ TRAIT

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef RBDTrait ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::TRAIT

◆ UTILS

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef U ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::UTILS

◆ specialized_t

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef RobCoGenContainer<RBDTrait, LinkDataMapT, UTILS> ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::specialized_t

◆ Ptr_t

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef std::shared_ptr<specialized_t> ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::Ptr_t

◆ HomogeneousTransforms

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef RBDTrait::HomogeneousTransforms ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::HomogeneousTransforms

◆ MotionTransforms

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef RBDTrait::MotionTransforms ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::MotionTransforms

◆ ForceTransforms

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef RBDTrait::ForceTransforms ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::ForceTransforms

◆ Jacobians

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef RBDTrait::Jacobians ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::Jacobians

◆ InertiaProperties

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef RBDTrait::InertiaProperties ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::InertiaProperties

◆ JSIM

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef RBDTrait::JSIM ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::JSIM

◆ ForwardDynamics

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef RBDTrait::FwdDynEngine ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::ForwardDynamics

◆ InverseDynamics

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef RBDTrait::InvDynEngine ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::InverseDynamics

◆ LinkIdentifiers

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef RBDTrait::LinkID ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::LinkIdentifiers

◆ LinkForceMap

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef LinkDataMapT<Eigen::Matrix<SCALAR, 6, 1> > ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::LinkForceMap

◆ HomogeneousTransform

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef Eigen::Matrix<SCALAR, 4, 4> ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::HomogeneousTransform

◆ ForceTransform

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef Eigen::Matrix<SCALAR, 6, 6> ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::ForceTransform

◆ Jacobian

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef Eigen::Matrix<SCALAR, 6, NJOINTS> ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::Jacobian

◆ Matrix3Tpl

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef Eigen::Matrix<SCALAR, 3, 3> ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::Matrix3Tpl

◆ Position3Tpl

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef kindr::Position<SCALAR, 3> ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::Position3Tpl

◆ Vector3Tpl

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
typedef Eigen::Matrix<SCALAR, 3, 1> ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::Vector3Tpl

◆ RigidBodyPoseTpl

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
using ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::RigidBodyPoseTpl = tpl::RigidBodyPose<SCALAR>

Constructor & Destructor Documentation

◆ RobCoGenContainer()

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::RobCoGenContainer ( )
inline

Member Function Documentation

◆ homogeneousTransforms() [1/2]

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
HomogeneousTransforms& ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::homogeneousTransforms ( )
inline

◆ homogeneousTransforms() [2/2]

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
const HomogeneousTransforms& ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::homogeneousTransforms ( ) const
inline

◆ motionTransforms() [1/2]

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
MotionTransforms& ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::motionTransforms ( )
inline

◆ motionTransforms() [2/2]

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
const MotionTransforms& ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::motionTransforms ( ) const
inline

◆ forceTransforms() [1/2]

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
ForceTransforms& ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::forceTransforms ( )
inline

◆ forceTransforms() [2/2]

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
const ForceTransforms& ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::forceTransforms ( ) const
inline

◆ jacobians() [1/2]

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
Jacobians& ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::jacobians ( )
inline

◆ jacobians() [2/2]

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
const Jacobians& ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::jacobians ( ) const
inline

◆ inertiaProperties() [1/2]

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
InertiaProperties& ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::inertiaProperties ( )
inline

◆ inertiaProperties() [2/2]

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
const InertiaProperties& ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::inertiaProperties ( ) const
inline

◆ jSim() [1/2]

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
JSIM& ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::jSim ( )
inline

◆ jSim() [2/2]

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
const JSIM& ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::jSim ( ) const
inline

◆ forwardDynamics() [1/2]

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
ForwardDynamics& ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::forwardDynamics ( )
inline

◆ forwardDynamics() [2/2]

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
const ForwardDynamics& ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::forwardDynamics ( ) const
inline

◆ inverseDynamics() [1/2]

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
InverseDynamics& ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::inverseDynamics ( )
inline

◆ inverseDynamics() [2/2]

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
const InverseDynamics& ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::inverseDynamics ( ) const
inline

◆ getHomogeneousTransformBaseLinkById()

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
HomogeneousTransform ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::getHomogeneousTransformBaseLinkById ( size_t  linkId,
const typename JointState< NJOINTS, SCALAR >::Position &  jointPosition 
)
inline

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. $ {_Bx} = T_{BL} {_Lx} $ where $ T_{BL} $ is the transform you obtain from this function.

Parameters
linkIdlink id
positionjoint positions (angles)
Returns
Homogeneous transformation from link to base $ T_{BL} $

References ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::homogeneousTransforms().

◆ getForceTransformLinkBaseById()

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
ForceTransform ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::getForceTransformLinkBaseById ( size_t  linkId,
const typename JointState< NJOINTS, SCALAR >::Position &  jointPosition 
)
inline

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. $ {_Lx} = T_{LB} {_Bx} $ where $ T_{LB} $ is the transform you obtain from this function.

Parameters
linkIdlink id
positionjoint positions (angles)
Returns
Force transformation from link to base $ T_{LB} $

References ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::forceTransforms().

◆ getHomogeneousTransformBaseEEById()

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
HomogeneousTransform ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::getHomogeneousTransformBaseEEById ( size_t  eeId,
const typename JointState< NJOINTS, SCALAR >::Position &  jointPosition 
)
inline

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. $ {_EEx} = T_{EE-B} {_Bx} $ The endeffector frame corresponds to the convention used when creating the RobCoGen code.

Parameters
eeIdEnd-effector ID
jointPositionJoint angles/positions
Returns
Homogeneous transformation from base to endeffector $ T_{EE-B} $

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().

◆ getJacobianBaseEEbyId()

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
Jacobian ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::getJacobianBaseEEbyId ( size_t  eeId,
const typename JointState< NJOINTS, SCALAR >::Position &  jointPosition 
)
inline

Get the end-effector Jacobian expressed in the base frame.

Parameters
eeIdendeffector ID
jointPositioncurrent joint position
Returns
Jacobian of the endeffector expressed in the base frame

References ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::jacobians().

◆ getEEPositionInBase()

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
Position3Tpl ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::getEEPositionInBase ( size_t  eeId,
const typename JointState< NJOINTS, SCALAR >::Position &  jointPosition 
)
inline

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. $ {_EEx} = T_{EE-B} {_Bx} $ The endeffector frame corresponds to the convention used when creating the RobCoGen code.

Parameters
eeIdEnd-effector ID
jointPositionJoint angles/positions
Returns
Homogeneous transformation from base to endeffector $ T_{EE-B} $

Get the endeffector position expressed in the base frame

Parameters
eeIdendeffector ID
jointPositioncurrent joint position
Returns
position of the endeffector expressed in the base frame

References ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::getHomogeneousTransformBaseEEById().

◆ getEEPoseInBase()

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
RigidBodyPoseTpl ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::getEEPoseInBase ( size_t  eeId,
const typename JointState< NJOINTS, SCALAR >::Position &  jointPosition,
typename RigidBodyPoseTpl::STORAGE_TYPE  storage = RigidBodyPoseTpl::EULER 
)
inline

Get the endeffector pose expressed in the base frame.

Parameters
eeIdendeffector ID
jointPositioncurrent joint position
storagethe type of storage inteded for the pose
Returns
position of the endeffector expressed in the base frame

References ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::getHomogeneousTransformBaseEEById().

◆ getEERotInBase()

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
Matrix3Tpl ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::getEERotInBase ( size_t  eeId,
const typename JointState< NJOINTS, SCALAR >::Position &  jointPosition 
)
inline

compute the forward kinematics and return a rotation matrix specifying the ee-rotation w.r.t. the base frame

References ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::getHomogeneousTransformBaseEEById().

Member Data Documentation

◆ NJOINTS

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
const size_t ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::NJOINTS = RBDTrait::joints_count
static

◆ NLINKS

template<class RBDTrait, template< typename > class LinkDataMapT, class U>
const size_t ct::rbd::RobCoGenContainer< RBDTrait, LinkDataMapT, U >::NLINKS = RBDTrait::links_count
static

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