37 #ifndef OMPL_EXTENSION_MORSE_STATE_SPACE_
38 #define OMPL_EXTENSION_MORSE_STATE_SPACE_
40 #include "ompl/base/StateSpace.h"
41 #include "ompl/extensions/morse/MorseEnvironment.h"
78 double positionWeight = 1.0,
double linVelWeight = 0.5,
79 double angVelWeight = 0.5,
double orientationWeight = 1.0);
94 return env_->rigidBodies_;
MORSE State. This is a compound state that allows accessing the properties of the bodies the state sp...
Definition of a compound state.
State space representing MORSE states.
A boost shared pointer wrapper for ompl::base::StateSampler.
void interpolate(const State *from, const State *to, const double t, State *state) const
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state...
void readState(State *state) const
Read the parameters of the MORSE bodies and store them in state.
State * allocState(void) const
Allocate a state that can store a point in the described space.
CompoundState StateType
Define the type of state allocated by this state space.
void freeState(State *state) const
Free the memory of the allocated state.
unsigned int getNrBodies(void) const
Get the number of bodies this state space represents.
A space to allow the composition of state spaces.
StateSamplerPtr allocStateSampler(void) const
Allocate an instance of the state sampler for this space. This sampler will be allocated with the sam...
Definition of an abstract state.
void writeState(const State *state) const
Set the parameters of the MORSE bodies to be the ones read from state.
MorseEnvironmentPtr env_
Representation of the MORSE parameters OMPL needs to plan.
bool satisfiesBounds(const State *state) const
This function checks whether a state satisfies its bounds.
The lower and upper bounds for an Rn space.
StateSamplerPtr allocDefaultStateSampler(void) const
Allocate an instance of the default uniform state sampler for this space.
void setBounds(void)
Set the bounds given by the MorseEnvironment.
void setLinearVelocityBounds(const RealVectorBounds &bounds)
Set the bounds for each of the linear velocity subspaces.
void setPositionBounds(const RealVectorBounds &bounds)
Set the bounds for each of the position subspaces.
A boost shared pointer wrapper for ompl::base::MorseEnvironment.
void copyState(State *destination, const State *source) const
Copy a state to another. The memory of source and destination should NOT overlap. ...
void setAngularVelocityBounds(const RealVectorBounds &bounds)
Set the bounds for each of the angular velocity subspaces.
MorseStateSpace(const MorseEnvironmentPtr &env, double positionWeight=1.0, double linVelWeight=0.5, double angVelWeight=0.5, double orientationWeight=1.0)
Construct a state space representing MORSE states.
const MorseEnvironmentPtr & getEnvironment(void) const
Get the MORSE environment this state space corresponds to.