Aikido
aikido::statespace::StateSpace Class Referenceabstract

Represents a Lie group and its associated Lie algebra, i.e. More...

#include <aikido/statespace/StateSpace.hpp>

Inheritance diagram for aikido::statespace::StateSpace:
aikido::statespace::CartesianProduct aikido::statespace::dart::JointStateSpace aikido::statespace::R< N > aikido::statespace::SE2 aikido::statespace::SE3 aikido::statespace::SO2 aikido::statespace::SO3 aikido::statespace::dart::MetaSkeletonStateSpace aikido::statespace::dart::RJoint< N > aikido::statespace::dart::SE2Joint aikido::statespace::dart::SE3Joint aikido::statespace::dart::SO2Joint aikido::statespace::dart::SO3Joint aikido::statespace::dart::WeldJoint aikido::statespace::dart::RJoint< N > aikido::statespace::dart::WeldJoint aikido::statespace::dart::SE2Joint aikido::statespace::dart::SE3Joint aikido::statespace::dart::SO2Joint aikido::statespace::dart::SO3Joint

Classes

class  State
 

Public Types

using StateHandle = statespace::StateHandle< StateSpace, State >
 
using StateHandleConst = statespace::StateHandle< StateSpace, const State >
 
using ScopedState = statespace::ScopedState< StateHandle >
 
using ScopedStateConst = statespace::ScopedState< StateHandleConst >
 

Public Member Functions

virtual ~StateSpace ()=default
 
ScopedState createState () const
 Helper function to create a ScopedState. More...
 
ScopedState cloneState (const State *stateIn) const
 Creates an identical clone of stateIn. More...
 
virtual StateallocateState () const
 Allocate a new state. More...
 
virtual void freeState (State *_state) const
 Free a state previously created by allocateState. More...
 
virtual std::size_t getStateSizeInBytes () const =0
 Gets the size of a State, in bytes. More...
 
virtual StateallocateStateInBuffer (void *_buffer) const =0
 Create a new state in a pre-allocated buffer. More...
 
virtual void freeStateInBuffer (State *_state) const =0
 Free a state previously created by allocateStateInBuffer. More...
 
virtual void compose (const State *_state1, const State *_state2, State *_out) const =0
 Lie group operation for this StateSpace. More...
 
virtual void compose (State *_state1, const State *_state2) const
 Lie group operation for this StateSpace. More...
 
virtual void getIdentity (State *_out) const =0
 Gets the identity element for this Lie group, such that: More...
 
virtual void getInverse (const State *_state, State *_out) const =0
 Gets the inverse of _in in this Lie group, such that: More...
 
virtual void getInverse (State *_state) const
 Gets the inverse of _in in this Lie group. More...
 
virtual std::size_t getDimension () const =0
 Get the dimension of this Lie group. More...
 
virtual void copyState (const StateSpace::State *_source, StateSpace::State *_destination) const =0
 Copy a state. More...
 
virtual void expMap (const Eigen::VectorXd &_tangent, State *_out) const =0
 Exponential mapping of Lie algebra element to a Lie group element. More...
 
virtual void logMap (const State *_in, Eigen::VectorXd &_tangent) const =0
 Log mapping of Lie group element to a Lie algebra element. More...
 
virtual void print (const State *_state, std::ostream &_os) const =0
 Print the state to the output stream. More...
 

Detailed Description

Represents a Lie group and its associated Lie algebra, i.e.

a differentiable manifold embedded in Euclidean space. This is a base class for all other state spaces and provides the following operations:

  • a group operation
  • an identity element
  • an inverse operation
  • the log map from an element of the Lie group to the Lie algebra
  • the exponential map from an element of the Lie algebra to the Lie group

These operations on StateSpace are only defined on on State objects created by the same StateSpace instance. State is an opaque class that can only be modified if you know which concrete type of StateSpace created it. We strongly recommend using the ScopedState and StateHandle mechanism to keep each State paired with the StateSpace that it resides in.

Member Typedef Documentation

◆ ScopedState

◆ ScopedStateConst

◆ StateHandle

◆ StateHandleConst

Constructor & Destructor Documentation

◆ ~StateSpace()

virtual aikido::statespace::StateSpace::~StateSpace ( )
virtualdefault

Member Function Documentation

◆ allocateState()

virtual State* aikido::statespace::StateSpace::allocateState ( ) const
virtual

Allocate a new state.

This must be deleted with freeState. This is a helper function that allocates memory, uses allocateStateInBuffer to create a State, and returns that pointer.

Returns
state in this space

◆ allocateStateInBuffer()

virtual State* aikido::statespace::StateSpace::allocateStateInBuffer ( void *  _buffer) const
pure virtual

Create a new state in a pre-allocated buffer.

The input argument must contain at least getStateSizeInBytes() bytes of memory. This state must be freed with freeStateInBuffer before freeing _buffer.

Parameters
_buffermemory used to store the returned state
Returns
state object allocated in _buffer

Implemented in aikido::statespace::SO2, aikido::statespace::CartesianProduct, aikido::statespace::R< N >, aikido::statespace::SE2, aikido::statespace::SE3, and aikido::statespace::SO3.

◆ cloneState()

ScopedState aikido::statespace::StateSpace::cloneState ( const State stateIn) const

Creates an identical clone of stateIn.

◆ compose() [1/2]

virtual void aikido::statespace::StateSpace::compose ( const State _state1,
const State _state2,
State _out 
) const
pure virtual

Lie group operation for this StateSpace.

It is not acceptable for _out to share memory with _state1 or _state2.

