29 #ifndef HPP_PINOCCHIO_LIEGROUP_SPACE_HH
30 #define HPP_PINOCCHIO_LIEGROUP_SPACE_HH
32 #include <boost/variant.hpp>
35 #include <hpp/util/serialization-fwd.hh>
36 #include <pinocchio/fwd.hpp>
37 #include <pinocchio/multibody/liegroup/special-euclidean.hpp>
38 #include <pinocchio/multibody/liegroup/special-orthogonal.hpp>
39 #include <pinocchio/multibody/liegroup/vector-space.hpp>
48 #ifdef HPP_PINOCCHIO_PARSED_BY_DOXYGEN
61 typedef boost::variant<liegroup::VectorSpaceOperation<Eigen::Dynamic, false>,
103 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
169 return liegroupTypes_;
209 template <DerivativeProduct s
ide>
235 template <DerivativeProduct s
ide>
240 template <
bool ApplyOnTheLeft>
253 template <DerivativeProduct s
ide>
265 template <DerivativeProduct s
ide>
303 void init(
const LiegroupSpaceWkPtr_t weak);
307 void computeNeutral();
308 typedef std::vector<LiegroupType> LiegroupTypes;
309 LiegroupTypes liegroupTypes_;
315 LiegroupSpaceWkPtr_t weak_;
Definition: liegroup-element.hh:117
Definition: liegroup-element.hh:45
Definition: liegroup-space.hh:101
LiegroupElementRef elementRef(vectorOut_t q) const
Create a LiegroupElementRef from a configuration.
LiegroupElement element(vectorIn_t q) const
Create a LiegroupElement from a configuration.
void dDifference_dq0(vectorIn_t q0, vectorIn_t q1, matrixOut_t J0) const
static LiegroupSpacePtr_t R2()
Return as a Lie group.
LiegroupElement exp(vectorIn_t v) const
Return exponential of a tangent vector.
void dIntegrate_dq(LiegroupElementConstRef q, vectorIn_t v, matrixOut_t J) const
bool isVectorSpace() const
LiegroupSpace(const LiegroupType &type)
size_type nq(const std::size_t &rank) const
Dimension of elementary Liegroup at given rank.
static LiegroupSpacePtr_t create(const LiegroupType &type)
Create instance with one Elementary Lie group.
Definition: liegroup-space.hh:151
bool operator==(const LiegroupSpace &other) const
size_type nq() const
Dimension of the vector representation.
Definition: liegroup-space.hh:159
void interpolate(vectorIn_t q0, vectorIn_t q1, value_type u, vectorOut_t result) const
static LiegroupSpacePtr_t R2xSO2()
Return .
size_type nv(const std::size_t &rank) const
Dimension of elementary Liegroup tangent space at given rank.
LiegroupElement neutral() const
Return the neutral element as a vector.
static LiegroupSpacePtr_t empty()
Return empty Lie group.
static LiegroupSpacePtr_t createCopy(const LiegroupSpaceConstPtr_t &other)
Create copy.
Definition: liegroup-space.hh:143
static LiegroupSpacePtr_t R3()
Return as a Lie group.
std::string name() const
Return name of Lie group.
static LiegroupSpacePtr_t Rn(const size_type &n)
static LiegroupSpacePtr_t SE2()
Return .
static LiegroupSpacePtr_t create(const size_type &size)
Create instance of vector space of given size.
Definition: liegroup-space.hh:135
void Jdifference(vectorIn_t q0, vectorIn_t q1, matrixOut_t J0, matrixOut_t J1) const
void dIntegrate_dv(LiegroupElementConstRef q, vectorIn_t v, matrixOut_t Jv) const
LiegroupSpacePtr_t operator*=(const LiegroupSpaceConstPtr_t &other)
static LiegroupSpacePtr_t R1(bool rotation=false)
static LiegroupSpacePtr_t SE3()
Return .
static LiegroupSpacePtr_t SO2()
Return .
void dDifference_dq1(vectorIn_t q0, vectorIn_t q1, matrixOut_t J1) const
static LiegroupSpacePtr_t R3xSO3()
Return .
const std::vector< LiegroupType > & liegroupTypes() const
Get reference to vector of elementary types.
Definition: liegroup-space.hh:168
size_type nv() const
Dimension of the Lie group tangent space.
Definition: liegroup-space.hh:161
LiegroupElementConstRef elementConstRef(vectorIn_t q) const
Create a LiegroupElementRef from a configuration.
static LiegroupSpacePtr_t SO3()
Return .
LiegroupSpace(const size_type &size)
Constructor of vector space of given size.
bool operator!=(const LiegroupSpace &other) const
LiegroupSpacePtr_t vectorSpacesMerged() const
LiegroupSpace(const LiegroupSpace &other)
hpp::pinocchio::LiegroupSpacePtr_t operator^(const hpp::pinocchio::LiegroupSpaceConstPtr_t &sp, hpp::pinocchio::size_type n)
Cartesian power by an integer.
hpp::pinocchio::LiegroupSpacePtr_t operator*(const hpp::pinocchio::LiegroupSpaceConstPtr_t &sp1, const hpp::pinocchio::LiegroupSpaceConstPtr_t &sp2)
Cartesian product between Lie groups.
DerivativeProduct
Definition: liegroup-space.hh:80
ABoostVariant LiegroupType
Definition: liegroup-space.hh:59
@ InputTimesDerivative
Definition: liegroup-space.hh:80
@ DerivativeTimesInput
Definition: liegroup-space.hh:80
Eigen::Ref< matrix_t > matrixOut_t
Definition: fwd.hh:96
Eigen::Matrix< value_type, Eigen::Dynamic, 1 > vector_t
Definition: fwd.hh:88
Eigen::Ref< vector_t > vectorOut_t
Definition: fwd.hh:94
std::ostream & operator<<(std::ostream &os, const hpp::pinocchio::Device &device)
Definition: device.hh:366
shared_ptr< const LiegroupSpace > LiegroupSpaceConstPtr_t
Definition: fwd.hh:151
shared_ptr< LiegroupSpace > LiegroupSpacePtr_t
Definition: fwd.hh:150
matrix_t::Index size_type
Definition: fwd.hh:97
double value_type
Definition: fwd.hh:51
Eigen::Ref< const vector_t > vectorIn_t
Definition: fwd.hh:93
Utility functions.
Definition: body.hh:39
Definition: collision-object.hh:40
Definition: liegroup-space.hh:329
Definition: cartesian-product.hh:40
Definition: special-euclidean.hh:39
Definition: special-orthogonal.hh:39
Definition: vector-space.hh:60