This namespace contains sampling based planning routines shared by both planning under geometric constraints (geometric) and planning under differential constraints (dynamic). More...
Classes | |
class | AllValidStateValidityChecker |
The simplest state validity checker: all states are valid. More... | |
class | CompoundState |
Definition of a compound state. More... | |
class | CompoundStateSampler |
Definition of a compound state sampler. This is useful to construct samplers for compound states. More... | |
class | CompoundStateSpace |
A space to allow the composition of state spaces. More... | |
class | DiscreteMotionValidator |
A motion validator that only uses the state validity checker. Motions are checked for validity at a specified resolution. More... | |
class | EuclideanProjection |
The datatype for state projections. This class contains a real vector. More... | |
class | GaussianValidStateSampler |
Generate valid samples using the Gaussian sampling strategy. More... | |
class | Goal |
Abstract definition of goals. Will contain solutions, if found. More... | |
class | GoalLazySamples |
Definition of a goal region that can be sampled, but the sampling process can be slow. This class allows sampling the happen in a separate thread, and the number of goals may increase, as the planner is running, in a thread-safe manner. More... | |
class | GoalPtr |
A boost shared pointer wrapper for ompl::base::Goal. More... | |
class | GoalRegion |
Definition of a goal region. More... | |
class | GoalSampleableRegion |
Abstract definition of a goal region that can be sampled. More... | |
class | GoalState |
Definition of a goal state. More... | |
class | GoalStates |
Definition of a set of goal states. More... | |
class | MaximizeClearanceValidStateSampler |
Generate valid samples randomly, but with a bias towards higher clearance. More... | |
class | MotionValidator |
Abstract definition for a class checking the validity of motions -- path segments between states. This is often called a local planner. The implementation of this class must be thread safe. More... | |
class | MotionValidatorPtr |
A boost shared pointer wrapper for ompl::base::MotionValidator. More... | |
class | ObstacleBasedValidStateSampler |
Generate valid samples using the Bridge Test. More... | |
class | Path |
Abstract definition of a path. More... | |
class | PathPtr |
A boost shared pointer wrapper for ompl::base::Path. More... | |
class | Planner |
Base class for a planner. More... | |
class | PlannerAlwaysTerminatingCondition |
Simple termination condition that always returns true. The termination condition will always be met. More... | |
class | PlannerAndTerminationCondition |
Combine two termination conditions into one. Both termination conditions need to return true for this one to return true. More... | |
class | PlannerData |
Datatype holding data a planner can expose for debug purposes. More... | |
class | PlannerInputStates |
Helper class to extract valid start & goal states. Usually used internally by planners. More... | |
class | PlannerNonTerminatingCondition |
Simple termination condition that always returns false. The termination condition will never be met. More... | |
class | PlannerOrTerminationCondition |
Combine two termination conditions into one. If either termination condition returns true, this one will return true as well. More... | |
class | PlannerPtr |
A boost shared pointer wrapper for ompl::base::Planner. More... | |
class | PlannerTerminationCondition |
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whether they should terminate before a solution is found or not. operator() will return true if either the implemented condition is met (the call to eval() returns true) or if the user called terminate(true). More... | |
class | PlannerThreadedTerminationCondition |
Termination condition with lazy evaluation. This is just as a regular termination condition, except the condition is actually evaluated by computeEval() and the return value is stored in evalValue_. Every time eval() is called, evalValue_ is returned instead of actually evaluating the termination condition. Furthermore, the termination condition is evaluated every period_ seconds in a separate thread. The thread automatically starts when the condition is constructed and it terminates when the condition becomes true. More... | |
class | ProblemDefinition |
Definition of a problem to be solved. This includes the start state(s) for the system and a goal specification. More... | |
class | ProblemDefinitionPtr |
A boost shared pointer wrapper for ompl::base::ProblemDefinition. More... | |
class | ProjectionEvaluator |
Abstract definition for a class computing projections to Rn. Implicit integer grids are imposed on this projection space by setting cell sizes. Before use, the user must supply cell sizes for the integer grid (setCellSizes()). The implementation of this class is thread safe. More... | |
class | ProjectionEvaluatorPtr |
A boost shared pointer wrapper for ompl::base::ProjectionEvaluator. More... | |
class | ProjectionMatrix |
A projection matrix -- it allows multiplication of real vectors by a specified matrix. The matrix can also be randomly generated. More... | |
class | RealVectorBounds |
The lower and upper bounds for an Rn space. More... | |
class | RealVectorIdentityProjectionEvaluator |
Define the identity projection. More... | |
class | RealVectorLinearProjectionEvaluator |
Definition for a class computing linear projections (multiplication of a k-by-n matrix to the the Rn vector state to produce an Rk projection. The multiplication matrix needs to be supplied as input. More... | |
class | RealVectorOrthogonalProjectionEvaluator |
Definition for a class computing orthogonal projections. More... | |
class | RealVectorRandomLinearProjectionEvaluator |
Definition for a class computing a random linear projections. More... | |
class | RealVectorStateSampler |
State sampler for the Rn state space. More... | |
class | RealVectorStateSpace |
A state space representing Rn. The distance function is the L2 norm. More... | |
struct | SamplerSelector |
Depending on the type of state sampler, we have different allocation routines. More... | |
class | ScopedState |
Definition of a scoped state. More... | |
class | SE2StateSpace |
A state space representing SE(2). More... | |
class | SE3StateSpace |
A state space representing SE(3). More... | |
class | SO2StateSampler |
State space sampler for SO(2). More... | |
class | SO2StateSpace |
A state space representing SO(2). The distance function and interpolation take into account angle wrapping. More... | |
class | SO3StateSampler |
State space sampler for SO(3), using quaternion representation. More... | |
class | SO3StateSpace |
A state space representing SO(3). The internal representation is done with quaternions. The distance between states is the angle between quaternions and interpolation is done with slerp. More... | |
class | SpaceInformation |
The base class for space information. This contains all the information about the space planning is done in. setup() needs to be called as well, before use. More... | |
class | SpaceInformationPtr |
A boost shared pointer wrapper for ompl::base::SpaceInformation. More... | |
class | State |
Definition of an abstract state. More... | |
class | StateSampler |
Abstract definition of a state space sampler. More... | |
class | StateSamplerArray |
Class to ease the creation of a set of samplers. This is especially useful for multi-threaded planners. More... | |
class | StateSamplerPtr |
A boost shared pointer wrapper for ompl::base::StateSampler. More... | |
class | StateSpace |
Representation of a space in which planning can be performed. Topology specific sampling, interpolation and distance are defined. More... | |
class | StateSpacePtr |
A boost shared pointer wrapper for ompl::base::StateSpace. More... | |
class | StateValidityChecker |
Abstract definition for a class checking the validity of states. The implementation of this class must be thread safe. More... | |
class | StateValidityCheckerPtr |
A boost shared pointer wrapper for ompl::base::StateValidityChecker. More... | |
class | TimeStateSampler |
State space sampler for time. More... | |
class | TimeStateSpace |
A state space representing time. The time can be unbounded, in which case enforceBounds() is a no-op, satisfiesBounds() always returns true, sampling uniform time states always produces time 0 and getMaximumExtent() returns 1. If time is bounded (setBounds() has been previously called), the state space behaves as expected. After construction, the state space is unbounded. isBounded() can be used to check if the state space is bounded or not. More... | |
class | UniformValidStateSampler |
A state sampler that only samples valid states, uniformly. More... | |
class | ValidStateSampler |
Abstract definition of a state sampler. More... | |
class | ValidStateSamplerPtr |
A boost shared pointer wrapper for ompl::base::ValidStateSampler. More... | |
Typedefs | |
typedef boost::function2< bool, const GoalLazySamples *, State * > | GoalSamplingFn |
Goal sampling function. Returns false when no further calls should be made to it. Fills its second argument (the state) with the sampled goal state. | |
typedef boost::function1 < PlannerPtr, const SpaceInformationPtr & > | PlannerAllocator |
Definition of a function that can allocate a planner. | |
typedef boost::function0< bool > | PlannerTerminationConditionFn |
Signature for functions that decide whether termination conditions have been met for a planner, even if no solution is found. This is usually reaching a time or memory limit. If the function returns true, the planner is signaled to terminate its computation. Otherwise, computation continues while this function returns false, until a solution is found. | |
typedef std::vector< int > | ProjectionCoordinates |
Grid cells corresponding to a projection value are described in terms of their coordinates. | |
typedef boost::shared_ptr < ScopedState<> > | ScopedStatePtr |
Shared pointer to a ScopedState<> | |
typedef boost::function1< bool, const State * > | StateValidityCheckerFn |
If no state validity checking class is specified (StateValidityChecker), a boost function can be specified instead. | |
typedef boost::function1 < ValidStateSamplerPtr, const SpaceInformation * > | ValidStateSamplerAllocator |
Definition of a function that can allocate a state sampler. | |
Enumerations | |
enum | PlannerType { PLAN_UNKNOWN = 0, PLAN_TO_GOAL_STATE = 1, PLAN_TO_GOAL_STATES = 2, PLAN_TO_GOAL_SAMPLEABLE_REGION = 4 | PLAN_TO_GOAL_STATES | PLAN_TO_GOAL_STATE, PLAN_TO_GOAL_REGION = 8 | PLAN_TO_GOAL_SAMPLEABLE_REGION, PLAN_TO_GOAL_ANY = 32768 | PLAN_TO_GOAL_REGION } |
Different planners may be able to handle only specific types of goal regions. For instance, the most general goal representation is not suitable for bi-directional planners. Planners set their type to specify which type of goal regions they can handle. More... | |
enum | StateSpaceType { STATE_SPACE_UNKNOWN = 0, STATE_SPACE_REAL_VECTOR = 1, STATE_SPACE_SO2 = 2, STATE_SPACE_SO3 = 3, STATE_SPACE_SE2 = 4, STATE_SPACE_SE3 = 5, STATE_SPACE_TIME = 6, STATE_SPACE_TYPE_COUNT } |
The type of a state space. More... | |
Functions | |
ClassForward (ValidStateSampler) | |
Forward declaration of ompl::base::ValidStateSampler. | |
ClassForward (StateValidityChecker) | |
Forward declaration of ompl::base::StateValidityChecker. | |
ClassForward (StateSampler) | |
Forward declaration of ompl::base::StateSampler. | |
ClassForward (ProjectionEvaluator) | |
Forward declaration of ompl::base::ProjectionEvaluator. | |
ClassForward (StateSpace) | |
Forward declaration of ompl::base::StateSpace. | |
ClassForward (ProblemDefinition) | |
Forward declaration of ompl::base::ProblemDefinition. | |
ClassForward (Planner) | |
Forward declaration of ompl::base::Planner. | |
ClassForward (Path) | |
Forward declaration of ompl::base::Path. | |
ClassForward (MotionValidator) | |
Forward declaration of ompl::base::MotionValidator. | |
ClassForward (SpaceInformation) | |
Forward declaration of ompl::base::SpaceInformation. | |
ClassForward (Goal) | |
Forward declaration of ompl::base::Goal. | |
int | copyStateData (const StateSpacePtr &destS, State *dest, const StateSpacePtr &sourceS, const State *source) |
Copy data from source (state from space sourceS) to dest (state from space destS) on a component by component basis. State spaces are matched by name. If the state space destS contains any subspace whose name matches any subspace of the state space sourceS, the corresponding state components are copied. The return value is either 0 (no data copied), 1 (some data copied), 2 (all data copied). | |
StateSpacePtr | operator* (const StateSpacePtr &a, const StateSpacePtr &b) |
Construct a compound state space that contains subspaces that are in both a and b. | |
PlannerTerminationCondition | operator* (const PlannerTerminationCondition &a, const PlannerTerminationCondition &b) |
Combine two termination conditions into one. Both termination conditions need to return true for the construced one to return true. | |
StateSpacePtr | operator+ (const StateSpacePtr &a, const StateSpacePtr &b) |
Construct a compound state space from two existing state spaces. The components of this compound space are a (or the components of a, if a is compound) and b (or the components of b, if b is compound). State spaces are identified by name. Duplicates are checked for and added only once. If the compound state space would end up containing solely one component, that component is returned instead. | |
PlannerTerminationCondition | operator+ (const PlannerTerminationCondition &a, const PlannerTerminationCondition &b) |
Combine two termination conditions into one. If either termination condition returns true, the constructed one will return true as well. | |
StateSpacePtr | operator- (const StateSpacePtr &a, const std::string &name) |
Construct a compound state space that contains subspaces only from a, except for maybe the one named name. | |
StateSpacePtr | operator- (const StateSpacePtr &a, const StateSpacePtr &b) |
Construct a compound state space that contains subspaces only from a. If a is compound, b (or the components from b, if b is compound) are removed and the remaining components are returned as a compound state space. If the compound space would end up containing solely one component, that component is returned instead. | |
template<class T , class Y > | |
ScopedState< T > & | operator<< (ScopedState< T > &to, const ScopedState< Y > &from) |
This is a fancy version of the assignment operator. It is a partial assignment, in some sense. The difference is that if the states are part of compound state spaces, the data is copied from from to to on a component by component basis. State spaces are matched by name. If the state space for to contains any subspace whose name matches any subspace of the state space for from, the corresponding state components are copied. | |
template<class T > | |
std::ostream & | operator<< (std::ostream &out, const ScopedState< T > &state) |
Overload stream output operator. Calls ompl::base::StateSpace::printState(). | |
template<class T , class Y > | |
const ScopedState< T > & | operator>> (const ScopedState< T > &from, ScopedState< Y > &to) |
This is a fancy version of the assignment operator. It is a partial assignment, in some sense. The difference is that if the states are part of compound state spaces, the data is copied from from to to on a component by component basis. State spaces are matched by name. If the state space for to contains any subspace whose name matches any subspace of the state space for from, the corresponding state components are copied. | |
template<class T , class Y > | |
ScopedState | operator^ (const ScopedState< T > &a, const ScopedState< Y > &b) |
Given state a from state space A and state b from state space B, construct a state from state space A + B. The resulting state contains all the information from the input states (the states are concatenated). | |
PlannerTerminationCondition | timedPlannerTerminationCondition (double duration) |
Return a planner termination condition that becomes true after a specified number of seconds (duration). |
This namespace contains sampling based planning routines shared by both planning under geometric constraints (geometric) and planning under differential constraints (dynamic).
typedef boost::function2<bool, const GoalLazySamples*, State*> ompl::base::GoalSamplingFn |
Goal sampling function. Returns false when no further calls should be made to it. Fills its second argument (the state) with the sampled goal state.
Definition at line 43 of file GoalLazySamples.h.
typedef boost::function1<PlannerPtr, const SpaceInformationPtr&> ompl::base::PlannerAllocator |
typedef boost::function0<bool> ompl::base::PlannerTerminationConditionFn |
Signature for functions that decide whether termination conditions have been met for a planner, even if no solution is found. This is usually reaching a time or memory limit. If the function returns true, the planner is signaled to terminate its computation. Otherwise, computation continues while this function returns false, until a solution is found.
Definition at line 56 of file PlannerTerminationCondition.h.
typedef std::vector<int> ompl::base::ProjectionCoordinates |
Grid cells corresponding to a projection value are described in terms of their coordinates.
Definition at line 55 of file ProjectionEvaluator.h.
typedef boost::shared_ptr< ScopedState<> > ompl::base::ScopedStatePtr |
Shared pointer to a ScopedState<>
Definition at line 529 of file ScopedState.h.
typedef boost::function1<bool, const State*> ompl::base::StateValidityCheckerFn |
If no state validity checking class is specified (StateValidityChecker), a boost function can be specified instead.
Definition at line 78 of file base/SpaceInformation.h.
typedef boost::function1<ValidStateSamplerPtr, const SpaceInformation*> ompl::base::ValidStateSamplerAllocator |
Definition of a function that can allocate a state sampler.
Definition at line 119 of file ValidStateSampler.h.
Different planners may be able to handle only specific types of goal regions. For instance, the most general goal representation is not suitable for bi-directional planners. Planners set their type to specify which type of goal regions they can handle.
PLAN_UNKNOWN |
This value should not be set. |
PLAN_TO_GOAL_STATE |
This bit is set if planning to goal states (ompl::base::GoalState) is possible. |
PLAN_TO_GOAL_STATES |
This bit is set if planning to goal states (ompl::base::GoalStates) is possible. |
PLAN_TO_GOAL_SAMPLEABLE_REGION |
This bit is set if planning to sampleable goal regions (ompl::base::GoalSampleableRegion) is possible. |
PLAN_TO_GOAL_REGION |
This bit is set if planning to goal regions (ompl::base::GoalRegion) is possible. |
PLAN_TO_GOAL_ANY |
This bit is set if planning to generic goal regions (ompl::base::Goal) is possible. |
The type of a state space.
Definition at line 46 of file StateSpaceTypes.h.
ompl::base::ClassForward | ( | ValidStateSampler | ) |
Forward declaration of ompl::base::ValidStateSampler.
ompl::base::ClassForward | ( | StateValidityChecker | ) |
Forward declaration of ompl::base::StateValidityChecker.
ompl::base::ClassForward | ( | StateSampler | ) |
Forward declaration of ompl::base::StateSampler.
ompl::base::ClassForward | ( | ProjectionEvaluator | ) |
Forward declaration of ompl::base::ProjectionEvaluator.
ompl::base::ClassForward | ( | StateSpace | ) |
Forward declaration of ompl::base::StateSpace.
ompl::base::ClassForward | ( | ProblemDefinition | ) |
Forward declaration of ompl::base::ProblemDefinition.
ompl::base::ClassForward | ( | Planner | ) |
Forward declaration of ompl::base::Planner.
ompl::base::ClassForward | ( | Path | ) |
Forward declaration of ompl::base::Path.
ompl::base::ClassForward | ( | MotionValidator | ) |
Forward declaration of ompl::base::MotionValidator.
ompl::base::ClassForward | ( | SpaceInformation | ) |
Forward declaration of ompl::base::SpaceInformation.
ompl::base::ClassForward | ( | Goal | ) |
Forward declaration of ompl::base::Goal.
int ompl::base::copyStateData | ( | const StateSpacePtr & | destS, | |
State * | dest, | |||
const StateSpacePtr & | sourceS, | |||
const State * | source | |||
) |
Copy data from source (state from space sourceS) to dest (state from space destS) on a component by component basis. State spaces are matched by name. If the state space destS contains any subspace whose name matches any subspace of the state space sourceS, the corresponding state components are copied. The return value is either 0 (no data copied), 1 (some data copied), 2 (all data copied).
PlannerTerminationCondition ompl::base::operator* | ( | const PlannerTerminationCondition & | a, | |
const PlannerTerminationCondition & | b | |||
) |
Combine two termination conditions into one. Both termination conditions need to return true for the construced one to return true.
PlannerTerminationCondition ompl::base::operator+ | ( | const PlannerTerminationCondition & | a, | |
const PlannerTerminationCondition & | b | |||
) |
Combine two termination conditions into one. If either termination condition returns true, the constructed one will return true as well.
PlannerTerminationCondition ompl::base::timedPlannerTerminationCondition | ( | double | duration | ) |
Return a planner termination condition that becomes true after a specified number of seconds (duration).