aikido
Classes | Public Types | Public Member Functions | List of all members
aikido::statespace::SO3 Class Reference

The two-dimensional special orthogonal group SO(3), i.e. More...

#include <SO3.hpp>

Inheritance diagram for aikido::statespace::SO3:
aikido::statespace::StateSpace aikido::statespace::dart::SO3Joint

Classes

class  State
 State in SO(3), a spatial rotation. More...
 

Public Types

using StateHandle = SO3StateHandle< State >
 
using StateHandleConst = SO3StateHandle< const State >
 
using ScopedState = statespace::ScopedState< StateHandle >
 
using ScopedStateConst = statespace::ScopedState< StateHandleConst >
 
using Quaternion = State::Quaternion
 
- 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

 SO3 ()=default
 Constructs a state space representing SO(3).
 
ScopedState createState () const
 Helper function to create a ScopedState. More...
 
ScopedState cloneState (const StateSpace::State *stateIn) const
 Creates an identical clone of stateIn.
 
const Quaternion & getQuaternion (const State *_state) const
 Gets a state as a unit quaternion. More...
 
void setQuaternion (State *_state, const Quaternion &_quaternion) const
 Sets a state to a unit quaternion. 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
 
void compose (const StateSpace::State *_state1, const StateSpace::State *_state2, StateSpace::State *_out) const override
 
void getIdentity (StateSpace::State *_out) const override
 
void getInverse (const StateSpace::State *_in, StateSpace::State *_out) const override
 
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 quaternion represented by the state. More...
 
- Public Member Functions inherited from aikido::statespace::StateSpace
ScopedState createState () const
 Helper function to create a ScopedState. More...
 
ScopedState cloneState (const State *stateIn) const
 Creates an identical clone of stateIn.
 
virtual StateallocateState () const
 Allocate a new state. More...
 
virtual void freeState (State *_state) const
 Free a state previously created by allocateState. 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 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

The two-dimensional special orthogonal group SO(3), i.e.

the space of spatial rigid body rotations.

Member Function Documentation

§ allocateStateInBuffer()

StateSpace::State * aikido::statespace::SO3::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.

§ copyState()

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

Copy a state.

Parameters
_sourceinput state
[out]_destinationoutput state

Implements aikido::statespace::StateSpace.

§ createState()

auto aikido::statespace::SO3::createState ( ) const

Helper function to create a ScopedState.

Returns
new ScopedState

§ expMap()

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

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

The tangent space is parameterized as a spatial rotation velocity.

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

§ getDimension()

std::size_t aikido::statespace::SO3::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.

§ getQuaternion()

auto aikido::statespace::SO3::getQuaternion ( const State _state) const

Gets a state as a unit quaternion.

Parameters
_stateinput state
Returns
unit quaternion representing orientation

§ getStateSizeInBytes()

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

Gets the size of a State, in bytes.

Returns
size, in bytes, requires to store a State

Implements aikido::statespace::StateSpace.

§ logMap()

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

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

The tangent space is parameterized as a spatial rotational velocity.

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

§ print()

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

Print the quaternion represented by the state.

Format: [w, x, y, z]

§ setQuaternion()

void aikido::statespace::SO3::setQuaternion ( State _state,
const Quaternion &  _quaternion 
) const

Sets a state to a unit quaternion.

Parameters
_stateinput state
_quaternionunit quaternion representing orientation

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