Aikido
aikido::statespace::CartesianProduct Class Reference

Represents the Cartesian product of other StateSpaces. More...

#include <aikido/statespace/CartesianProduct.hpp>

Inheritance diagram for aikido::statespace::CartesianProduct:
aikido::statespace::StateSpace aikido::statespace::dart::MetaSkeletonStateSpace

Classes

class  State
 A tuple of states where the i-th state is from the i-th subspace. More...
 

Public Types

using StateHandle = CompoundStateHandle< State >
 
using StateHandleConst = CompoundStateHandle< const State >
 
using ScopedState = statespace::ScopedState< StateHandle >
 
using ScopedStateConst = statespace::ScopedState< StateHandleConst >
 
- Public Types inherited from aikido::statespace::StateSpace
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

 CartesianProduct (std::vector< ConstStateSpacePtr > _subspaces)
 Construct the Cartesian product of a vector of subspaces. More...
 
ScopedState createState () const
 Helper function to create a ScopedState. More...
 
ScopedState cloneState (const StateSpace::State *stateIn) const
 Creates an identical clone of stateIn. More...
 
std::size_t getNumSubspaces () const
 Gets number of subspaces. More...
 
template<class Space = StateSpace>
std::shared_ptr< const Space > getSubspace (std::size_t _index) const
 Gets subspace of type Space by at _index. More...
 
template<class Space = StateSpace>
Space::State * getSubState (State *_state, std::size_t _index) const
 Gets substate of type Space::State from a CompoundState by index. More...
 
template<class Space = StateSpace>
const Space::State * getSubState (const State *_state, std::size_t _index) const
 Gets substate of type Space::State from a CompoundState by index. More...
 
template<class Space = StateSpace>
Space::StateHandle getSubStateHandle (State *_state, std::size_t _index) const
 Gets substate of type Space::State from a CompoundState by index and wraps it in a Space::StateHandle helper class. More...
 
template<class Space = StateSpace>
Space::StateHandleConst getSubStateHandle (const State *_state, std::size_t _index) const
 Gets substate of type Space::State from a CompoundState by index and wraps it in a Space::ConstStateHandle helper class. More...
 
std::size_t getStateSizeInBytes () const override
 Gets the size of a State, in bytes. More...
 
StateSpace::StateallocateStateInBuffer (void *_buffer) const override
 Create a new state in a pre-allocated buffer. More...
 
void freeStateInBuffer (StateSpace::State *_state) const override
 Free a state previously created by allocateStateInBuffer. More...
 
void compose (const StateSpace::State *_state1, const StateSpace::State *_state2, StateSpace::State *_out) const override
 Lie group operation for this StateSpace. More...
 
void getIdentity (StateSpace::State *_state) const override
 Gets the identity element for this Lie group, such that: More...
 
void getInverse (const StateSpace::State *_in, StateSpace::State *_out) const override
 Gets the inverse of _in in this Lie group, such that: More...
 
std::size_t getDimension () const override
 Get the dimension of this Lie group. More...
 
void copyState (const StateSpace::State *_source, StateSpace::State *_destination) const override
 Copy a state. More...
 
void expMap (const Eigen::VectorXd &_tangent, StateSpace::State *_out) const override
 Exponential mapping of Lie algebra element to a Lie group element. More...
 
void logMap (const StateSpace::State *_in, Eigen::VectorXd &_tangent) const override
 Log mapping of Lie group element to a Lie algebra element. More...
 
void print (const StateSpace::State *_state, std::ostream &_os) const override
 Print the contents of each substate contained in the state as a list with each substate enclosed in brackets and including its index Format: [0: ...] [1: ...] ... 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...
 
- Public Member Functions inherited from aikido::statespace::StateSpace
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 void compose (State *_state1, const State *_state2) const
 Lie group operation for this StateSpace. More...
 
virtual void getInverse (State *_state) const
 Gets the inverse of _in in this Lie group. More...
 

Private Attributes

std::vector< ConstStateSpacePtrmSubspaces
 
std::vector< std::size_t > mOffsets
 
std::size_t mSizeInBytes
 

Detailed Description

Represents the Cartesian product of other StateSpaces.

Member Typedef Documentation

◆ ScopedState

◆ ScopedStateConst

◆ StateHandle

◆ StateHandleConst

Constructor & Destructor Documentation

◆ CartesianProduct()

aikido::statespace::CartesianProduct::CartesianProduct ( std::vector< ConstStateSpacePtr _subspaces)
explicit

Construct the Cartesian product of a vector of subspaces.

Parameters
_subspacesvector of subspaces

Member Function Documentation

◆ allocateStateInBuffer()

StateSpace::State* aikido::statespace::CartesianProduct::allocateStateInBuffer ( void *  _buffer) const
overridevirtual

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

Implements aikido::statespace::StateSpace.

◆ cloneState()

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

Creates an identical clone of stateIn.

◆ compose() [1/3]

virtual void aikido::statespace::StateSpace::compose

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

◆ compose() [2/3]

void aikido::statespace::CartesianProduct::compose ( const StateSpace::State _state1,
const StateSpace::State _state2,
StateSpace::State _out 
) const
overridevirtual

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

Implements aikido::statespace::StateSpace.

