ompl::control::ODESimpleSetup Class Reference

Create the set of classes typically needed to solve a control problem when forward propagation is computed with ODE. More...

#include <ODESimpleSetup.h>

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

List of all members.

Public Member Functions

base::ScopedState< ODEStateSpacegetCurrentState (void) const
 Get the current ODE state (read parameters from ODE bodies).
const ODEEnvironmentPtrgetEnvironment (void) const
 Get the ODE environment associated to the state and control spaces.
 ODESimpleSetup (const ODEEnvironmentPtr &env)
 The control space is assumed to be ODEControlSpace. The state space is assumed to be ODEStateSpace. Constructor only needs the ODE environment.
 ODESimpleSetup (const base::StateSpacePtr &space)
 The control space is assumed to be ODEControlSpace. Constructor only needs the state space.
 ODESimpleSetup (const ControlSpacePtr &space)
 Constructor needs the control space needed for planning.
void playPath (const base::PathPtr &path, double timeFactor=1.0) const
 Set the ODE world to the states that are contained in a given path, sequentially. Using timeFactor, the speed at which this sequence is iterated through is altered.
void playSolutionPath (double timeFactor=1.0) const
 Call playPath() on the solution path, if one is available.
void setAngularVelocityBounds (const base::RealVectorBounds &bounds)
 Set the bounds for the angular velocity.
void setCurrentState (const base::State *state)
 Set the current ODE state (set parameters for ODE bodies).
void setCurrentState (const base::ScopedState<> &state)
 Set the current ODE state (set parameters for ODE bodies).
void setLinearVelocityBounds (const base::RealVectorBounds &bounds)
 Set the bounds for the linear velocity.
virtual void setup (void)
 This method will create the necessary classes for planning. The solve() method will call this function automatically.
void setVolumeBounds (const base::RealVectorBounds &bounds)
 Set the bounds for the planning volume.
base::PathPtr simulate (unsigned int steps) const
 Simulate the ODE environment forward for steps simulation steps, using the null control (ompl::control::ControlSpace::nullControl()). Construct a path representing this action.
base::PathPtr simulateControl (const Control *control, unsigned int steps) const
 Simulate the ODE environment forward for steps simulation steps, using the control control. Construct a path representing this action.
base::PathPtr simulateControl (const double *control, unsigned int steps) const
 Simulate the ODE environment forward for steps simulation steps, using the control control. Construct a path representing this action.
virtual ~ODESimpleSetup (void)

Private Member Functions

void useEnvParams (void)

Detailed Description

Create the set of classes typically needed to solve a control problem when forward propagation is computed with ODE.

Definition at line 47 of file ODESimpleSetup.h.


Constructor & Destructor Documentation

ompl::control::ODESimpleSetup::ODESimpleSetup ( const ControlSpacePtr space  )  [explicit]

Constructor needs the control space needed for planning.

ompl::control::ODESimpleSetup::ODESimpleSetup ( const base::StateSpacePtr space  )  [explicit]

The control space is assumed to be ODEControlSpace. Constructor only needs the state space.

ompl::control::ODESimpleSetup::ODESimpleSetup ( const ODEEnvironmentPtr env  )  [explicit]

The control space is assumed to be ODEControlSpace. The state space is assumed to be ODEStateSpace. Constructor only needs the ODE environment.

virtual ompl::control::ODESimpleSetup::~ODESimpleSetup ( void   )  [inline, virtual]

Definition at line 61 of file ODESimpleSetup.h.


Member Function Documentation

base::ScopedState<ODEStateSpace> ompl::control::ODESimpleSetup::getCurrentState ( void   )  const

Get the current ODE state (read parameters from ODE bodies).

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

Get the ODE environment associated to the state and control spaces.

Definition at line 66 of file ODESimpleSetup.h.

void ompl::control::ODESimpleSetup::playPath ( const base::PathPtr path,
double  timeFactor = 1.0 
) const

Set the ODE world to the states that are contained in a given path, sequentially. Using timeFactor, the speed at which this sequence is iterated through is altered.

void ompl::control::ODESimpleSetup::playSolutionPath ( double  timeFactor = 1.0  )  const

Call playPath() on the solution path, if one is available.

void ompl::control::ODESimpleSetup::setAngularVelocityBounds ( const base::RealVectorBounds bounds  )  [inline]

Set the bounds for the angular velocity.

Definition at line 93 of file ODESimpleSetup.h.

void ompl::control::ODESimpleSetup::setCurrentState ( const base::State state  ) 

Set the current ODE state (set parameters for ODE bodies).

void ompl::control::ODESimpleSetup::setCurrentState ( const base::ScopedState<> &  state  ) 

Set the current ODE state (set parameters for ODE bodies).

void ompl::control::ODESimpleSetup::setLinearVelocityBounds ( const base::RealVectorBounds bounds  )  [inline]

Set the bounds for the linear velocity.

Definition at line 87 of file ODESimpleSetup.h.

virtual void ompl::control::ODESimpleSetup::setup ( void   )  [virtual]

This method will create the necessary classes for planning. The solve() method will call this function automatically.

Reimplemented from ompl::control::SimpleSetup.

void ompl::control::ODESimpleSetup::setVolumeBounds ( const base::RealVectorBounds bounds  )  [inline]

Set the bounds for the planning volume.

Definition at line 81 of file ODESimpleSetup.h.

base::PathPtr ompl::control::ODESimpleSetup::simulate ( unsigned int  steps  )  const

Simulate the ODE environment forward for steps simulation steps, using the null control (ompl::control::ControlSpace::nullControl()). Construct a path representing this action.

base::PathPtr ompl::control::ODESimpleSetup::simulateControl ( const Control control,
unsigned int  steps 
) const

Simulate the ODE environment forward for steps simulation steps, using the control control. Construct a path representing this action.

base::PathPtr ompl::control::ODESimpleSetup::simulateControl ( const double *  control,
unsigned int  steps 
) const

Simulate the ODE environment forward for steps simulation steps, using the control control. Construct a path representing this action.

void ompl::control::ODESimpleSetup::useEnvParams ( void   )  [private]

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