hpp-pinocchio  6.0.0
Wrapping of the kinematic/dynamic chain Pinocchio for HPP.
hpp::pinocchio::LiegroupSpace Class Reference

#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 element (vectorIn_t q) const
 Create a LiegroupElement from a configuration. More...
 
LiegroupElementRef elementRef (vectorOut_t q) const
 Create a LiegroupElementRef from a configuration. More...
 
LiegroupElementConstRef elementConstRef (vectorIn_t q) const
 Create a LiegroupElementRef from a configuration. More...
 
LiegroupElement exp (vectorIn_t v) const
 Return exponential of a tangent vector. More...
 
template<DerivativeProduct side>
void dIntegrate_dq (LiegroupElementConstRef q, vectorIn_t v, matrixOut_t J) const
 
template<DerivativeProduct side>
void dIntegrate_dv (LiegroupElementConstRef q, vectorIn_t v, matrixOut_t Jv) const
 
template<bool ApplyOnTheLeft>
void Jdifference (vectorIn_t q0, vectorIn_t q1, matrixOut_t J0, matrixOut_t J1) const
 
template<DerivativeProduct side>
void dDifference_dq0 (vectorIn_t q0, vectorIn_t q1, matrixOut_t J0) const
 
template<DerivativeProduct side>
void dDifference_dq1 (vectorIn_t q0, vectorIn_t q1, matrixOut_t J1) const
 
void interpolate (vectorIn_t q0, vectorIn_t q1, value_type u, vectorOut_t result) const
 
std::string name () const
 Return name of Lie group. More...
 
void mergeVectorSpaces ()
 
LiegroupSpacePtr_t vectorSpacesMerged () const
 
bool isVectorSpace () const
 
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)
 
static LiegroupSpacePtr_t R1 (bool rotation=false)
 
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 SO2 ()
 Return \(SO(2)\). More...
 
static LiegroupSpacePtr_t SO3 ()
 Return \(SO(3)\). More...
 
static LiegroupSpacePtr_t R2xSO2 ()
 Return \(\mathbf{R}^2 \times SO(2)\). More...
 