◆ compose() [3/3]

virtual void aikido::statespace::StateSpace::compose

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()

void aikido::statespace::CartesianProduct::copyState ( const StateSpace::State _source,
StateSpace::State _destination 
) const
overridevirtual

Copy a state.

Parameters
_sourceinput state
[out]_destinationoutput state

Implements aikido::statespace::StateSpace.

◆ createState()

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

Helper function to create a ScopedState.

Returns
new ScopedState

◆ expMap()

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

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

The tangent space is parameterized by stacking the tangent vector of each subspace in the order the subspaces are listed in.

Parameters
_tangentelement of the tangent space
[out]_outcorresponding element of the Lie group

Implements aikido::statespace::StateSpace.

◆ freeStateInBuffer()

void aikido::statespace::CartesianProduct::freeStateInBuffer ( StateSpace::State _state) const
overridevirtual

Free a state previously created by allocateStateInBuffer.

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

Parameters
_statestate to free

Implements aikido::statespace::StateSpace.

◆ getDimension()

std::size_t aikido::statespace::CartesianProduct::getDimension ( ) const
overridevirtual

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

Implements aikido::statespace::StateSpace.

◆ getIdentity()

void aikido::statespace::CartesianProduct::getIdentity ( StateSpace::State _out) const
overridevirtual

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

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

Implements aikido::statespace::StateSpace.

◆ getInverse()

void aikido::statespace::CartesianProduct::getInverse ( const StateSpace::State _state,
StateSpace::State _out 
) const
overridevirtual

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

Implements aikido::statespace::StateSpace.

◆ getNumSubspaces()

std::size_t aikido::statespace::CartesianProduct::getNumSubspaces ( ) const

Gets number of subspaces.

Returns
number of subspaces

◆ getStateSizeInBytes()

std::size_t aikido::statespace::CartesianProduct::getStateSizeInBytes ( ) const
overridevirtual

Gets the size of a State, in bytes.

Returns
size, in bytes, requires to store a State

Implements aikido::statespace::StateSpace.

◆ getSubspace()

template<class Space >
std::shared_ptr< const Space > aikido::statespace::CartesianProduct::getSubspace ( std::size_t  _index) const

Gets subspace of type Space by at _index.

Template Parameters
Spacetype of StateSpace for subspace _index
Parameters
_indexin the range [ 0, getNumSubspaces() ]
Returns
subspace at _index

◆ getSubState() [1/2]

template<class Space >
const Space::State * aikido::statespace::CartesianProduct::getSubState ( const State _state,
std::size_t  _index 
) const

Gets substate of type Space::State from a CompoundState by index.

This is an overload for when _state is const.

Template Parameters
Spacetype of StateSpace for subspace _index
Parameters
_statestate in this CartesianProduct
_indexin the range [ 0, getNumSubspaces() ]
Returns
state at _index

◆ getSubState() [2/2]

template<class Space >
Space::State * aikido::statespace::CartesianProduct::getSubState ( State _state,
std::size_t  _index 
) const

Gets substate of type Space::State from a CompoundState by index.

Template Parameters
Spacetype of StateSpace for subspace _index
Parameters
_statestate in this CartesianProduct
_indexin the range [ 0, getNumSubspaces() ]
Returns
state at _index

◆ getSubStateHandle() [1/2]

template<class Space >
Space::StateHandleConst aikido::statespace::CartesianProduct::getSubStateHandle ( const State _state,
std::size_t  _index 
) const

Gets substate of type Space::State from a CompoundState by index and wraps it in a Space::ConstStateHandle helper class.

This is an overload for when _state is const.

Template Parameters
Spacetype of StateSpace for subspace _index
Parameters
_statestate in this CartesianProduct
_indexin the range [ 0, \ getNumSubspaces() ]
Returns
state at _index

◆ getSubStateHandle() [2/2]

template<class Space >
Space::StateHandle aikido::statespace::CartesianProduct::getSubStateHandle ( State _state,
std::size_t  _index 
) const

Gets substate of type Space::State from a CompoundState by index and wraps it in a Space::StateHandle helper class.

Template Parameters
Spacetype of StateSpace for subspace _index
Parameters
_statestate in this CartesianProduct
_indexin the range [ 0, getNumSubspaces() ]
Returns
state at _index

◆ logMap()

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

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

The tangent space is parameterized by stacking the tangent vector of each subspace in the order the subspaces are listed in.

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

Implements aikido::statespace::StateSpace.

◆ print()

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

Print the contents of each substate contained in the state as a list with each substate enclosed in brackets and including its index Format: [0: ...] [1: ...] ...

[n: ...]

Implements aikido::statespace::StateSpace.

Member Data Documentation

◆ mOffsets

std::vector<std::size_t> aikido::statespace::CartesianProduct::mOffsets
private

◆ mSizeInBytes

std::size_t aikido::statespace::CartesianProduct::mSizeInBytes
private

◆ mSubspaces

std::vector<ConstStateSpacePtr> aikido::statespace::CartesianProduct::mSubspaces
private
aikido::statespace::CartesianProduct::compose
void compose(const StateSpace::State *_state1, const StateSpace::State *_state2, StateSpace::State *_out) const override
Lie group operation for this StateSpace.