SE3StateSpace.h
void setName(const std::string &name)
Set the name of the state space.
Definition: StateSpace.cpp:212
State * allocState() const override
Allocate a state that can store a point in the described space.
Definition: SE3StateSpace.cpp:41
void freeState(State *state) const override
Free the memory of the allocated state.
Definition: SE3StateSpace.cpp:48
void lock()
Lock this state space. This means no further spaces can be added as components. This function can be ...
const RealVectorBounds & getBounds() const
Get the bounds for this state space.
Definition: SE3StateSpace.h:133
A state in SE(3): position = (x, y, z), quaternion = (x, y, z, w)
Definition: SE3StateSpace.h:53
SO3StateSpace::StateType & rotation()
Get the rotation component of the state and allow changing it as well.
Definition: SE3StateSpace.h:83
void setBounds(const RealVectorBounds &bounds)
Set the bounds of this state space. This defines the range of the space in which sampling is performe...
Definition: SE3StateSpace.h:127
A space to allow the composition of state spaces.
Definition: StateSpace.h:573
The definition of a state in SO(3) represented as a unit quaternion.
Definition: SO3StateSpace.h:90
const SO3StateSpace::StateType & rotation() const
Get the rotation component of the state.
Definition: SE3StateSpace.h:77
void addSubspace(const StateSpacePtr &component, double weight)
Adds a new state space as part of the compound state space. For computing distances within the compou...
void registerProjections() override
Register the projections for this state space. Usually, this is at least the default projection...
Definition: SE3StateSpace.cpp:53
The lower and upper bounds for an Rn space.
Definition: RealVectorBounds.h:47
void setXYZ(double x, double y, double z)
Set the X, Y and Z components of the state.
Definition: SE3StateSpace.h:107