SE2StateSpace.cpp
78 memcpy(&projection(0), state->as<SE2StateSpace::StateType>()->as<RealVectorStateSpace::StateType>(0)->values, 2 * sizeof(double));
82 registerDefaultProjection(ProjectionEvaluatorPtr(dynamic_cast<ProjectionEvaluator*>(new SE2DefaultProjection(this))));
virtual void registerProjections()
Register the projections for this state space. Usually, this is at least the default projection...
Definition: SE2StateSpace.cpp:53
CompoundState StateType
Define the type of state allocated by this state space.
Definition: StateSpace.h:549
void allocStateComponents(CompoundState *state) const
Allocate the state components. Called by allocState(). Usually called by derived state spaces...
Definition: StateSpace.cpp:1130
virtual void freeState(State *state) const
Free the memory of the allocated state.
Definition: SE2StateSpace.cpp:48
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...
Definition: MagicConstants.h:57
Representation of a space in which planning can be performed. Topology specific sampling, interpolation and distance are defined.
Definition: StateSpace.h:73
boost::numeric::ublas::vector< double > EuclideanProjection
The datatype for state projections. This class contains a real vector.
Definition: ProjectionEvaluator.h:62
virtual void freeState(State *state) const
Free the memory of the allocated state.
Definition: StateSpace.cpp:1137
virtual State * allocState() const
Allocate a state that can store a point in the described space.
Definition: SE2StateSpace.cpp:41
The definition of a state in Rn
Definition: RealVectorStateSpace.h:80
const T * as(const unsigned int index) const
Cast a component of this instance to a desired type.
Definition: State.h:109
Abstract definition for a class computing projections to Rn. Implicit integer grids are imposed on th...
Definition: ProjectionEvaluator.h:138