static LiegroupSpacePtr_t R3xSO3 ()
 Return \(\mathbf{R}^3 \times 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

  • integrating a velocity from a given element during unit time,
  • computing the constant velocity that moves from one element to another one in unit time.

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

◆ LiegroupSpace() [1/3]

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

Constructor of vector space of given size.

◆ LiegroupSpace() [2/3]

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

◆ LiegroupSpace() [3/3]

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

Member Function Documentation

◆ create() [1/2]

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

Create instance with one Elementary Lie group.

◆ create() [2/2]

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

Create instance of vector space of given size.

◆ createCopy()

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

Create copy.

◆ dDifference_dq0()

template<DerivativeProduct side>
void hpp::pinocchio::LiegroupSpace::dDifference_dq0 ( vectorIn_t  q0,
vectorIn_t  q1,
matrixOut_t  J0 
) const

Compute the Jacobian matrices of the difference operation. Given \( \mathbf{v} = \mathbf{q}_1 - \mathbf{q}_0 \),

Compute matrices \(J_{0}\) and \(J_{1}\) such that

\begin{equation} \dot{\mathbf{v}} = J_{0}\dot{\mathbf{q}_0} + J_{1}\dot{\mathbf{q}_1} \end{equation}

Parameters
[in]q0,q1Lie group elements,
[out]J0the Jacobian of v with respect to q0.

◆ dDifference_dq1()

template<DerivativeProduct side>
void hpp::pinocchio::LiegroupSpace::dDifference_dq1 ( vectorIn_t  q0,
vectorIn_t  q1,
matrixOut_t  J1 
) const

Compute the Jacobian matrices of the difference operation. Given \( \mathbf{v} = \mathbf{q}_1 - \mathbf{q}_0 \),

Compute matrices \(J_{0}\) and \(J_{1}\) such that

\begin{equation} \dot{\mathbf{v}} = J_{0}\dot{\mathbf{q}_0} + J_{1}\dot{\mathbf{q}_1} \end{equation}

Parameters
[in]q0,q1Lie group elements,
[out]J1the Jacobian of v with respect to q1.

◆ dIntegrate_dq()

template<DerivativeProduct side>
void hpp::pinocchio::LiegroupSpace::dIntegrate_dq ( LiegroupElementConstRef  q,
vectorIn_t  v,
matrixOut_t  J 
) const

Compute the Jacobian of the integration operation with respect to \(\mathbf{q}\).

Given \( \mathbf{p} = \mathbf{q} + \mathbf{v} \), compute \(J_{\mathbf{q}}\) such that

\begin{equation} \dot{\mathbf{p}} = J_{\mathbf{q}}\dot{\mathbf{q}} \end{equation}

for constant \(\mathbf{v}\). \(J_{\mathbf{q}}\) is a block diagonal matrix, each block corresponding to an elementary Lie group.

Template Parameters
sideside to multiply in place the Jacobian blocks. See "Return values" for an explanation.
Parameters
qthe configuration,
vthe velocity vector,
Return values
Jin place multiplied result. \(J\leftarrow J.J_{\mathbf{q}}\) if side is InputTimesDerivative \(J\leftarrow J_{\mathbf{q}}.J\) if side is DerivativeTimesInput. If \(J\) is initialized to identity, both results are the same.

◆ dIntegrate_dv()

template<DerivativeProduct side>
void hpp::pinocchio::LiegroupSpace::dIntegrate_dv ( LiegroupElementConstRef  q,
vectorIn_t  v,
matrixOut_t  Jv 
) const

Compute the Jacobian of the integration operation with respect to \(\mathbf{v}\).

Given \( \mathbf{p} = \mathbf{q} + \mathbf{v} \), compute \(J_{\mathbf{q}}\) such that

\begin{equation} \dot{\mathbf{p}} = J_{\mathbf{v}}\dot{\mathbf{v}} \end{equation}

for constant \(\mathbf{q}\). \(J_{\mathbf{v}}\) is a block diagonal matrix, each block corresponding to an elementary Lie group.

Template Parameters
sideside to multiply in place the Jacobian blocks. See "Return values" for an explanation.
Parameters
qthe configuration,
vthe velocity vector,
Return values
Jin place multiplied result. \(J\leftarrow J.J_{\mathbf{v}}\) if side is InputTimesDerivative \(J\leftarrow J_{\mathbf{v}}.J\) if side is DerivativeTimesInput. If \(J\) is initialized to identity, both results are the same.

◆ element()

LiegroupElement hpp::pinocchio::LiegroupSpace::element ( vectorIn_t  q) const

Create a LiegroupElement from a configuration.

◆ elementConstRef()

LiegroupElementConstRef hpp::pinocchio::LiegroupSpace::elementConstRef ( vectorIn_t  q) const

Create a LiegroupElementRef from a configuration.

◆ elementRef()

LiegroupElementRef hpp::pinocchio::LiegroupSpace::elementRef ( vectorOut_t  q) const

Create a LiegroupElementRef from a configuration.

◆ empty()

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

Return empty Lie group.

◆ exp()

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

Return exponential of a tangent vector.

◆ interpolate()

void hpp::pinocchio::LiegroupSpace::interpolate ( vectorIn_t  q0,
vectorIn_t  q1,
value_type  u,
vectorOut_t  result 
) const

Interpolate between two elements of the Lie group.

This is equivalent to \( q_0 \oplus u*(q_1 \ominus q_0) \).

Parameters
q0,q1two elements
uin [0,1] position along the interpolation: q0 for u=0, q1 for u=1
Return values
resultinterpolated configuration

◆ isVectorSpace()

bool hpp::pinocchio::LiegroupSpace::isVectorSpace ( ) const

◆ Jdifference()

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

◆ liegroupTypes()

const std::vector<LiegroupType>& hpp::pinocchio::LiegroupSpace::liegroupTypes ( ) const
inline

Get reference to vector of elementary types.

◆ mergeVectorSpaces()

void hpp::pinocchio::LiegroupSpace::mergeVectorSpaces ( )

◆ name()

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

Return name of Lie group.

◆ neutral()

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

Return the neutral element as a vector.

◆ nq() [1/2]

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

Dimension of the vector representation.

◆ nq() [2/2]

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

Dimension of elementary Liegroup at given rank.

◆ nv() [1/2]

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

Dimension of the Lie group tangent space.

◆ nv() [2/2]

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

Dimension of elementary Liegroup tangent space at given rank.

◆ operator!=()

bool hpp::pinocchio::LiegroupSpace::operator!= ( const LiegroupSpace other) const

◆ operator*=()

LiegroupSpacePtr_t hpp::pinocchio::LiegroupSpace::operator*= ( const LiegroupSpaceConstPtr_t other)

◆ operator==()

bool hpp::pinocchio::LiegroupSpace::operator== ( const LiegroupSpace other) const

◆ R1()

static LiegroupSpacePtr_t hpp::pinocchio::LiegroupSpace::R1 ( bool  rotation = false)
static

Return \(\mathbf{R}\) as a Lie group

Parameters
rotationwhether values of this space represent angles or lengths.

◆ R2()

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

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

◆ R2xSO2()

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

Return \(\mathbf{R}^2 \times SO(2)\).

◆ R3()

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

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

◆ R3xSO3()

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

Return \(\mathbf{R}^3 \times SO(3)\).

◆ Rn()

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

◆ SE2()

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

Return \(SE(2)\).

◆ SE3()

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

Return \(SE(3)\).

◆ SO2()

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

Return \(SO(2)\).

◆ SO3()

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

Return \(SO(3)\).

◆ vectorSpacesMerged()

LiegroupSpacePtr_t hpp::pinocchio::LiegroupSpace::vectorSpacesMerged ( ) const

The documentation for this class was generated from the following file: