- 3.0.2 models module.
iit::ct_InvertedPendulum Namespace Reference

Namespaces

 dyn
 
 tpl
 

Classes

class  JointDataMap
 
class  LinkDataMap
 

Typedefs

using Column1d = tpl::Column1d< double >
 
typedef Column1d JointState
 
typedef tpl::Traits< double > Traits
 

Enumerations

enum  JointIdentifiers { JOINT1 = 0 }
 
enum  LinkIdentifiers { INVERTEDPENDULUMBASE = 0, LINK1 }
 

Functions

template<typename T >
std::ostream & operator<< (std::ostream &out, const JointDataMap< T > &map)
 
template<typename T >
std::ostream & operator<< (std::ostream &out, const LinkDataMap< T > &map)
 
Center of mass calculation

Computes the Center Of Mass (COM) position of the whole robot, in base coordinates.

Common parameters are the inertia properties of the robot and the set of homogeneous coordinate transforms. If a joint status variable is also passed, then the transforms are updated accordingly; otherwise, they are not modified before being used.

iit::rbd::Vector3d getWholeBodyCOM (const dyn::InertiaProperties &inertia, const HomogeneousTransforms &transforms)
 
iit::rbd::Vector3d getWholeBodyCOM (const dyn::InertiaProperties &inertia, const JointState &q, HomogeneousTransforms &transforms)
 

Typedef Documentation

◆ Column1d

◆ JointState

◆ Traits

Enumeration Type Documentation

◆ JointIdentifiers

◆ LinkIdentifiers

Enumerator
INVERTEDPENDULUMBASE 
LINK1 

Function Documentation

◆ operator<<() [1/2]

template<typename T >
std::ostream& iit::ct_InvertedPendulum::operator<< ( std::ostream &  out,
const JointDataMap< T > &  map 
)
inline

References JOINT1.

◆ operator<<() [2/2]

template<typename T >
std::ostream& iit::ct_InvertedPendulum::operator<< ( std::ostream &  out,
const LinkDataMap< T > &  map 
)
inline

References INVERTEDPENDULUMBASE, and LINK1.

◆ getWholeBodyCOM() [1/2]

iit::rbd::Vector3d iit::ct_InvertedPendulum::getWholeBodyCOM ( const dyn::InertiaProperties inertia,
const HomogeneousTransforms &  transforms 
)
Parameters
inertiathe inertia properties of the links of the robot
transformsthe homogeneous coordinate transforms of the robot
Returns
the position of the Center Of Mass of the whole robot, expressed in base coordinates

◆ getWholeBodyCOM() [2/2]

iit::rbd::Vector3d iit::ct_InvertedPendulum::getWholeBodyCOM ( const dyn::InertiaProperties inertia,
const JointState q,
HomogeneousTransforms &  transforms 
)
Parameters
inertiathe inertia properties of the links of the robot
qthe joint status vector describing the configuration of the robot
transformsthe homogeneous coordinate transforms of the robot
Returns
the position of the Center Of Mass of the whole robot, expressed in base coordinates