Parameters
_state1left input state
_state2right input state
[out]_outoutput state

Implemented in aikido::statespace::SO2, aikido::statespace::CartesianProduct, aikido::statespace::R< N >, aikido::statespace::SE2, aikido::statespace::SE3, and aikido::statespace::SO3.

◆ compose() [2/2]

virtual void aikido::statespace::StateSpace::compose ( State _state1,
const State _state2 
) const
virtual

Lie group operation for this StateSpace.

This is an in-place version of the three argument compose member function that computes:

_state1 = _state1 * _state2.
Parameters
[in,out]_state1left input state, overwritten by output
_state2right input state

◆ copyState()

virtual void aikido::statespace::StateSpace::copyState ( const StateSpace::State _source,
StateSpace::State _destination 
) const
pure virtual

Copy a state.

Parameters
_sourceinput state
[out]_destinationoutput state

Implemented in aikido::statespace::SO2, aikido::statespace::CartesianProduct, aikido::statespace::R< N >, aikido::statespace::SE2, aikido::statespace::SE3, and aikido::statespace::SO3.

◆ createState()

ScopedState aikido::statespace::StateSpace::createState ( ) const

Helper function to create a ScopedState.

Returns
new ScopedState

◆ expMap()

virtual void aikido::statespace::StateSpace::expMap ( const Eigen::VectorXd &  _tangent,
State _out 
) const
pure virtual

Exponential mapping of Lie algebra element to a Lie group element.

The parameterization of the tangent space is defined by the concrete implementation of this class.

Parameters
_tangentcorresponding element of the tangent space
[out]_outelement of this Lie group

Implemented in aikido::statespace::SO2, aikido::statespace::CartesianProduct, aikido::statespace::R< N >, aikido::statespace::SE2, aikido::statespace::SE3, and aikido::statespace::SO3.

◆ freeState()

virtual void aikido::statespace::StateSpace::freeState ( State _state) const
virtual

Free a state previously created by allocateState.

It is undefined behavior to access _state after calling this function.

Parameters
_statestate to be deleted

◆ freeStateInBuffer()

virtual void aikido::statespace::StateSpace::freeStateInBuffer ( State _state) const
pure virtual

Free a state previously created by allocateStateInBuffer.

It is undefined behavior to access _state after calling this function.

Parameters
_statestate to free

Implemented in aikido::statespace::SO2, aikido::statespace::CartesianProduct, aikido::statespace::R< N >, aikido::statespace::SE2, aikido::statespace::SE3, and aikido::statespace::SO3.

◆ getDimension()

virtual std::size_t aikido::statespace::StateSpace::getDimension ( ) const
pure virtual

Get the dimension of this Lie group.

This is also the dimension of the tangent space, i.e. the Lie algebra, associated with this group.

Returns
dimension of this state space

Implemented in aikido::statespace::CartesianProduct, aikido::statespace::R< N >, aikido::statespace::SE2, aikido::statespace::SE3, aikido::statespace::SO3, and aikido::statespace::SO2.

◆ getIdentity()

virtual void aikido::statespace::StateSpace::getIdentity ( State _out) const
pure virtual

Gets the identity element for this Lie group, such that:

compose(state, identity) = state
Parameters
[out]_outoutput state

Implemented in aikido::statespace::SO2, aikido::statespace::CartesianProduct, aikido::statespace::R< N >, aikido::statespace::SE2, aikido::statespace::SE3, and aikido::statespace::SO3.

◆ getInverse() [1/2]

virtual void aikido::statespace::StateSpace::getInverse ( const State _state,
State _out 
) const
pure virtual

Gets the inverse of _in in this Lie group, such that:

compose(state, inverse(state)) = identity

It is not acceptable for _in to share memory with _out.

Parameters
_stateinput state
[out]_outoutput state

Implemented in aikido::statespace::SO2, aikido::statespace::CartesianProduct, aikido::statespace::R< N >, aikido::statespace::SE2, aikido::statespace::SE3, and aikido::statespace::SO3.

◆ getInverse() [2/2]

virtual void aikido::statespace::StateSpace::getInverse ( State _state) const
virtual

Gets the inverse of _in in this Lie group.

This is an in-place version of the two-argument getInverse member function.

Parameters
[in,out]_stateinput state, to be overwritten by output

◆ getStateSizeInBytes()

virtual std::size_t aikido::statespace::StateSpace::getStateSizeInBytes ( ) const
pure virtual

◆ logMap()

virtual void aikido::statespace::StateSpace::logMap ( const State _in,
Eigen::VectorXd &  _tangent 
) const
pure virtual

Log mapping of Lie group element to a Lie algebra element.

The parameterization of the tangent space is defined by the concrete implementation of this class.

Parameters
_inelement of this Lie group
[out]_tangentcorresponding element of the tangent space

Implemented in aikido::statespace::SO2, aikido::statespace::SE2, aikido::statespace::CartesianProduct, aikido::statespace::R< N >, aikido::statespace::SE3, and aikido::statespace::SO3.

◆ print()

virtual void aikido::statespace::StateSpace::print ( const State _state,
std::ostream &  _os 
) const
pure virtual

Print the state to the output stream.

Parameters
_stateThe element to print
_osThe stream to print to

Implemented in aikido::statespace::SO2, aikido::statespace::CartesianProduct, aikido::statespace::R< N >, aikido::statespace::SE3, aikido::statespace::SE2, and aikido::statespace::SO3.

aikido::statespace::StateSpace::compose
virtual void compose(const State *_state1, const State *_state2, State *_out) const =0
Lie group operation for this StateSpace.