37 #include "ompl/base/spaces/SE2StateSpace.h"
38 #include "ompl/tools/config/MagicConstants.h"
63 virtual unsigned int getDimension(
void)
const
68 virtual void defaultCellSizes(
void)
82 registerDefaultProjection(
ProjectionEvaluatorPtr(dynamic_cast<ProjectionEvaluator*>(
new SE2DefaultProjection(
this))));
A state in SE(2): (x, y, yaw)
CompoundState StateType
Define the type of state allocated by this state space.
void allocStateComponents(CompoundState *state) const
Allocate the state components. Called by allocState(). Usually called by derived state spaces...
const T * as(void) const
Cast this instance to a desired type.
virtual void registerProjections(void)
Register the projections for this state space. Usually, this is at least the default projection...
virtual void freeState(State *state) const
Free the memory of the allocated state.
A state space representing SE(2)
A boost shared pointer wrapper for ompl::base::ProjectionEvaluator.
static const double PROJECTION_DIMENSION_SPLITS
When the cell sizes for a projection are automatically computed, this value defines the number of par...
Representation of a space in which planning can be performed. Topology specific sampling, interpolation and distance are defined.
boost::numeric::ublas::vector< double > EuclideanProjection
The datatype for state projections. This class contains a real vector.
virtual void freeState(State *state) const
Free the memory of the allocated state.
virtual State * allocState(void) const
Allocate a state that can store a point in the described space.
Definition of an abstract state.
double * values
The value of the actual vector in Rn
The definition of a state in Rn
const T * as(const unsigned int index) const
Cast a component of this instance to a desired type.
Abstract definition for a class computing projections to Rn. Implicit integer grids are imposed on th...