SE2StateSpace.h
void setName(const std::string &name)
Set the name of the state space.
Definition: StateSpace.cpp:212
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: SE2StateSpace.h:118
State * allocState() const override
Allocate a state that can store a point in the described space.
Definition: SE2StateSpace.cpp:41
void lock()
Lock this state space. This means no further spaces can be added as components. This function can be ...
void setYaw(double yaw)
Set the yaw component of the state. This is the rotation in plane, with respect to the Z axis...
Definition: SE2StateSpace.h:100
double getYaw() const
Get the yaw component of the state. This is the rotation in plane, with respect to the Z axis...
Definition: SE2StateSpace.h:73
A space to allow the composition of state spaces.
Definition: StateSpace.h:573
void setXY(double x, double y)
Set the X and Y components of the state.
Definition: SE2StateSpace.h:91
void freeState(State *state) const override
Free the memory of the allocated state.
Definition: SE2StateSpace.cpp:48
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...
The lower and upper bounds for an Rn space.
Definition: RealVectorBounds.h:47
void registerProjections() override
Register the projections for this state space. Usually, this is at least the default projection...
Definition: SE2StateSpace.cpp:53
const RealVectorBounds & getBounds() const
Get the bounds for this state space.
Definition: SE2StateSpace.h:124