ompl::control::ODEStateSpace Class Reference

State space representing ODE states. More...

#include <ODEStateSpace.h>

Inheritance diagram for ompl::control::ODEStateSpace:
Inheritance graph
[legend]

List of all members.

Classes

class  StateType
 ODE State. This is a compound state that allows accessing the properties of the bodies the state space is constructed for. More...

Public Types

enum  { STATE_COLLISION_KNOWN_BIT = 0, STATE_COLLISION_VALUE_BIT = 1, STATE_VALIDITY_KNOWN_BIT = 2, STATE_VALIDITY_VALUE_BIT = 3 }

Public Member Functions

virtual base::StateallocState (void) const
 Allocate a state that can store a point in the described space.
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.
virtual bool evaluateCollision (const base::State *source) const
 Fill the ODEStateSpace::STATE_COLLISION_VALUE_BIT of StateType::collision member of a state, if unspecified. Return the value value of that bit.
virtual void freeState (base::State *state) const
 Free the memory of the allocated state.
const ODEEnvironmentPtrgetEnvironment (void) const
 Get the ODE environment this state space corresponds to.
unsigned int getNrBodies (void) const
 Get the number of bodies state is maintained for.
 ODEStateSpace (const ODEEnvironmentPtr &env, double positionWeight=1.0, double linVelWeight=0.5, double angVelWeight=0.5, double orientationWeight=1.0)
 Construct a state space representing ODE states.
virtual void readState (base::State *state) const
 Read the parameters of the ODE bodies and store them in state.
bool satisfiesBoundsExceptRotation (const StateType *state) const
 This is a convenience function provided for optimization purposes. It checks whether a state satisfies its bounds. Typically, in the process of simulation the rotations remain valid (very slightly out of bounds), so there is no point in updating or checking them. This function checks all other bounds (position, linear and agular velocities).
void setAngularVelocityBounds (const base::RealVectorBounds &bounds)
 Set the bounds for each of the angular velocity subspaces.
void setDefaultBounds (void)
 By default, the volume bounds enclosing the geometry of the environment are computed to include all objects in the spaces collision checking is performed (env.collisionSpaces_). The linear and angular velocity bounds are set as -1 to 1 for each dimension.
void setLinearVelocityBounds (const base::RealVectorBounds &bounds)
 Set the bounds for each of the linear velocity subspaces.
void setVolumeBounds (const base::RealVectorBounds &bounds)
 Set the bounds for each of the position subspaces.
virtual void writeState (const base::State *state) const
 Set the parameters of the ODE bodies to be the ones read from state. The code will technically work if this function is called from multiple threads simultaneously, but the results are unpredictable.
virtual ~ODEStateSpace (void)

Protected Attributes

ODEEnvironmentPtr env_
 Representation of the ODE parameters OMPL needs to plan.

Detailed Description

State space representing ODE states.

Definition at line 51 of file ODEStateSpace.h.


Member Enumeration Documentation

anonymous enum
Enumerator:
STATE_COLLISION_KNOWN_BIT 

Index of bit in StateType::collision indicating whether it is known if a state is in collision or not. Initially this is 0. The value of this bit is updated by ODEStateSpace::evaluateCollision() and ODEControlSpace::propagate().

STATE_COLLISION_VALUE_BIT 

Index of bit in StateType::collision indicating whether a state is in collision or not. Initially the value of this field is unspecified. The value gains meaning (1 or 0) when ODEStateSpace::STATE_COLLISION_KNOWN_BIT becomes 1. The value of this bit is updated by ODEStateSpace::evaluateCollision() and ODEControlSpace::propagate(). A value of 1 implies that there is no collision for which ODEEnvironment::isValidCollision() returns false.

STATE_VALIDITY_KNOWN_BIT 

Index of bit in StateType::collision indicating whether it is known if a state is in valid or not. Initially this is 0. The value of this bit is updated by ODEStateValidityChecker::isValid(). This bit is only used if the ODEStateValidityChecker is used.

STATE_VALIDITY_VALUE_BIT 

Index of bit in StateType::collision indicating whether a state is valid or not. Initially the value of this field is unspecified. The value gains meaning (1 or 0) when ODEStateSpace::STATE_VALIDITY_KNOWN_BIT becomes 1. The value of this bit is updated by ODEEnvironment::isValid(). A value of 1 implies that a state is valid. This bit is only used if the ODEStateValidityChecker is used.

