A state space representing SE(2) More...
#include <SE2StateSpace.h>
Classes | |
class | StateType |
A state in SE(2): (x, y, yaw) More... | |
Public Member Functions | |
void | setBounds (const RealVectorBounds &bounds) |
Set the bounds of this state space. This defines the range of the space in which sampling is performed. | |
const RealVectorBounds & | getBounds (void) const |
Get the bounds for this state 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 void | registerProjections (void) |
Register the projections for this state space. Usually, this is at least the default projection. These are implicit projections, set by the implementation of the state space. This is called by setup(). |
A state space representing SE(2)
Definition at line 50 of file SE2StateSpace.h.
const RealVectorBounds& ompl::base::SE2StateSpace::getBounds | ( | void | ) | const [inline] |
Get the bounds for this state space.
Definition at line 132 of file SE2StateSpace.h.
void ompl::base::SE2StateSpace::setBounds | ( | const RealVectorBounds & | bounds | ) | [inline] |
Set the bounds of this state space. This defines the range of the space in which sampling is performed.
Definition at line 126 of file SE2StateSpace.h.