Aikido
aikido::statespace::R< N > Class Template Reference

Represents a N-dimensional real vector space with vector addition as the group operation. More...

#include <aikido/statespace/Rn.hpp>

Inheritance diagram for aikido::statespace::R< N >:
aikido::statespace::StateSpace aikido::statespace::dart::RJoint< N > aikido::statespace::dart::WeldJoint

Classes

class  State
 Point in a R<N>. More...
 

Public Types

using VectorNd = Eigen::Matrix< double, N, 1 >
 
using StateHandle = RStateHandle< State >
 
using StateHandleConst = RStateHandle< 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

 R ()
 Constructs a N dimensional real vector space only when the dimension is can be known in compile time. More...
 
 R (int dimension)
 Constructs a dimension dimensional real vector space. 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...
 
Eigen::Map< const VectorNdgetValue (const State *_state) const
 Gets the real vector stored in a State. More...
 
void setValue (State *_state, const VectorNd &_value) const
 Sets the real vector stored in a State. 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 *_out) 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 n-dimensional vector represented by the state Format: [x_1, x_2, ..., x_n]. 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...
 

Static Public Attributes

static constexpr int DimensionAtCompileTime = N
 Dimension of the space. More...
 

Private Member Functions

Eigen::Map< VectorNdgetMutableValue (State *_state) const
 Gets the mutable value stored in a Rn::State. More...
 

Private Attributes

int mDimension
 Dimension of the real vector space. More...
 

Detailed Description

template<int N>
class aikido::statespace::R< N >

Represents a N-dimensional real vector space with vector addition as the group operation.

N should be either non-negative or Eigen::Dynamic.

Member Typedef Documentation

◆ ScopedState

◆ ScopedStateConst

◆ StateHandle

template<int N>
using aikido::statespace::R< N >::StateHandle = RStateHandle<State>

◆ StateHandleConst

template<int N>
using aikido::statespace::R< N >::StateHandleConst = RStateHandle<const State>

◆ VectorNd

template<int N>
using aikido::statespace::R< N >::VectorNd = Eigen::Matrix<double, N, 1>

Constructor & Destructor Documentation

◆ R() [1/2]

template<int N>
aikido::statespace::R< N >::R

Constructs a N dimensional real vector space only when the dimension is can be known in compile time.

If the dimension is known in compile time, it is recommended to use this constructor over R(int) because this constructor uses fixed size Eigen objects to represent the state data internally, which is generally faster than using dynamic size Eigen objects.

N must be non-negative and not Eigen::Dynamic.

Exceptions
std::invalid_argumentwhen N is Eigen::Dynamic.
See also
R(int)

◆ R() [2/2]

template<int N>
aikido::statespace::R< N >::R ( int  dimension)
explicit

Constructs a dimension dimensional real vector space.

This constructor must be used only when N is Eigen::Dynamic (i.e., -1). Otherwise, throws an std::invalid_argument exception.

N must be non-negative and not Eigen::Dynamic.

Exceptions
std::invalid_argumentwhen N is not Eigen::Dynamic and dimension is not the same with N.
See also
R()

Member Function Documentation

◆ allocateStateInBuffer()

template<int N>
StateSpace::State * aikido::statespace::R< N >::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()

template<int N>
auto aikido::statespace::R< N >::cloneState ( const StateSpace::State stateIn) const

Creates an identical clone of stateIn.

◆ compose() [1/3]

template<int N>
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]

template<int N>
void aikido::statespace::R< N >::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]

template<int N>
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()

template<int N>
void aikido::statespace::R< N >::copyState ( const StateSpace::State _source,
StateSpace::State _destination 
) const
overridevirtual

Copy a state.

Parameters
_sourceinput state
[out]_destinationoutput state

Implements aikido::statespace::StateSpace.

◆ createState()

template<int N>
auto aikido::statespace::R< N >::createState

Helper function to create a ScopedState.

Returns
new ScopedState

◆ expMap()

template<int N>
void aikido::statespace::R< N >::expMap ( const Eigen::VectorXd &  _tangent,
StateSpace::State _out 
) const
overridevirtual

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

This is simply the identity transformation on a real vector space.

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

Implements aikido::statespace::StateSpace.

◆ freeStateInBuffer()

template<int N>
void aikido::statespace::R< N >::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()

template<int N>
std::size_t aikido::statespace::R< N >::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()

template<int N>
void aikido::statespace::R< N >::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()

template<int N>
void aikido::statespace::R< N >::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.

◆ getMutableValue()

template<int N>
auto aikido::statespace::R< N >::getMutableValue ( State _state) const
private

Gets the mutable value stored in a Rn::State.

This is used internally to implement the public getValue member functions.

Parameters
_stateelement of this state space
Returns
mutable reference to real vector stored in _state

◆ getStateSizeInBytes()

template<int N>
std::size_t aikido::statespace::R< N >::getStateSizeInBytes ( ) const
overridevirtual

Gets the size of a State, in bytes.

Returns
size, in bytes, requires to store a State

Implements aikido::statespace::StateSpace.

◆ getValue()

template<int N>
auto aikido::statespace::R< N >::getValue ( const State _state) const

Gets the real vector stored in a State.

Parameters
_statea State in this state space
Returns
real vector represented by _state

◆ logMap()

template<int N>
void aikido::statespace::R< N >::logMap ( const StateSpace::State _in,
Eigen::VectorXd &  _tangent 
) const
overridevirtual

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

This is simply an identity transformation on a real vector space.

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

Implements aikido::statespace::StateSpace.

◆ print()

template<int N>
void aikido::statespace::R< N >::print ( const StateSpace::State _state,
std::ostream &  _os 
) const
overridevirtual

Print the n-dimensional vector represented by the state Format: [x_1, x_2, ..., x_n].

Implements aikido::statespace::StateSpace.

◆ setValue()

template<int N>
void aikido::statespace::R< N >::setValue ( State _state,
const VectorNd _value 
) const

Sets the real vector stored in a State.

Parameters
_statea State in this state space
_valuereal vector to store in _state

Member Data Documentation

◆ DimensionAtCompileTime

template<int N>
constexpr int aikido::statespace::R< N >::DimensionAtCompileTime = N
staticconstexpr

Dimension of the space.

◆ mDimension

template<int N>
int aikido::statespace::R< N >::mDimension
private

Dimension of the real vector space.

Note that this value is only used for dynamic sized vector space (the dimension is changable).

Warning
Don't use this variable directly. Use getDimension() instead.
See also
getDimension().
aikido::statespace::R::compose
void compose(const StateSpace::State *_state1, const StateSpace::State *_state2, StateSpace::State *_out) const override
Lie group operation for this StateSpace.
Definition: Rn-impl.hpp:196