MorseStateSpace.cpp
42 ompl::base::MorseStateSpace::MorseStateSpace(const MorseEnvironmentPtr &env, double positionWeight, double linVelWeight,
101 if (!components_[i]->satisfiesBounds(state->as<CompoundStateSpace::StateType>()->components[i]))
139 void ompl::base::MorseStateSpace::interpolate(const State *from, const State *to, const double t, State *state) const
void readState(State *state) const
Read the parameters of the MORSE bodies and store them in state.
Definition: MorseStateSpace.cpp:154
A space to allow the composition of state spaces.
Definition: StateSpace.h:637
@ STATE_SPACE_TYPE_COUNT
Number of state space types; To add new types, use values that are larger than the count.
Definition: StateSpaceTypes.h:188
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: StateSpace.cpp:1109
StateSamplerPtr allocDefaultStateSampler() const override
Allocate an instance of the default uniform state sampler for this space.
Definition: StateSpace.cpp:1118
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
void lock()
Lock this state space. This means no further spaces can be added as components. This function can be ...
Definition: StateSpace.cpp:1163
The definition of a state in SO(3) represented as a unit quaternion.
Definition: SO3StateSpace.h:154
A state space representing SO(3). The internal representation is done with quaternions....
Definition: SO3StateSpace.h:146
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
void freeState(State *state) const override
Free the memory of the allocated state.
Definition: StateSpace.cpp:1154
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
void copyState(State *destination, const State *source) const override
Copy a state to another. The memory of source and destination should NOT overlap.
Definition: StateSpace.cpp:1030
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.
MORSE State. This is a compound state that allows accessing the properties of the bodies the state sp...
Definition: MorseStateSpace.h:149
bool satisfiesBounds(const State *state) const override
This function checks whether a state satisfies its bounds.
Definition: MorseStateSpace.cpp:94
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 addSubspace(const StateSpacePtr &component, double weight)
Adds a new state space as part of the compound state space. For computing distances within the compou...
Definition: StateSpace.cpp:871
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
std::vector< StateSpacePtr > components_
The state spaces that make up the compound state space.
Definition: StateSpace.h:799
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
The lower and upper bounds for an Rn space.
Definition: RealVectorBounds.h:111
MorseEnvironmentPtr env_
Representation of the MORSE parameters OMPL needs to plan.
Definition: MorseStateSpace.h:227