SE3StateSpace.h
void setName(const std::string &name)
Set the name of the state space.
Definition: StateSpace.cpp:203
virtual State * allocState() const
Allocate a state that can store a point in the described space.
Definition: SE3StateSpace.cpp:41
A boost shared pointer wrapper for ompl::base::StateSpace.
void lock()
Lock this state space. This means no further spaces can be added as components. This function can be ...
Definition: StateSpace.cpp:1146
A state in SE(3): position = (x, y, z), quaternion = (x, y, z, w)
Definition: SE3StateSpace.h:55
A state space 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: SO3StateSpace.h:84
SO3StateSpace::StateType & rotation()
Get the rotation component of the state and allow changing it as well.
Definition: SE3StateSpace.h:87
CompoundState StateType
Define the type of state allocated by this state space.
Definition: StateSpace.h:549
virtual void registerProjections()
Register the projections for this state space. Usually, this is at least the default projection...
Definition: SE3StateSpace.cpp:53
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:134
A space to allow the composition of state spaces.
Definition: StateSpace.h:544
The definition of a state in SO(3) represented as a unit quaternion.
Definition: SO3StateSpace.h:94
const RealVectorBounds & getBounds() const
Get the bounds for this state space.
Definition: SE3StateSpace.h:140
A state space representing Rn. The distance function is the L2 norm.
Definition: RealVectorStateSpace.h:75
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...
Definition: StateSpace.cpp:855
The lower and upper bounds for an Rn space.
Definition: RealVectorBounds.h:48
virtual void freeState(State *state) const
Free the memory of the allocated state.
Definition: SE3StateSpace.cpp:48
void setXYZ(double x, double y, double z)
Set the X, Y and Z components of the state.
Definition: SE3StateSpace.h:111
const SO3StateSpace::StateType & rotation() const
Get the rotation component of the state.
Definition: SE3StateSpace.h:81