Definition at line 55 of file ODEStateSpace.h.


Constructor & Destructor Documentation

ompl::control::ODEStateSpace::ODEStateSpace ( const ODEEnvironmentPtr env,
double  positionWeight = 1.0,
double  linVelWeight = 0.5,
double  angVelWeight = 0.5,
double  orientationWeight = 1.0 
)

Construct a state space representing ODE states.

This will be a compound state space with 4 components for each body in env.stateBodies_. The 4 subspaces constructed for each body are: position (R3), linear velocity (R3), angular velocity (R3) and orientation (SO(3)). Default bounds are set by calling setDefaultBounds().

Parameters:
env the environment to construct the state space for
positionWeight the weight to pass to CompoundStateSpace::addSubSpace() for position subspaces
linVelWeight the weight to pass to CompoundStateSpace::addSubSpace() for linear velocity subspaces
angVelWeight the weight to pass to CompoundStateSpace::addSubSpace() for angular velocity subspaces
orientationWeight the weight to pass to CompoundStateSpace::addSubSpace() for orientation subspaces
virtual ompl::control::ODEStateSpace::~ODEStateSpace ( void   )  [inline, virtual]

Definition at line 152 of file ODEStateSpace.h.


Member Function Documentation

virtual base::State* ompl::control::ODEStateSpace::allocState ( void   )  const [virtual]

Allocate a state that can store a point in the described space.

Reimplemented from ompl::base::CompoundStateSpace.

virtual void ompl::control::ODEStateSpace::copyState ( base::State destination,
const base::State source 
) const [virtual]

Copy a state to another. The memory of source and destination should NOT overlap.

Reimplemented from ompl::base::CompoundStateSpace.

virtual bool ompl::control::ODEStateSpace::evaluateCollision ( const base::State source  )  const [virtual]

Fill the ODEStateSpace::STATE_COLLISION_VALUE_BIT of StateType::collision member of a state, if unspecified. Return the value value of that bit.

virtual void ompl::control::ODEStateSpace::freeState ( base::State state  )  const [virtual]

Free the memory of the allocated state.

Reimplemented from ompl::base::CompoundStateSpace.

const ODEEnvironmentPtr& ompl::control::ODEStateSpace::getEnvironment ( void   )  const [inline]

Get the ODE environment this state space corresponds to.

Definition at line 157 of file ODEStateSpace.h.

unsigned int ompl::control::ODEStateSpace::getNrBodies ( void   )  const [inline]

Get the number of bodies state is maintained for.

Definition at line 163 of file ODEStateSpace.h.

virtual void ompl::control::ODEStateSpace::readState ( base::State state  )  const [virtual]

Read the parameters of the ODE bodies and store them in state.

bool ompl::control::ODEStateSpace::satisfiesBoundsExceptRotation ( const StateType state  )  const

This is a convenience function provided for optimization purposes. It checks whether a state satisfies its bounds. Typically, in the process of simulation the rotations remain valid (very slightly out of bounds), so there is no point in updating or checking them. This function checks all other bounds (position, linear and agular velocities).

void ompl::control::ODEStateSpace::setAngularVelocityBounds ( const base::RealVectorBounds bounds  ) 

Set the bounds for each of the angular velocity subspaces.

void ompl::control::ODEStateSpace::setDefaultBounds ( void   ) 

By default, the volume bounds enclosing the geometry of the environment are computed to include all objects in the spaces collision checking is performed (env.collisionSpaces_). The linear and angular velocity bounds are set as -1 to 1 for each dimension.

void ompl::control::ODEStateSpace::setLinearVelocityBounds ( const base::RealVectorBounds bounds  ) 

Set the bounds for each of the linear velocity subspaces.

void ompl::control::ODEStateSpace::setVolumeBounds ( const base::RealVectorBounds bounds  ) 

Set the bounds for each of the position subspaces.

virtual void ompl::control::ODEStateSpace::writeState ( const base::State state  )  const [virtual]

Set the parameters of the ODE bodies to be the ones read from state. The code will technically work if this function is called from multiple threads simultaneously, but the results are unpredictable.


Member Data Documentation

Representation of the ODE parameters OMPL needs to plan.

Definition at line 214 of file ODEStateSpace.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


ompl
Author(s): Ioan Sucan/isucan@rice.edu, Mark Moll/mmoll@rice.edu, Lydia Kavraki/kavraki@rice.edu
autogenerated on Fri Jan 11 09:34:02 2013