ompl::control Namespace Reference

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

Classes

class  Automaton
 A class to represent a deterministic finite automaton, each edge of which corresponds to a World. A system trajectory, by way of project() and worldAtRegion() in PropositionalDecomposition, determines a sequence of Worlds, which are read by an Automaton to determine whether a trajectory satisfies a given specification. More...
 
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  ControlSpace
 A control space representing the space of applicable controls. More...
 
class  Decomposition
 A Decomposition is a partition of a bounded Euclidean space into a fixed number of regions which are denoted by integers. More...
 
class  DirectedControlSampler
 Abstract definition of a directed control sampler. Motion planners that need to sample controls that take the system to a desired direction will call functions from this class. Planners should call the versions of sampleTo() with most arguments, whenever this information is available. If no direction information is available, the use of a ControlSampler is perhaps more appropriate. More...
 
class  DiscreteControlSampler
 Control space sampler for discrete controls. More...
 
class  DiscreteControlSpace
 A space representing discrete controls; i.e. there are a small number of discrete controls the system can react to. Controls are represented as integers [lowerBound, upperBound], where lowerBound and upperBound are inclusive. More...
 
class  EST
 Expansive Space Trees. More...
 
class  GridDecomposition
 A GridDecomposition is a Decomposition implemented using a grid. More...
 
class  KPIECE1
 Kinodynamic Planning by Interior-Exterior Cell Exploration. More...
 
class  LTLPlanner
 A planner for generating system trajectories to satisfy a logical specification given by an automaton, the propositions of which are defined over a decomposition of the system's state space. More...
 
class  LTLProblemDefinition
 
class  LTLSpaceInformation
 
class  MorseControlSpace
 Representation of controls applied in MORSE environments. This is an array of double values. More...
 
class  MorseSimpleSetup
 Create the set of classes typically needed to solve a control problem when forward propagation is computed with MORSE. More...
 
class  MorseStatePropagator
 State propagation with MORSE. Only forward propagation is possible. More...
 
class  ODEAdaptiveSolver
 Adaptive step size solver for ordinary differential equations of the type q' = f(q, u), where q is the current state of the system and u is a control applied to the system. The maximum integration error is bounded in this approach. Solver is the numerical integration method used to solve the equations, and must implement the error stepper concept from boost::numeric::odeint. The default is a fifth order Runge-Kutta Cash-Karp method with a fourth order error bound. More...
 
class  ODEBasicSolver
 Basic solver for ordinary differential equations of the type q' = f(q, u), where q is the current state of the system and u is a control applied to the system. StateType defines the container object describing the state of the system. Solver is the numerical integration method used to solve the equations. The default is a fourth order Runge-Kutta method. This class wraps around the simple stepper concept from boost::numeric::odeint. More...
 
class  ODEErrorSolver
 Solver for ordinary differential equations of the type q' = f(q, u), where q is the current state of the system and u is a control applied to the system. StateType defines the container object describing the state of the system. Solver is the numerical integration method used to solve the equations. The default is a fifth order Runge-Kutta Cash-Karp method with a fourth order error bound. This class wraps around the error stepper concept from boost::numeric::odeint. More...
 
class  ODESolver
 Abstract base class for an object that can solve ordinary differential equations (ODE) of the type q' = f(q,u) using numerical integration. Classes deriving from this must implement the solve method. The user must supply the ODE to solve. More...
 
class  OpenDEControlSpace
 Representation of controls applied in OpenDE environments. This is an array of double values. More...
 
class  OpenDEEnvironment
 This class contains the OpenDE constructs OMPL needs to know about when planning. More...
 
class  OpenDESimpleSetup
 Create the set of classes typically needed to solve a control problem when forward propagation is computed with OpenDE. More...
 
class  OpenDEStatePropagator
 State propagation with OpenDE. Only forward propagation is possible. More...
 
class  OpenDEStateSpace
 State space representing OpenDE states. More...
 
class  OpenDEStateValidityChecker
 The simplest state validity checker: all states are valid. More...
 
class  PathControl
 Definition of a control path. More...
 
