OpenDEStateSpace.h
159 OpenDEStateSpace(OpenDEEnvironmentPtr env, double positionWeight = 1.0, double linVelWeight = 0.5,
OpenDEEnvironmentPtr env_
Representation of the OpenDE parameters OMPL needs to plan.
Definition: OpenDEStateSpace.h:323
const double * getBodyPosition(unsigned int body) const
Get the position (x, y, z) of the body at index body.
Definition: OpenDEStateSpace.h:181
void copyState(base::State *destination, const base::State *source) const override
Copy a state to another. The memory of source and destination should NOT overlap.
Definition: OpenDEStateSpace.cpp:156
@ STATE_COLLISION_VALUE_BIT
Index of bit in StateType::collision indicating whether a state is in collision or not....
Definition: OpenDEStateSpace.h:192
OpenDEStateSpace(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.
Definition: OpenDEStateSpace.cpp:43
void setAngularVelocityBounds(const base::RealVectorBounds &bounds)
Set the bounds for each of the angular velocity subspaces.
Definition: OpenDEStateSpace.cpp:239
virtual void readState(base::State *state) const
Read the parameters of the OpenDE bodies and store them in state.
Definition: OpenDEStateSpace.cpp:321
void freeState(base::State *state) const override
Free the memory of the allocated state.
Definition: OpenDEStateSpace.cpp:252
OpenDE State. This is a compound state that allows accessing the properties of the bodies the state s...
Definition: OpenDEStateSpace.h:175
base::State * allocState() const override
Allocate a state that can store a point in the described space.
Definition: OpenDEStateSpace.cpp:245
A shared pointer wrapper for ompl::control::OpenDEEnvironment.
const base::SO3StateSpace::StateType & getBodyRotation(unsigned int body) const
Get the quaternion of the body at index body.
Definition: OpenDEStateSpace.h:193
void setDefaultBounds()
By default, the volume bounds enclosing the geometry of the environment are computed to include all o...
Definition: OpenDEStateSpace.cpp:69
@ STATE_COLLISION_KNOWN_BIT
Index of bit in StateType::collision indicating whether it is known if a state is in collision or not...
Definition: OpenDEStateSpace.h:186
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...
Definition: OpenDEStateSpace.cpp:356
void interpolate(const base::State *from, const base::State *to, double t, base::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: OpenDEStateSpace.cpp:260
const double * getBodyLinearVelocity(unsigned int body) const
Get the linear velocity (x, y, z) of the body at index body.
Definition: OpenDEStateSpace.h:205
ompl::base::State StateType
Define the type of state allocated by this space.
Definition: StateSpace.h:142
const OpenDEEnvironmentPtr & getEnvironment() const
Get the OpenDE environment this state space corresponds to.
Definition: OpenDEStateSpace.h:261
@ STATE_VALIDITY_VALUE_BIT
Index of bit in StateType::collision indicating whether a state is valid or not. Initially the value ...
Definition: OpenDEStateSpace.h:202
base::StateSamplerPtr allocDefaultStateSampler() const override
Allocate an instance of the default uniform state sampler for this space.
Definition: OpenDEStateSpace.cpp:307
base::StateSamplerPtr allocStateSampler() const override
Allocate an instance of the state sampler for this space. This sampler will be allocated with the sam...
Definition: OpenDEStateSpace.cpp:313
bool satisfiesBoundsExceptRotation(const StateType *state) const
This is a convenience function provided for optimization purposes. It checks whether a state satisfie...
Definition: OpenDEStateSpace.cpp:218
void setVolumeBounds(const base::RealVectorBounds &bounds)
Set the bounds for each of the position subspaces.
Definition: OpenDEStateSpace.cpp:227
virtual bool evaluateCollision(const base::State *state) const
Fill the OpenDEStateSpace::STATE_COLLISION_VALUE_BIT of StateType::collision member of a state,...
Definition: OpenDEStateSpace.cpp:202
ompl::base::CompoundState StateType
Define the type of state allocated by this state space.
Definition: StateSpace.h:641
const double * getBodyAngularVelocity(unsigned int body) const
Get the angular velocity (x, y, z) of the body at index body.
Definition: OpenDEStateSpace.h:217
void setLinearVelocityBounds(const base::RealVectorBounds &bounds)
Set the bounds for each of the linear velocity subspaces.
Definition: OpenDEStateSpace.cpp:233
@ STATE_VALIDITY_KNOWN_BIT
Index of bit in StateType::collision indicating whether it is known if a state is in valid or not....
Definition: OpenDEStateSpace.h:196
unsigned int getNrBodies() const
Get the number of bodies state is maintained for.
Definition: OpenDEStateSpace.h:267
Main namespace. Contains everything in this library.
Definition: MultiLevelPlanarManipulatorDemo.cpp:65
The lower and upper bounds for an Rn space.
Definition: RealVectorBounds.h:111