ompl::base::MorseStateSpace Class Reference
State space representing MORSE states. More...
#include <ompl/extensions/morse/MorseStateSpace.h>
Inheritance diagram for ompl::base::MorseStateSpace:

Classes | |
class | StateType |
MORSE State. This is a compound state that allows accessing the properties of the bodies the state space is constructed for. More... | |
Public Member Functions | |
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 () const |
Get the MORSE environment this state space corresponds to. | |
unsigned int | getNrBodies () const |
Get the number of bodies this state space represents. | |
void | setBounds () |
Set the bounds given by the MorseEnvironment. | |
void | setPositionBounds (const RealVectorBounds &bounds) |
Set the bounds for each of the position subspaces. | |
void | setLinearVelocityBounds (const RealVectorBounds &bounds) |
Set the bounds for each of the linear velocity subspaces. | |
void | setAngularVelocityBounds (const RealVectorBounds &bounds) |
Set the bounds for each of the angular velocity subspaces. | |
void | readState (State *state) const |
Read the parameters of the MORSE bodies and store them in state. | |
void | writeState (const State *state) const |
Set the parameters of the MORSE bodies to be the ones read from state. | |
bool | satisfiesBounds (const State *state) const |
This function checks whether a state satisfies its bounds. | |
State * | allocState () const |
Allocate a state that can store a point in the described space. | |
void | freeState (State *state) const |
void | copyState (State *destination, const State *source) const |
void | interpolate (const State *from, const State *to, const double t, State *state) const |
StateSamplerPtr | allocDefaultStateSampler () const |
Allocate an instance of the default uniform state sampler for this space. | |
StateSamplerPtr | allocStateSampler () const |
Allocate an instance of the state sampler for this space. This sampler will be allocated with the sampler allocator that was previously specified by setStateSamplerAllocator() or, if no sampler allocator was specified, allocDefaultStateSampler() is called. | |
Protected Attributes | |
MorseEnvironmentPtr | env_ |
Representation of the MORSE parameters OMPL needs to plan. |
Detailed Description
State space representing MORSE states.
Definition at line 49 of file MorseStateSpace.h.
Constructor & Destructor Documentation
ompl::base::MorseStateSpace::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.
This will be a compound state space with 4 components for each body in env.stateBodies_. The 4 subspaces constructed for each body are: position (R3), linear velocity (R3), angular velocity (R3) and orientation (SO(3)). Default bounds are set by calling setDefaultBounds().
- Parameters:
-
env the environment to construct the state space for positionWeight the weight to pass to CompoundStateSpace::addSubspace() for position subspaces linVelWeight the weight to pass to CompoundStateSpace::addSubspace() for linear velocity subspaces angVelWeight the weight to pass to CompoundStateSpace::addSubspace() for angular velocity subspaces orientationWeight the weight to pass to CompoundStateSpace::addSubspace() for orientation subspaces
Definition at line 44 of file MorseStateSpace.cpp.
The documentation for this class was generated from the following files:
- ompl/extensions/morse/MorseStateSpace.h
- ompl/extensions/morse/src/MorseStateSpace.cpp