Aikido
|
The two-dimensional special orthogonal group SO(2), i.e. More...
#include <aikido/statespace/SO2.hpp>
Classes | |
class | State |
Public Types | |
using | StateHandle = SO2StateHandle< State > |
using | StateHandleConst = SO2StateHandle< const State > |
using | ScopedState = statespace::ScopedState< StateHandle > |
using | ScopedStateConst = statespace::ScopedState< StateHandleConst > |
![]() | |
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 | |
SO2 ()=default | |
Constructs a state space representing SO(2). 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... | |
double | toAngle (const State *state) const |
Returns state as a rotation angle in (-pi, pi]. More... | |
void | fromAngle (State *state, double angle) const |
Sets state from a rotation angle in (-inf, inf). More... | |
Eigen::Rotation2Dd | toRotation (const State *state) const |
Returns state as an Eigen rotation. More... | |
void | fromRotation (State *state, const Eigen::Rotation2Dd &rotation) const |
Sets state from an Eigen rotation. More... | |
std::size_t | getStateSizeInBytes () const override |
Gets the size of a State, in bytes. More... | |
StateSpace::State * | allocateStateInBuffer (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 angle represented by the state. 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 | ~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 State * | allocateState () 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... | |
The two-dimensional special orthogonal group SO(2), i.e.
the space of planar rigid body rotations.
using aikido::statespace::SO2::StateHandleConst = SO2StateHandle<const State> |
|
default |
Constructs a state space representing SO(2).
|
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
.
_buffer | memory used to store the returned state |
_buffer
Implements aikido::statespace::StateSpace.
ScopedState aikido::statespace::SO2::cloneState | ( | const StateSpace::State * | stateIn | ) | const |
Creates an identical clone of stateIn
.
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
.
_state1 | left input state | |
_state2 | right input state | |
[out] | _out | output state |
|
overridevirtual |
Lie group operation for this StateSpace.
It is not acceptable for _out
to share memory with _state1
or _state2
.
_state1 | left input state | |
_state2 | right input state | |
[out] | _out | output state |
Implements aikido::statespace::StateSpace.
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:
[in,out] | _state1 | left input state, overwritten by output |
_state2 | right input state |
|
overridevirtual |
Copy a state.
_source | input state | |
[out] | _destination | output state |
Implements aikido::statespace::StateSpace.
ScopedState aikido::statespace::SO2::createState | ( | ) | const |
Helper function to create a ScopedState
.
ScopedState
.
|
overridevirtual |
Exponential mapping of Lie algebra element to a Lie group element.
The tangent space is parameterized a rotation angle.
[in] | tangent | Element of the tangent space. |
[out] | out | Corresponding element of the Lie group. |
Implements aikido::statespace::StateSpace.
|
overridevirtual |
Free a state previously created by allocateStateInBuffer
.
It is undefined behavior to access _state
after calling this function.
_state | state to free |
Implements aikido::statespace::StateSpace.
void aikido::statespace::SO2::fromAngle | ( | State * | state, |
double | angle | ||
) | const |
Sets state from a rotation angle in (-inf, inf).
[out] | state | State corresponding to angle. |
[in] | angle | Rotation angle in (-inf, inf). |
void aikido::statespace::SO2::fromRotation | ( | State * | state, |
const Eigen::Rotation2Dd & | rotation | ||
) | const |
Sets state from an Eigen rotation.
[out] | state | State corresponding to rotation. |
[in] | rotation | Eigen rotation. |
|
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.
Implements aikido::statespace::StateSpace.
|
overridevirtual |
Gets the identity element for this Lie group, such that:
[out] | _out | output state |
Implements aikido::statespace::StateSpace.
|
overridevirtual |
Gets the inverse of _in
in this Lie group, such that:
It is not acceptable for _in
to share memory with _out
.
_state | input state | |
[out] | _out | output state |
Implements aikido::statespace::StateSpace.
|
overridevirtual |
Gets the size of a State, in bytes.
State
Implements aikido::statespace::StateSpace.
|
overridevirtual |
Log mapping of Lie group element to a Lie algebra element.
The tangent space is parameterized as a rotation angle.
[in] | in | Element of this Lie group. |
[out] | tangent | Corresponding element of the tangent space. |
Implements aikido::statespace::StateSpace.
|
overridevirtual |
Print the angle represented by the state.
Implements aikido::statespace::StateSpace.
double aikido::statespace::SO2::toAngle | ( | const State * | state | ) | const |
Returns state as a rotation angle in (-pi, pi].
[in] | state | State. |