class  PDST
 Path-Directed Subdivision Tree. More...
 
class  PlannerData
 Object containing planner generated vertex and edge data. It is assumed that all vertices are unique, and only a single directed edge connects two vertices. More...
 
class  PlannerDataEdgeControl
 Representation of an edge in PlannerData for planning with controls. This structure encodes a specific control and a duration to apply the control. More...
 
class  PlannerDataStorage
 Object that handles loading/storing a PlannerData object to/from a binary stream. Serialization of vertices and edges is performed using the Boost archive method serialize. Derived vertex/edge classes are handled, presuming those classes implement the serialize method. More...
 
class  ProductGraph
 A ProductGraph represents the weighted, directed, graph-based Cartesian product of a PropositionalDecomposition object, an Automaton corresponding to a co-safe LTL specification, and an Automaton corresponding to a safe LTL specification. More...
 
class  PropositionalDecomposition
 A propositional decomposition wraps a given Decomposition with a region-to-proposition assignment operator. Each region in the decomposition has a corresponding World. More...
 
class  PropositionalTriangularDecomposition
 A PropositionalTriangularDecomposition is a triangulation that ignores obstacles and respects propositional regions of interest. Practically speaking, it is both a TriangularDecomposition and a PropositionalDecomposition, but it is implemented without using multiple inheritance. More...
 
class  RealVectorControlSpace
 A control space representing Rn. More...
 
class  RealVectorControlUniformSampler
 Uniform sampler for the Rn state space. More...
 
class  RRT
 Rapidly-exploring Random Tree. More...
 
class  SimpleDirectedControlSampler
 Implementation of a simple directed control sampler. This is a basic implementation that does not actually take direction into account and builds upon ControlSampler. Instead, a set of k random controls are sampled, and the control that gets the system closest to the target state is returned. 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  SST
 
class  StatePropagator
 Model the effect of controls on system states. More...
 
class  SteeredControlSampler
 Abstract definition of a steered control sampler. It uses the steering function in a state propagator to find the controls that drive from one state to another. More...
 
class  Syclop
 Synergistic Combination of Layers of Planning. More...
 
class  SyclopEST
 SyclopEST is Syclop with EST as its low-level tree planner. More...
 
class  SyclopRRT
 SyclopRRT is Syclop with RRT as its low-level tree planner. More...
 
class  TriangularDecomposition
 A TriangularDecomposition is a triangulation that ignores obstacles. More...
 
class  World
 A class to represent an assignment of boolean values to propositions. A World can be partially restrictive, i.e., some propositions do not have to be assigned a value, in which case it can take on any value. Our notion of a World is similar to a set of truth assignments in propositional logic. More...
 

Typedefs

using ControlSamplerAllocator = std::function< ControlSamplerPtr(const ControlSpace *)>
 Definition of a function that can allocate a control sampler.
 
using DirectedControlSamplerAllocator = std::function< DirectedControlSamplerPtr(const SpaceInformation *)>
 Definition of a function that can allocate a directed control sampler.
 
using StatePropagatorFn = std::function< void(const base::State *, const Control *, const double, base::State *)>
 A function that achieves state propagation.
 

Enumerations

enum  ControlSpaceType { CONTROL_SPACE_UNKNOWN = 0, CONTROL_SPACE_REAL_VECTOR = 1, CONTROL_SPACE_DISCRETE = 2, CONTROL_SPACE_TYPE_COUNT }
 The type of a control space. More...
 

Functions

std::ostream & operator<< (std::ostream &out, const ProductGraph::State &s)
 

Detailed Description

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

Enumeration Type Documentation

◆ ControlSpaceType

The type of a control space.

Enumerator
CONTROL_SPACE_UNKNOWN 

Unset type; this is the default type.

CONTROL_SPACE_REAL_VECTOR 

ompl::control::RealVectorControlSpace

CONTROL_SPACE_DISCRETE 

ompl::control::DiscreteControlSpace

CONTROL_SPACE_TYPE_COUNT 

Number of control space types; To add new types, use values that are larger than the count.

Definition at line 109 of file ControlSpaceTypes.h.