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::LiegroupElementBase< vector_type > |
class | hpp::pinocchio::LiegroupNonconstElementBase< vector_type > |
class | hpp::pinocchio::LiegroupSpace |
Cartesian product of elementary Lie groups. More... | |
Functions | |
template<typename vector_type > | |
LiegroupElement | hpp::pinocchio::operator+ (const LiegroupElementBase< 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 LiegroupElementBase< vector_type1 > &e1, const LiegroupElementBase< 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... | |
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
Element of a Lie group.
See class LiegroupSpace.
typedef boost::variant<liegroup::VectorSpaceOperation <Eigen::Dynamic, false>, liegroup::VectorSpaceOperation <1, true>, liegroup::VectorSpaceOperation <1, false>, liegroup::VectorSpaceOperation <2, false>, liegroup::VectorSpaceOperation <3, false>, liegroup::VectorSpaceOperation <3, true>, liegroup::CartesianProductOperation< liegroup::VectorSpaceOperation<3, false>, liegroup::SpecialOrthogonalOperation<3> >, liegroup::CartesianProductOperation< liegroup::VectorSpaceOperation<2, false>, liegroup::SpecialOrthogonalOperation<2> >, liegroup::SpecialOrthogonalOperation <2>, liegroup::SpecialOrthogonalOperation <3>, se3::SpecialEuclideanOperation <2>, se3::SpecialEuclideanOperation <3> > hpp::pinocchio::LiegroupType |
Elementary Lie groups.
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 LiegroupElementBase< 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
vector_t hpp::pinocchio::operator- | ( | const LiegroupElementBase< vector_type1 > & | e1, |
const LiegroupElementBase< 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
|
inline |
Writing in a stream.
References hpp::pinocchio::LiegroupSpace::name().