All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Public Member Functions | Static Public Member Functions | Protected Member Functions | List of all members
hpp::pinocchio::LiegroupSpace Class Reference

Cartesian product of elementary Lie groups. More...

#include <hpp/pinocchio/liegroup-space.hh>

Public Member Functions

size_type nq () const
 Dimension of the vector representation. More...
 
size_type nv () const
 Dimension of the Lie group tangent space. More...
 
size_type nq (const std::size_t &rank) const
 Dimension of elementary Liegroup at given rank. More...
 
size_type nv (const std::size_t &rank) const
 Dimension of elementary Liegroup tangent space at given rank. More...
 
const std::vector< LiegroupType > & liegroupTypes () const
 Get reference to vector of elementary types. More...
 
LiegroupElement neutral () const
 Return the neutral element as a vector. More...
 
LiegroupElement exp (vectorIn_t v) const
 Return exponential of a tangent vector. More...
 
void Jintegrate (vectorIn_t v, matrixOut_t J) const
 Compute the Jacobian of the integration operation. More...
 
template<bool ApplyOnTheLeft>
void Jdifference (vectorIn_t q0, vectorIn_t q1, matrixOut_t J0, matrixOut_t J1) const
 Compute the Jacobian of the difference operation. More...
 
std::string name () const
 Return name of Lie group. More...
 
void mergeVectorSpaces ()
 
bool operator== (const LiegroupSpace &other) const
 
bool operator!= (const LiegroupSpace &other) const
 
LiegroupSpacePtr_t operator*= (const LiegroupSpaceConstPtr_t &other)
 

Static Public Member Functions

static LiegroupSpacePtr_t create (const size_type &size)
 Create instance of vector space of given size. More...
 
static LiegroupSpacePtr_t createCopy (const LiegroupSpaceConstPtr_t &other)
 Create copy. More...
 
static LiegroupSpacePtr_t create (const LiegroupType &type)
 Create instance with one Elementary Lie group. More...
 
Elementary Lie groups
static LiegroupSpacePtr_t Rn (const size_type &n)
 Return $\mathbf{R}^n$ as a Lie group. More...
 
static LiegroupSpacePtr_t R1 ()
 Return $\mathbf{R}$ as a Lie group. More...
 
static LiegroupSpacePtr_t R2 ()
 Return $\mathbf{R}^2$ as a Lie group. More...
 
static LiegroupSpacePtr_t R3 ()
 Return $\mathbf{R}^3$ as a Lie group. More...
 
static LiegroupSpacePtr_t SE2 ()
 Return $SE(2)$. More...
 
static LiegroupSpacePtr_t SE3 ()
 Return $SE(3)$. More...
 
static LiegroupSpacePtr_t R2xSO2 ()
 Return $SO(2)$. More...
 
static LiegroupSpacePtr_t R3xSO3 ()
 Return $SO(3)$. More...
 
static LiegroupSpacePtr_t empty ()
 Return empty Lie group. More...
 

Protected Member Functions

 LiegroupSpace (const size_type &size)
 Constructor of vector space of given size. More...
 
 LiegroupSpace (const LiegroupSpace &other)
 
 LiegroupSpace (const LiegroupType &type)
 

Detailed Description

Cartesian product of elementary Lie groups.

Some values produced and manipulated by functions belong to Lie groups For instance rotations, rigid-body motions are element of Lie groups.

Elements of Lie groups are usually applied common operations, like

By analogy with vector spaces that are a particular type of Lie group, the above operations are implemented as operators + and - respectively acting on LiegroupElement instances.

This class represents a Lie group as the cartesian product of elementaty Lie groups. Those elementary Lie groups are gathered in a variant called LiegroupType.

Elements of a Lie group are represented by class LiegroupElement.

Constructor & Destructor Documentation

hpp::pinocchio::LiegroupSpace::LiegroupSpace ( const size_type size)
protected

Constructor of vector space of given size.

hpp::pinocchio::LiegroupSpace::LiegroupSpace ( const LiegroupSpace other)
protected
hpp::pinocchio::LiegroupSpace::LiegroupSpace ( const LiegroupType type)
protected

Member Function Documentation

static LiegroupSpacePtr_t hpp::pinocchio::LiegroupSpace::create ( const size_type size)
inlinestatic

