hpp-pinocchio  4.9.1
Wrapping of the kinematic/dynamic chain Pinocchio for HPP.
Lie group

Classes

class  hpp::pinocchio::LiegroupElementConstBase< vector_type >
 
class  hpp::pinocchio::LiegroupElementBase< vector_type >
 
class  hpp::pinocchio::LiegroupSpace
 

Typedefs

typedef ABoostVariant hpp::pinocchio::LiegroupType
 

Enumerations

enum  hpp::pinocchio::DerivativeProduct { hpp::pinocchio::DerivativeTimesInput, hpp::pinocchio::InputTimesDerivative }
 

Functions

template<typename vector_type >
LiegroupElement hpp::pinocchio::operator+ (const LiegroupElementConstBase< vector_type > &e, vectorIn_t v)
 
template<typename vector_type1 , typename vector_type2 >
vector_t hpp::pinocchio::operator- (const LiegroupElementConstBase< vector_type1 > &e1, const LiegroupElementConstBase< vector_type2 > &e2)
 
std::ostream & hpp::pinocchio::operator<< (std::ostream &os, const LiegroupSpace &space)
 Writing in a stream. More...
 
hpp::pinocchio::LiegroupSpacePtr_t boost::operator* (const hpp::pinocchio::LiegroupSpaceConstPtr_t &sp1, const hpp::pinocchio::LiegroupSpaceConstPtr_t &sp2)
 Cartesian product between Lie groups. More...
 
hpp::pinocchio::LiegroupSpacePtr_t boost::operator^ (const hpp::pinocchio::LiegroupSpaceConstPtr_t &sp, hpp::pinocchio::size_type n)
 Cartesian power by an integer. More...
 

Detailed Description

Configurations of robots, as well as some values like the position of a robot joint with respect to a fixed frame belong to differential manifolds that have the structure of Lie groups. These manifolds are the cartesian products of the following elementary Lie groups

Typedef Documentation

◆ LiegroupType

typedef ABoostVariant hpp::pinocchio::LiegroupType

Elementary Lie groups A boost variant with the following classes:

Enumeration Type Documentation

◆ DerivativeProduct

Enumerator
DerivativeTimesInput 
InputTimesDerivative 

Function Documentation

◆ operator*()

Cartesian product between Lie groups.

◆ operator+()

template<typename vector_type >
LiegroupElement hpp::pinocchio::operator+ ( const LiegroupElementConstBase< vector_type > &  e,
vectorIn_t  v 
)

Integration of a velocity vector from a configuration

Parameters
eelement of the Lie group,
velement of the tangent space of the Lie group.
Returns
the element of the Lie group resulting from the integration

By extension of the vector space case, we represent the integration of a constant velocity during unit time by an addition

◆ operator-()

template<typename vector_type1 , typename vector_type2 >
vector_t hpp::pinocchio::operator- ( const LiegroupElementConstBase< vector_type1 > &  e1,
const LiegroupElementConstBase< vector_type2 > &  e2 
)

Difference between two configurations

Parameters
e1,e2elements of the Lie group,
Returns
the velocity that integrated from e2 yiels e1

By extension of the vector space case, we represent the integration of a constant velocity during unit time by an addition

◆ operator<<()

std::ostream& hpp::pinocchio::operator<< ( std::ostream &  os,
const LiegroupSpace space 
)
inline

Writing in a stream.

◆ operator^()

Cartesian power by an integer.