37 #ifndef OMPL_EXTENSION_OPENDE_STATE_SPACE_
38 #define OMPL_EXTENSION_OPENDE_STATE_SPACE_
40 #include "ompl/base/StateSpace.h"
41 #include "ompl/base/spaces/RealVectorStateSpace.h"
42 #include "ompl/base/spaces/SO3StateSpace.h"
43 #include "ompl/extensions/opende/OpenDEEnvironment.h"
78 return as<base::RealVectorStateSpace::StateType>(body * 4)->values;
84 return as<base::RealVectorStateSpace::StateType>(body * 4)->values;
90 return *as<base::SO3StateSpace::StateType>(body * 4 + 3);
96 return *as<base::SO3StateSpace::StateType>(body * 4 + 3);
102 return as<base::RealVectorStateSpace::StateType>(body * 4 + 1)->values;
108 return as<base::RealVectorStateSpace::StateType>(body * 4 + 1)->values;
114 return as<base::RealVectorStateSpace::StateType>(body * 4 + 2)->values;
120 return as<base::RealVectorStateSpace::StateType>(body * 4 + 2)->values;
149 double positionWeight = 1.0,
double linVelWeight = 0.5,
150 double angVelWeight = 0.5,
double orientationWeight = 1.0);
165 return env_->stateBodies_.size();
Index of bit in StateType::collision indicating whether it is known if a state is in collision or not...
const double * getBodyPosition(unsigned int body) const
Get the position (x, y, z) of the body at index body.
Index of bit in StateType::collision indicating whether a state is valid or not. Initially the value ...
Definition of a compound state.
void setVolumeBounds(const base::RealVectorBounds &bounds)
Set the bounds for each of the position subspaces.
const double * getBodyAngularVelocity(unsigned int body) const
Get the angular velocity (x, y, z) of the body at index body.
double * getBodyLinearVelocity(unsigned int body)
Get the linear velocity (x, y, z) of the body at index body.
base::SO3StateSpace::StateType & getBodyRotation(unsigned int body)
Get the quaternion of the body at index body.
virtual void readState(base::State *state) const
Read the parameters of the OpenDE bodies and store them in state.
A boost shared pointer wrapper for ompl::base::StateSampler.
Index of bit in StateType::collision indicating whether a state is in collision or not...
void setAngularVelocityBounds(const base::RealVectorBounds &bounds)
Set the bounds for each of the angular velocity subspaces.
CompoundState StateType
Define the type of state allocated by this state space.
virtual void writeState(const base::State *state) const
Set the parameters of the OpenDE bodies to be the ones read from state. The code will technically wor...
const double * getBodyLinearVelocity(unsigned int body) const
Get the linear velocity (x, y, z) of the body at index body.
OpenDE State. This is a compound state that allows accessing the properties of the bodies the state s...
const OpenDEEnvironmentPtr & getEnvironment(void) const
Get the OpenDE environment this state space corresponds to.
double * getBodyPosition(unsigned int body)
Get the position (x, y, z) of the body at index body.
bool satisfiesBoundsExceptRotation(const StateType *state) const
This is a convenience function provided for optimization purposes. It checks whether a state satisfie...
virtual bool evaluateCollision(const base::State *source) const
Fill the OpenDEStateSpace::STATE_COLLISION_VALUE_BIT of StateType::collision member of a state...
unsigned int getNrBodies(void) const
Get the number of bodies state is maintained for.
State space representing OpenDE states.
A space to allow the composition of state spaces.
virtual base::State * allocState(void) const
Allocate a state that can store a point in the described space.
The definition of a state in SO(3) represented as a unit quaternion.
OpenDEStateSpace(const OpenDEEnvironmentPtr &env, double positionWeight=1.0, double linVelWeight=0.5, double angVelWeight=0.5, double orientationWeight=1.0)
Construct a state space representing OpenDE states.
virtual void copyState(base::State *destination, const base::State *source) const
Copy a state to another. The memory of source and destination should NOT overlap. ...
Index of bit in StateType::collision indicating whether it is known if a state is in valid or not...
Definition of an abstract state.
virtual void freeState(base::State *state) const
Free the memory of the allocated state.
virtual void interpolate(const base::State *from, const base::State *to, const double t, base::State *state) const
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state...
The lower and upper bounds for an Rn space.
virtual base::StateSamplerPtr allocDefaultStateSampler(void) const
Allocate an instance of the default uniform state sampler for this space.
void setDefaultBounds(void)
By default, the volume bounds enclosing the geometry of the environment are computed to include all o...
void setLinearVelocityBounds(const base::RealVectorBounds &bounds)
Set the bounds for each of the linear velocity subspaces.
double * getBodyAngularVelocity(unsigned int body)
Get the angular velocity (x, y, z) of the body at index body.
const base::SO3StateSpace::StateType & getBodyRotation(unsigned int body) const
Get the quaternion of the body at index body.
virtual base::StateSamplerPtr allocStateSampler(void) const
Allocate an instance of the state sampler for this space. This sampler will be allocated with the sam...
int collision
Flag containing information about state validity.
A boost shared pointer wrapper for ompl::control::OpenDEEnvironment.
OpenDEEnvironmentPtr env_
Representation of the OpenDE parameters OMPL needs to plan.