37 #include "ompl/extensions/morse/MorseStateSpace.h"
38 #include "ompl/base/spaces/RealVectorStateSpace.h"
39 #include "ompl/base/spaces/SO3StateSpace.h"
40 #include "ompl/base/spaces/DiscreteStateSpace.h"
42 #include <boost/lexical_cast.hpp>
45 double angVelWeight,
double orientationWeight) :
50 for (
unsigned int i = 0 ; i <
env_->rigidBodies_; ++i)
52 std::string body =
":B" + boost::lexical_cast<std::string>(i);
77 for (
unsigned int i = 0; i < 3; i++)
79 pbounds.low[i] = env_->positionBounds_[2*i];
80 pbounds.high[i] = env_->positionBounds_[2*i+1];
81 lbounds.low[i] = env_->linvelBounds_[2*i];
82 lbounds.high[i] = env_->linvelBounds_[2*i+1];
83 abounds.
low[i] = env_->angvelBounds_[2*i];
84 abounds.
high[i] = env_->angvelBounds_[2*i+1];
86 setPositionBounds(pbounds);
87 setLinearVelocityBounds(lbounds);
88 setAngularVelocityBounds(abounds);
98 for (
unsigned int i = 0 ; i < componentCount_ ; ++i)
112 for (
unsigned int i = 0 ; i < env_->rigidBodies_; ++i)
113 components_[i * 4]->as<RealVectorStateSpace>()->setBounds(bounds);
118 for (
unsigned int i = 0 ; i < env_->rigidBodies_; ++i)
119 components_[i * 4 + 1]->as<RealVectorStateSpace>()->setBounds(bounds);
124 for (
unsigned int i = 0 ; i < env_->rigidBodies_; ++i)
125 components_[i * 4 + 2]->as<RealVectorStateSpace>()->setBounds(bounds);
131 allocStateComponents(state);
132 return static_cast<State*
>(state);
158 env_->readState(state);
159 for (
unsigned int i = 0; i < env_->rigidBodies_*4; i+=4)
169 env_->writeState(state);
void setName(const std::string &name)
Set the name of the state space.
int type_
A type assigned for this state space.
MORSE State. This is a compound state that allows accessing the properties of the bodies the state sp...
Definition of a compound state.
virtual void copyState(State *destination, const State *source) const
Copy a state to another. The memory of source and destination should NOT overlap. ...
std::vector< double > low
Lower bound.
A boost shared pointer wrapper for ompl::base::StateSpace.
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.
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.
State * allocState(void) const
Allocate a state that can store a point in the described space.
virtual StateSamplerPtr allocDefaultStateSampler(void) const
Allocate an instance of the default uniform state sampler for this space.
const T * as(void) const
Cast this instance to a desired type.
void freeState(State *state) const
Free the memory of the allocated state.
virtual 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...
A space to allow the composition of state spaces.
The definition of a state in SO(3) represented as a unit quaternion.
const std::string & getName(void) const
Get the name of the state space.
std::vector< double > high
Upper bound.
StateSamplerPtr allocStateSampler(void) const
Allocate an instance of the state sampler for this space. This sampler will be allocated with the sam...
A state space representing Rn. The distance function is the L2 norm.
virtual void freeState(State *state) const
Free the memory of the allocated state.
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.
void lock(void)
Lock this state space. This means no further spaces can be added as components. This function can be ...
MorseEnvironmentPtr env_
Representation of the MORSE parameters OMPL needs to plan.
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...
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.
State ** components
The components that make up a compound state.
void setLinearVelocityBounds(const RealVectorBounds &bounds)
Set the bounds for each of the linear velocity subspaces.
A space representing discrete states; i.e. there are a small number of discrete states the system can...
Number of state space types; To add new types, use values that are larger than the count...
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. ...
std::vector< StateSpacePtr > components_
The state spaces that make up the compound state space.
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.