Create instance of vector space of given size.

static LiegroupSpacePtr_t hpp::pinocchio::LiegroupSpace::create ( const LiegroupType type)
inlinestatic

Create instance with one Elementary Lie group.

static LiegroupSpacePtr_t hpp::pinocchio::LiegroupSpace::createCopy ( const LiegroupSpaceConstPtr_t other)
inlinestatic

Create copy.

static LiegroupSpacePtr_t hpp::pinocchio::LiegroupSpace::empty ( )
static

Return empty Lie group.

LiegroupElement hpp::pinocchio::LiegroupSpace::exp ( vectorIn_t  v) const

Return exponential of a tangent vector.

template<bool ApplyOnTheLeft>
void hpp::pinocchio::LiegroupSpace::Jdifference ( vectorIn_t  q0,
vectorIn_t  q1,
matrixOut_t  J0,
matrixOut_t  J1 
) const

Compute the Jacobian of the difference operation.

Given $ v = q1 - q0 $,

Parameters
[in]q0,q1
[in]J0the Jacobian of q0.
[in]J1the Jacobian of q1.
[out]J0the Jacobian of v with respect to q0.
[out]J1the Jacobian of v with respect to q1.
Note
to compute only one jacobian, provide for J0 or J1 an empty matrix.
void hpp::pinocchio::LiegroupSpace::Jintegrate ( vectorIn_t  v,
matrixOut_t  J 
) const

Compute the Jacobian of the integration operation.

Given $ y = x + v $,

Parameters
[in]Jthe Jacobian of x
[out]Jthe Jacobian of y
const std::vector<LiegroupType>& hpp::pinocchio::LiegroupSpace::liegroupTypes ( ) const
inline

Get reference to vector of elementary types.

void hpp::pinocchio::LiegroupSpace::mergeVectorSpaces ( )
std::string hpp::pinocchio::LiegroupSpace::name ( ) const

Return name of Lie group.

Referenced by hpp::pinocchio::operator<<().

LiegroupElement hpp::pinocchio::LiegroupSpace::neutral ( ) const

Return the neutral element as a vector.

size_type hpp::pinocchio::LiegroupSpace::nq ( ) const
inline

Dimension of the vector representation.

size_type hpp::pinocchio::LiegroupSpace::nq ( const std::size_t &  rank) const
inline

Dimension of elementary Liegroup at given rank.

size_type hpp::pinocchio::LiegroupSpace::nv ( ) const
inline

Dimension of the Lie group tangent space.

size_type hpp::pinocchio::LiegroupSpace::nv ( const std::size_t &  rank) const
inline

Dimension of elementary Liegroup tangent space at given rank.

bool hpp::pinocchio::LiegroupSpace::operator!= ( const LiegroupSpace other) const
LiegroupSpacePtr_t hpp::pinocchio::LiegroupSpace::operator*= ( const LiegroupSpaceConstPtr_t other)
bool hpp::pinocchio::LiegroupSpace::operator== ( const LiegroupSpace other) const
static LiegroupSpacePtr_t hpp::pinocchio::LiegroupSpace::R1 ( )
static

Return $\mathbf{R}$ as a Lie group.

static LiegroupSpacePtr_t hpp::pinocchio::LiegroupSpace::R2 ( )
static

Return $\mathbf{R}^2$ as a Lie group.

static LiegroupSpacePtr_t hpp::pinocchio::LiegroupSpace::R2xSO2 ( )
static

Return $SO(2)$.

static LiegroupSpacePtr_t hpp::pinocchio::LiegroupSpace::R3 ( )
static

Return $\mathbf{R}^3$ as a Lie group.

static LiegroupSpacePtr_t hpp::pinocchio::LiegroupSpace::R3xSO3 ( )
static

Return $SO(3)$.

static LiegroupSpacePtr_t hpp::pinocchio::LiegroupSpace::Rn ( const size_type n)
static

Return $\mathbf{R}^n$ as a Lie group.

Parameters
ndimension of vector space
static LiegroupSpacePtr_t hpp::pinocchio::LiegroupSpace::SE2 ( )
static

Return $SE(2)$.

static LiegroupSpacePtr_t hpp::pinocchio::LiegroupSpace::SE3 ( )
static

Return $SE(3)$.