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 setName(const std::string &name)
Set the name of the state space.
Definition: StateSpace.cpp:212
MORSE State. This is a compound state that allows accessing the properties of the bodies the state sp...
Definition: MorseStateSpace.h:53
A shared pointer wrapper for ompl::base::StateSampler.
void lock()
Lock this state space. This means no further spaces can be added as components. This function can be ...
void freeState(State *state) const override
Free the memory of the allocated state.
Definition: MorseStateSpace.cpp:133
A state space representing SO(3). The internal representation is done with quaternions. The distance between states is the angle between quaternions and interpolation is done with slerp.
Definition: SO3StateSpace.h:82
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...
void copyState(State *destination, const State *source) const override
Copy a state to another. The memory of source and destination should NOT overlap. ...
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
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:573
void writeState(const State *state) const
Set the parameters of the MORSE bodies to be the ones read from state.
Definition: MorseStateSpace.cpp:165
The definition of a state in SO(3) represented as a unit quaternion.
Definition: SO3StateSpace.h:90
bool satisfiesBounds(const State *state) const override
This function checks whether a state satisfies its bounds.
Definition: MorseStateSpace.cpp:94
StateSamplerPtr allocDefaultStateSampler() const override
Allocate an instance of the default uniform state sampler for this space.
Definition: MorseStateSpace.cpp:144
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
StateSamplerPtr allocDefaultStateSampler() const override
Allocate an instance of the default uniform state sampler for this space.
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
MorseEnvironmentPtr env_
Representation of the MORSE parameters OMPL needs to plan.
Definition: MorseStateSpace.h:131
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...
The lower and upper bounds for an Rn space.
Definition: RealVectorBounds.h:47
State * allocState() const override
Allocate a state that can store a point in the described space.
Definition: MorseStateSpace.cpp:126
void setLinearVelocityBounds(const RealVectorBounds &bounds)
Set the bounds for each of the linear velocity subspaces.
Definition: MorseStateSpace.cpp:114
void freeState(State *state) const override
Free the memory of the allocated state.
Number of state space types; To add new types, use values that are larger than the count...
Definition: StateSpaceTypes.h:74
void setPositionBounds(const RealVectorBounds &bounds)
Set the bounds for each of the position subspaces.
Definition: MorseStateSpace.cpp:108
A shared pointer wrapper for ompl::base::MorseEnvironment.
std::vector< StateSpacePtr > components_
The state spaces that make up the compound state space.
Definition: StateSpace.h:735
void setAngularVelocityBounds(const RealVectorBounds &bounds)
Set the bounds for each of the angular velocity subspaces.
Definition: MorseStateSpace.cpp:120
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