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. More...
Classes | |
| class | hpp::pinocchio::LiegroupElementConstBase< vector_type > |
| Const reference to a LiegroupElement. More... | |
| class | hpp::pinocchio::LiegroupElementBase< vector_type > |
| Writable element of a Lie group. More... | |
| class | hpp::pinocchio::LiegroupSpace |
| Cartesian product of elementary Lie groups. More... | |
Typedefs | |
| typedef ABoostVariant | hpp::pinocchio::LiegroupType |
| Elementary Lie groups A boost variant with the following classes: More... | |
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) |
| Integration of a velocity vector from a configuration. More... | |
| 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. More... | |
| 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... | |
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 ABoostVariant hpp::pinocchio::LiegroupType |
Elementary Lie groups A boost variant with the following classes:
| hpp::pinocchio::LiegroupSpacePtr_t boost::operator* | ( | const hpp::pinocchio::LiegroupSpaceConstPtr_t & | sp1, |
| const hpp::pinocchio::LiegroupSpaceConstPtr_t & | sp2 | ||
| ) |
Cartesian product between Lie groups.
| LiegroupElement hpp::pinocchio::operator+ | ( | const LiegroupElementConstBase< vector_type > & | e, |
| vectorIn_t | v | ||
| ) |
Integration of a velocity vector from a configuration.
| e | element of the Lie group, |
| v | element of the tangent space of the Lie group. |
By extension of the vector space case, we represent the integration of a constant velocity during unit time by an addition
Referenced by hpp::pinocchio::LiegroupElementBase< vector_type >::operator=().
| vector_t hpp::pinocchio::operator- | ( | const LiegroupElementConstBase< vector_type1 > & | e1, |
| const LiegroupElementConstBase< vector_type2 > & | e2 | ||
| ) |
Difference between two configurations.
| e1,e2 | elements of the Lie group, |
By extension of the vector space case, we represent the integration of a constant velocity during unit time by an addition
Referenced by hpp::pinocchio::LiegroupElementBase< vector_type >::operator=().
|
inline |
Writing in a stream.
References hpp::pinocchio::LiegroupSpace::name().
| hpp::pinocchio::LiegroupSpacePtr_t boost::operator^ | ( | const hpp::pinocchio::LiegroupSpaceConstPtr_t & | sp, |
| hpp::pinocchio::size_type | n | ||
| ) |
Cartesian power by an integer.