ompl::control Namespace Reference

This namespace contains sampling based planning routines used by planning under differential constraints. More...

Classes

class  CompoundControl
 Definition of a compound control. More...
class  CompoundControlSampler
 Definition of a compound control sampler. This is useful to construct samplers for compound controls. More...
class  CompoundControlSpace
 A control space to allow the composition of control spaces. More...
class  Control
 Definition of an abstract control. More...
class  ControlSampler
 Abstract definition of a control sampler. Motion planners that need to sample controls will call functions from this class. Planners should call the versions of sample() and sampleNext() with most arguments, whenever this information is available. More...
class  ControlSamplerPtr
 A boost shared pointer wrapper for ompl::control::ControlSampler. More...
class  ControlSpace
 A control space representing the space of applicable controls. More...
class  ControlSpacePtr
 A boost shared pointer wrapper for ompl::control::ControlSpace. More...
class  KPIECE1
 Kinodynamic Planning by Interior-Exterior Cell Exploration. More...
class  ODEControlSpace
 Representation of controls applied in ODE environments. This is an array of double values. Only forward propagation is possible. More...
class  ODEEnvironment
 This class contains the ODE constructs OMPL needs to know about when planning. More...
class  ODEEnvironmentPtr
 A boost shared pointer wrapper for ompl::control::ODEEnvironment. More...
class  ODESimpleSetup
 Create the set of classes typically needed to solve a control problem when forward propagation is computed with ODE. More...
class  ODEStateSpace
 State space representing ODE states. More...
class  ODEStateValidityChecker
 The simplest state validity checker: all states are valid. More...
class  PathControl
 Definition of a control path. More...
class  RealVectorControlSpace
 A control space representing Rn. The distance function is the L2 norm. More...
class  RealVectorControlUniformSampler
 Uniform sampler for the Rn state space. More...
class  RRT
 Rapidly-exploring Random Tree. More...
class  SimpleSetup
 Create the set of classes typically needed to solve a control problem. More...
class  SpaceInformation
 Space information containing necessary information for planning with controls. setup() needs to be called before use. More...
class  SpaceInformationPtr
 A boost shared pointer wrapper for ompl::control::SpaceInformation. More...

Typedefs

typedef boost::function1
< ControlSamplerPtr, const
ControlSpace * > 
ControlSamplerAllocator
 Definition of a function that can allocate a control sampler.
typedef boost::function4< void,
const base::State *, const
Control *, const double,
base::State * > 
StatePropagationFn
 A function that achieves state propagation.

Functions

void checkProjectionEvaluator (const base::Planner *planner, base::ProjectionEvaluatorPtr &proj)
 Check if projection evaluator is defined properly. If not, attempt to use default.
 ClassForward (ODEEnvironment)
 Forward declaration of ompl::control::ODEEnvironment.
 ClassForward (SpaceInformation)
 Forward declaration of ompl::control::SpaceInformation.
 ClassForward (ControlSampler)
 Forward declaration of ompl::control::ControlSampler.
 ClassForward (ControlSpace)
 Forward declaration of ompl::control::ControlSpace.
base::PlannerPtr getDefaultPlanner (const base::GoalPtr &goal)
 Given a goal specification, decide on a planner for that goal.

Detailed Description

This namespace contains sampling based planning routines used by planning under differential constraints.


Typedef Documentation

Definition of a function that can allocate a control sampler.

Definition at line 175 of file ControlSampler.h.

typedef boost::function4<void, const base::State*, const Control*, const double, base::State*> ompl::control::StatePropagationFn

A function that achieves state propagation.

Definition at line 64 of file ControlSpace.h.


Function Documentation

void ompl::control::checkProjectionEvaluator ( const base::Planner *  planner,
base::ProjectionEvaluatorPtr &  proj 
)

Check if projection evaluator is defined properly. If not, attempt to use default.

ompl::control::ClassForward ( ODEEnvironment   ) 

Forward declaration of ompl::control::ODEEnvironment.

ompl::control::ClassForward ( SpaceInformation   ) 

Forward declaration of ompl::control::SpaceInformation.

ompl::control::ClassForward ( ControlSampler   ) 

Forward declaration of ompl::control::ControlSampler.

ompl::control::ClassForward ( ControlSpace   ) 

Forward declaration of ompl::control::ControlSpace.

base::PlannerPtr ompl::control::getDefaultPlanner ( const base::GoalPtr &  goal  ) 

Given a goal specification, decide on a planner for that goal.

 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:01 2013