SE3StateSpace.h
void setXYZ(double x, double y, double z)
Set the X, Y and Z components of the state.
Definition: SE3StateSpace.h:230
const RealVectorBounds & getBounds() const
Get the bounds for this state space.
Definition: SE3StateSpace.h:225
void lock()
Lock this state space. This means no further spaces can be added as components. This function can be ...
Definition: StateSpace.cpp:1162
void registerProjections() override
Register the projections for this state space. Usually, this is at least the default projection....
Definition: SE3StateSpace.cpp:52
ompl::base::State StateType
Define the type of state allocated by this space.
Definition: StateSpace.h:139
const SO3StateSpace::StateType & rotation() const
Get the rotation component of the state.
Definition: SE3StateSpace.h:200
void freeState(State *state) const override
Free the memory of the allocated state.
Definition: SE3StateSpace.cpp:47
ompl::base::CompoundState StateType
Define the type of state allocated by this state space.
Definition: StateSpace.h:638
State * allocState() const override
Allocate a state that can store a point in the described space.
Definition: SE3StateSpace.cpp:40
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:219
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:870