MorseStateSpace.h
79 MorseStateSpace(const MorseEnvironmentPtr &env, double positionWeight = 1.0, double linVelWeight = 0.5,
void readState(State *state) const
Read the parameters of the MORSE bodies and store them in state.
Definition: MorseStateSpace.cpp:154
State * allocState() const override
Allocate a state that can store a point in the described space.
Definition: MorseStateSpace.cpp:126
void setPositionBounds(const RealVectorBounds &bounds)
Set the bounds for each of the position subspaces.
Definition: MorseStateSpace.cpp:108
const MorseEnvironmentPtr & getEnvironment() const
Get the MORSE environment this state space corresponds to.
Definition: MorseStateSpace.h:183
void interpolate(const State *from, const State *to, double t, State *state) const override
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state....
Definition: MorseStateSpace.cpp:139
StateSamplerPtr allocStateSampler() const override
Allocate an instance of the state sampler for this space. This sampler will be allocated with the sam...
Definition: MorseStateSpace.cpp:149
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.
Definition: MorseStateSpace.cpp:42
StateSamplerPtr allocDefaultStateSampler() const override
Allocate an instance of the default uniform state sampler for this space.
Definition: MorseStateSpace.cpp:144
A shared pointer wrapper for ompl::base::MorseEnvironment.
bool satisfiesBounds(const State *state) const override
This function checks whether a state satisfies its bounds.
Definition: MorseStateSpace.cpp:94
ompl::base::CompoundState StateType
Define the type of state allocated by this state space.
Definition: StateSpace.h:641
unsigned int getNrBodies() const
Get the number of bodies this state space represents.
Definition: MorseStateSpace.h:189
void setLinearVelocityBounds(const RealVectorBounds &bounds)
Set the bounds for each of the linear velocity subspaces.
Definition: MorseStateSpace.cpp:114
A shared pointer wrapper for ompl::base::StateSampler.
void setAngularVelocityBounds(const RealVectorBounds &bounds)
Set the bounds for each of the angular velocity subspaces.
Definition: MorseStateSpace.cpp:120
void writeState(const State *state) const
Set the parameters of the MORSE bodies to be the ones read from state.
Definition: MorseStateSpace.cpp:165
void freeState(State *state) const override
Free the memory of the allocated state.
Definition: MorseStateSpace.cpp:133
void copyState(State *destination, const State *source) const override
Copy a state to another. The memory of source and destination should NOT overlap.
Definition: MorseStateSpace.cpp:89
Main namespace. Contains everything in this library.
Definition: MultiLevelPlanarManipulatorDemo.cpp:65
MorseEnvironmentPtr env_
Representation of the MORSE parameters OMPL needs to plan.
Definition: MorseStateSpace.h:227