A manifold representing SO(3). The internal representation is done with quaternions. The distance between states is the angle between quaternions and interpolation is done with slerp. More...
#include <SO3StateManifold.h>
Classes | |
class | StateType |
The definition of a state in SO(3) represented as a unit quaternion. More... | |
Public Member Functions | |
double | norm (const StateType *state) const |
Compute the norm of a state. | |
virtual unsigned int | getDimension (void) const |
Get the dimension of the space. | |
virtual double | getMaximumExtent (void) const |
Get the maximum value a call to distance() can return. | |
virtual void | enforceBounds (State *state) const |
Bring the state within the bounds of the state space. | |
virtual bool | satisfiesBounds (const State *state) const |
Check if a state is inside the bounding box. | |
virtual void | copyState (State *destination, const State *source) const |
Copy a state to another. The memory of source and destination should NOT overlap. | |
virtual double | distance (const State *state1, const State *state2) const |
Computes distance to between two states. This value will always be between 0 and getMaximumExtent() | |
virtual bool | equalStates (const State *state1, const State *state2) const |
Checks whether two states are equal. | |
virtual void | interpolate (const State *from, const State *to, const double t, State *state) const |
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state. The memory location of state is not required to be different from the memory of either from or to. | |
virtual ManifoldStateSamplerPtr | allocStateSampler (void) const |
Allocate an instance of a uniform state sampler for this space. | |
virtual State * | allocState (void) const |
Allocate a state that can store a point in the described space. | |
virtual void | freeState (State *state) const |
Free the memory of the allocated state. | |
virtual double * | getValueAddressAtIndex (State *state, const unsigned int index) const |
Many states contain a number of double values. This function provides a means to get the memory address of a double value from state state located at position index. The first double value is returned for index = 0. If index is too large (does not point to any double values in the state), the return value is NULL. | |
virtual void | printState (const State *state, std::ostream &out) const |
Print a state to a stream. | |
virtual void | printSettings (std::ostream &out) const |
Print the settings for this manifold to a stream. | |
virtual void | registerProjections (void) |
Register the projections for this manifold. Usually, this is at least the default projection. These are implicit projections, set by the implementation of the manifold. This is called by setup(). |
A manifold representing SO(3). The internal representation is done with quaternions. The distance between states is the angle between quaternions and interpolation is done with slerp.
Definition at line 66 of file SO3StateManifold.h.