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 | AtlasChart |
Tangent space and bounding polytope approximating some patch of the manifold. More... | |
class | AtlasStateSampler |
StateSampler for use on an atlas. More... | |
class | AtlasStateSpace |
ConstrainedStateSpace encapsulating a planner-agnostic atlas algorithm for planning on a constraint manifold. More... | |
class | BridgeTestValidStateSampler |
Generate valid samples using bridge test. First sample an invalid state, then sample another invalid state. Take the midpoint of those samples. If midpoint is valid, return. If midpoint is invalid continue. More... | |
class | CForestStateSampler |
Extended state sampler to use with the CForest planning algorithm. It wraps the user-specified state sampler. More... | |
class | CForestStateSpaceWrapper |
State space wrapper to use together with CForest. It adds some functionalities to the regular state spaces necessary to CForest. 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 | ConditionalStateSampler |
The Conditional Sampler samples feasible Space-Time States. First, a space configuration is sampled. Then, a feasible time conditioned on the start and goal states is sampled for the space configuration. More... | |
class | ConstrainedMotionValidator |
Constrained configuration space specific implementation of checkMotion() that uses discreteGeodesic(). More... | |
class | ConstrainedSpaceInformation |
Space information for a constrained state space. Implements more direct for getting motion states. More... | |
class | ConstrainedStateSpace |
A StateSpace that has a Constraint imposed upon it. Underlying space functions are passed to the ambient space, and the constraint is used to inform any manifold related operations. setSpaceInformation() must be called in order for collision checking to be done in tandem with manifold traversal. More... | |
class | ConstrainedValidStateSampler |
Valid state sampler for constrained state spaces. More... | |
class | Constraint |
Definition of a differentiable holonomic constraint on a configuration space. See Constrained Planning for more details. More... | |
class | ConstraintIntersection |
Definition of a constraint composed of multiple constraints that all must be satisfied simultaneously. This class ‘stacks’ the constraint functions together. More... | |
class | ConstraintObjective |
Wrapper around ompl::base::Constraint to use as an optimization objective. More... | |
class | ControlDurationObjective |
Defines optimization objectives where the total time of a control action is summed. This cost function is specified by implementing the controlCost() method. More... | |
class | Cost |
Definition of a cost value. Can represent the cost of a motion or the cost of a state. More... | |
class | CostConvergenceTerminationCondition |
: A termination condition for stopping an optimizing planner based on cost convergence More... | |
class | DeterministicSequence |
An abstract class for deterministic sequences in arbitrary dimensions. More... | |
class | DeterministicStateSampler |
An abstract class for the concept of using deterministic sampling sequences to decrease the dispersion of the samples. More... | |
class | DiscreteMotionValidator |
A motion validator that only uses the state validity checker. Motions are checked for validity at a specified resolution. More... | |
class | DiscreteStateSampler |
State space sampler for discrete states. More... | |
class | DiscreteStateSpace |
A space representing discrete states; i.e. there are a small number of discrete states the system can be in. States are represented as integers [lowerBound, upperBound], where lowerBound and upperBound are inclusive. States do not wrap around; i.e. the distance between state lowerBound and state upperBound is upperBound-lowerBound. The dimension of the space is 1. More... | |
class | DubinsMotionValidator |
A Dubins motion validator that only uses the state validity checker. Motions are checked for validity at a specified resolution. More... | |
class | DubinsStateSpace |
An SE(2) state space where distance is measured by the length of Dubins curves. More... | |
class | EmptyStateSpace |
A state space representing an empty state space. This is useful for multilevel representations, where some projections might project onto an empty state space. More... | |
class | GaussianValidStateSampler |
Generate valid samples using the Gaussian sampling strategy. More... | |
class | GenericParam |
Motion planning algorithms often employ parameters to guide their exploration process. (e.g., goal biasing). Motion planners (and some of their components) use this class to declare what the parameters are, in a generic way, so that they can be set externally. More... | |
class | Goal |
Abstract definition of goals. More... | |
class | GoalLazySamples |
Definition of a goal region that can be sampled, but the sampling process can be slow. This class allows sampling to happen in a separate thread, and the number of goals may increase, as the planner is running, in a thread-safe manner. More... | |
class | GoalRegion |
Definition of a goal region. More... | |
class | GoalSampleableRegion |
Abstract definition of a goal region that can be sampled. More... | |
class | GoalSpace |
Definition of a goal space, i.e., a subspace of the problem state space that defines the goal. More... | |
class | GoalState |
Definition of a goal state. More... | |
class | GoalStates |
Definition of a set of goal states. More... | |
class | HaltonSequence |
Realization of the Halton sequence for the generation of arbitrary dimensional, low-dispersion sequences. More... | |
class | HaltonSequence1D |
Realization of the Halton sequence for the generation of arbitrary dimensional, low-dispersion sequences. More... | |
class | InformedSampler |
An abstract class for the concept of using information about the state space and the current solution cost to limit future search to a planning subproblem that contains all possibly better solutions. More... | |
class | InformedStateSampler |
A wrapper class that allows an InformedSampler to be used as a StateSampler. More... | |
class | IterationTerminationCondition |
A class to run a planner for a specific number of iterations. Casts to a PTC for use with Planner::solve. More... | |
class | KleinBottleStateSampler |
State sampler for the Klein bottle state space. More... | |
class | KleinBottleStateSpace |
The Klein bottle is a 2-dimensional non-orientable surface. In this class, we implement a 3-dimensional immersion of the Bottle. More... | |
class | MaximizeClearanceValidStateSampler |
Generate valid samples randomly, but with a bias towards higher clearance. More... | |
class | MaximizeMinClearanceObjective |
Objective for attempting to maximize the minimum clearance along a path. More... | |
class | MechanicalWorkOptimizationObjective |
An optimization objective which defines path cost using the idea of mechanical work. To be used in conjunction with TRRT. More... | |
class | MinimaxObjective |
The cost of a path is defined as the worst state cost over the entire path. This objective attempts to find the path with the "best worst cost" over all paths. More... | |
class | MinimizeArrivalTime |
The cost of a path is defined as the highest time value along its states. This objective attempts to optimize for the minimum arrival time. More... | |
class | MinimumClearanceValidStateSampler |
Generate valid samples randomly with extra requirement of min for clearance to nearest obstacle. More... | |
class | MobiusStateSpace |
The Mobius strip is a 2-dimensional non-orientable surface. More... | |
class | MorseEnvironment |
This class contains the MORSE constructs OMPL needs to know about when planning. More... | |
class | MorseGoal |
This is a goal class that is more amenable to Python More... | |
class | MorseProjection |
This class implements a generic projection for the MorseStateSpace, namely, the subspace representing the x and y positions of every rigid body. More... | |
class | MorseStateSpace |
State space representing MORSE states. More... | |
class | MorseStateValidityChecker |
The simplest state validity checker: all states are valid if they are within bounds. More... | |
class | MorseTerminationCondition |
This class represents a termination condition for the planner that only terminates if the user shuts down the MORSE simulation. More... | |
class | Motion |
Representation of a motion. 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 | MultiOptimizationObjective |
This class allows for the definition of multiobjective optimal planning problems. Objectives are added to this compound object, and motion costs are computed by taking a weighted sum of the individual objective costs. More... | |
class | ObstacleBasedValidStateSampler |
Generate valid samples using obstacle based sampling. First sample an invalid state, then sample a valid state. Then, interpolate from the invalid state to the valid state, returning the first valid state encountered. More... | |
class | OptimizationObjective |
Abstract definition of optimization objectives. More... | |
class | OrderedInfSampler |
An informed sampler wrapper that generates m samples and then returns them in order of the heuristic. More... | |
class | ParamSet |
Maintain a set of parameters. More... | |
class | Path |
Abstract definition of a path. More... | |
class | PathLengthDirectInfSampler |
An informed sampler for problems seeking to minimize path length. More... | |
class | PathLengthOptimizationObjective |
An optimization objective which corresponds to optimizing path length. More... | |
class | Planner |
Base class for a planner. 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 | PlannerDataEdge |
Base class for a PlannerData edge. 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 | PlannerDataVertex |
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone and equivalence operators. It is assumed that each vertex in the PlannerData structure is unique (i.e. no duplicates allowed). More... | |
class | PlannerInputStates |
Helper class to extract valid start & goal states. Usually used internally by planners. More... | |
struct | PlannerSolution |
Representation of a solution to a planning problem. More... | |
struct | PlannerSpecs |
Properties that planners may have. More... | |
struct | PlannerStatus |
A class to store the exit status of Planner::solve() 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 | PrecomputedSequence |
General realization for a sampler of precomputed sequences or sets. More... | |
class | PrecomputedStateSampler |
State space sampler for discrete states. More... | |
class | ProblemDefinition |
Definition of a problem to be solved. This includes the start state(s) for the system and a goal specification. Will contain solutions, if found. More... | |
class | ProjectedStateSampler |
StateSampler for use for a projection-based state space. More... | |
class | ProjectedStateSpace |
ConstrainedStateSpace encapsulating a projection-based methodology for planning with constraints. 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 | 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 | RealVectorDeterministicStateSampler |
Deterministic state sampler for the Rn state 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... | |
class | ReedsSheppMotionValidator |
A Reeds-Shepp motion validator that only uses the state validity checker. Motions are checked for validity at a specified resolution. More... | |
class | ReedsSheppStateSpace |
An SE(2) state space where distance is measured by the length of Reeds-Shepp curves. More... | |
class | RejectionInfSampler |
A default rejection sampling scheme that samples uniformly from the entire planning domain. Samples are rejected until one is found that has a heuristic solution estimate that is less than the current solution. In general, direct sampling of the informed subset is much better, but this is a general default. 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 | SE2DeterministicStateSampler |
Deterministic state sampler for the Rn state space. More... | |
class | SE2StateSpace |
A state space representing SE(2) More... | |
class | SE3StateSpace |
A state space representing SE(3) More... | |
class | SO2DeterministicStateSampler |
Deterministic state space sampler for SO(2) 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 | SolutionNonExistenceProof |
Abstract definition of a proof for the non-existence of a solution to a problem. 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 | SpaceTimeStateSpace |
A state space consisting of a space and a time component. More... | |
class | SpecificParam |
This is a helper class that instantiates parameters with different data types. More... | |
class | SphereStateSampler |
State sampler for the sphere state space. More... | |
class | SphereStateSpace |
class | State |
Definition of an abstract state. More... | |
class | StateCostIntegralObjective |
Defines optimization objectives where path cost can be represented as a path integral over a cost function defined over the state space. This cost function is specified by implementing the stateCost() method. 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 | StateSpace |
Representation of a space in which planning can be performed. Topology specific sampling, interpolation and distance are defined. More... | |
class | StateStorage |
Manage loading and storing for a set of states of a specified state space. More... | |
class | StateStorageWithMetadata |
State storage that allows storing state metadata as well. More... | |
class | StateValidityChecker |
Abstract definition for a class checking the validity of states. The implementation of this class must be thread safe. More... | |
struct | StateValidityCheckerSpecs |
Properties that a state validity checker may have. More... | |
class | SubspaceProjectionEvaluator |
If the projection for a CompoundStateSpace is supposed to be the same as the one for one of its included subspaces, this class facilitates selecting a projection of that subspace. More... | |
class | SubspaceStateSampler |
Construct a sampler that samples only within a subspace of the space. More... | |
class | TangentBundleSpaceInformation |
Space information for a tangent bundle-based state space. Implements more direct for getting motion states and checking motion, as the lazy approach requires post-processing. More... | |
class | TangentBundleStateSpace |
ConstrainedStateSpace encapsulating a planner-agnostic lazy atlas algorithm for planning on a constraint manifold. 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 | TorusStateSampler |
State sampler for the torus state space. More... | |
class | TorusStateSpace |
class | TypedSpaceInformation |
class | TypedStateValidityChecker |
class | UniformValidStateSampler |
A state sampler that only samples valid states, uniformly. More... | |
class | ValidStateSampler |
Abstract definition of a state sampler. More... | |
class | VFMechanicalWorkOptimizationObjective |
class | VFUpstreamCriterionOptimizationObjective |
class | WrapperProjectionEvaluator |
A projection evaluator that wraps around another projection evaluator. More... | |
class | WrapperStateSampler |
A state sampler that wraps around another state sampler. More... | |
class | WrapperStateSpace |
State space wrapper that transparently passes state space operations through to the underlying space. Allows augmentation of state spaces with additional information. More... | |
Typedefs | |
using | GoalSamplingFn = std::function< bool(const GoalLazySamples *, State *)> |
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. This function need not be thread safe. | |
using | CostToGoHeuristic = std::function< Cost(const State *, const Goal *)> |
The definition of a function which returns an admissible estimate of the optimal path cost from a given state to a goal. | |
using | PlannerAllocator = std::function< PlannerPtr(const SpaceInformationPtr &)> |
Definition of a function that can allocate a planner. | |
using | PlannerTerminationConditionFn = std::function< bool()> |
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. | |
using | ReportIntermediateSolutionFn = std::function< void(const Planner *, const std::vector< const base::State * > &, const Cost)> |
When a planner has an intermediate solution (e.g., optimizing planners), a function with this signature can be called to report the states of that solution. | |
using | ScopedStatePtr = std::shared_ptr< ScopedState<> > |
Shared pointer to a ScopedState<> | |
using | StateValidityCheckerFn = std::function< bool(const State *)> |
If no state validity checking class is specified (StateValidityChecker), a std::function can be specified instead. | |
using | StateSamplerAllocator = std::function< StateSamplerPtr(const StateSpace *)> |
Definition of a function that can allocate a state sampler. | |
using | GraphStateStorage = StateStorageWithMetadata< std::vector< std::size_t > > |
Storage of states where the metadata is a vector of indices. This is is typically used to store a graph. | |
using | GraphStateStoragePtr = std::shared_ptr< GraphStateStorage > |
using | ValidStateSamplerAllocator = std::function< ValidStateSamplerPtr(const SpaceInformation *)> |
Definition of a function that can allocate a valid state sampler. | |
Enumerations | |
enum | GoalType { GOAL_ANY = 1, GOAL_REGION = GOAL_ANY + 2, GOAL_SAMPLEABLE_REGION = GOAL_REGION + 4, GOAL_STATE = GOAL_SAMPLEABLE_REGION + 8, GOAL_STATES = GOAL_SAMPLEABLE_REGION + 16, GOAL_LAZY_SAMPLES = GOAL_STATES + 32 } |
The type of goal. More... | |
enum | AdvancedStateCopyOperation { NO_DATA_COPIED = 0, SOME_DATA_COPIED = 1, ALL_DATA_COPIED = 2 } |
The possible outputs for an advanced copy operation. 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_DISCRETE = 7, STATE_SPACE_DUBINS = 8, STATE_SPACE_REEDS_SHEPP = 9, STATE_SPACE_MOBIUS = 10, STATE_SPACE_SPHERE = 11, STATE_SPACE_TORUS = 12, STATE_SPACE_KLEIN_BOTTLE = 13, STATE_SPACE_TYPE_COUNT } |
The type of a state space. More... | |
Functions | |
std::ostream & | operator<< (std::ostream &stream, Cost c) |
Output operator for Cost. | |
Cost | goalRegionCostToGo (const State *state, const Goal *goal) |
For use when the cost-to-go of a state under the optimization objective is equivalent to the goal region's distanceGoal() . This function assumes that all states within the goal region's threshold have a cost-to-go of exactly zero. Note: goal is assumed to be of type ompl::base::GoalRegion. | |
OptimizationObjectivePtr | operator+ (const OptimizationObjectivePtr &a, const OptimizationObjectivePtr &b) |
Given two optimization objectives, returns a MultiOptimizationObjective that combines the two objectives with both weights equal to 1.0. | |
OptimizationObjectivePtr | operator* (double weight, const OptimizationObjectivePtr &a) |
Given a weighing factor and an optimization objective, returns a MultiOptimizationObjective containing only this objective weighted by the given weight. | |
OptimizationObjectivePtr | operator* (const OptimizationObjectivePtr &a, double weight) |
Given a weighing factor and an optimization objective, returns a MultiOptimizationObjective containing only this objective weighted by the given weight. | |
std::ostream & | operator<< (std::ostream &out, const PlannerStatus &status) |
Print a PlannerStatus object. | |
PlannerTerminationCondition | plannerNonTerminatingCondition () |
Simple termination condition that always returns false. The termination condition will never be met. | |
PlannerTerminationCondition | plannerAlwaysTerminatingCondition () |
Simple termination condition that always returns true. The termination condition will always be met. | |
PlannerTerminationCondition | plannerOrTerminationCondition (const PlannerTerminationCondition &c1, const PlannerTerminationCondition &c2) |
Combine two termination conditions into one. If either termination condition returns true, this one will return true as well. | |
PlannerTerminationCondition | plannerAndTerminationCondition (const PlannerTerminationCondition &c1, const PlannerTerminationCondition &c2) |
Combine two termination conditions into one. Both termination conditions need to return true for this one to return true. | |
PlannerTerminationCondition | timedPlannerTerminationCondition (double duration) |
Return a termination condition that will become true duration seconds in the future (wall-time) | |
PlannerTerminationCondition | timedPlannerTerminationCondition (time::duration duration) |
Return a termination condition that will become true duration in the future (wall-time) | |
PlannerTerminationCondition | timedPlannerTerminationCondition (double duration, double interval) |
Return a termination condition that will become true duration seconds in the future (wall-time), but is checked in a separate thread, every interval seconds; interval must be less than duration. | |
PlannerTerminationCondition | exactSolnPlannerTerminationCondition (const ompl::base::ProblemDefinitionPtr &pdef) |
Return a termination condition that will become true as soon as the problem definition has an exact solution. | |
OMPL_CLASS_FORWARD (OptimizationObjective) | |
OMPL_CLASS_FORWARD (InformedSampler) | |
OMPL_CLASS_FORWARD (InformedStateSampler) | |
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 > | |
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 , 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 > | |
const 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. More... | |
AdvancedStateCopyOperation | 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. | |
AdvancedStateCopyOperation | copyStateData (const StateSpace *destS, State *dest, const StateSpace *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. | |
AdvancedStateCopyOperation | copyStateData (const StateSpacePtr &destS, State *dest, const StateSpacePtr &sourceS, const State *source, const std::vector< std::string > &subspaces) |
Copy data from source (state from space sourceS) to dest (state from space destS) but only for the subspaces indicated by name in subspaces. This uses StateSpace::getSubstateLocationsByName(). More... | |
AdvancedStateCopyOperation | copyStateData (const StateSpace *destS, State *dest, const StateSpace *sourceS, const State *source, const std::vector< std::string > &subspaces) |
Copy data from source (state from space sourceS) to dest (state from space destS) but only for the subspaces indicated by name in subspaces. This uses StateSpace::getSubstateLocationsByName(). More... | |
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. | |
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. | |
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 that are in both a and b. | |
Variables | |
const double | dInf = std::numeric_limits<double>::infinity() |
Detailed Description
This namespace contains sampling based planning routines shared by both planning under geometric constraints (geometric) and planning under differential constraints (dynamic)
Enumeration Type Documentation
◆ GoalType
enum ompl::base::GoalType |
The type of goal.
Enumerator | |
---|---|
GOAL_ANY | This bit is set if casting to generic goal regions (ompl::base::Goal) is possible. This bit shold always be set. |
GOAL_REGION | This bit is set if casting to goal regions (ompl::base::GoalRegion) is possible. |
GOAL_SAMPLEABLE_REGION | This bit is set if casting to sampleable goal regions (ompl::base::GoalSampleableRegion) is possible. |
GOAL_STATE | This bit is set if casting to goal state (ompl::base::GoalState) is possible. |
GOAL_STATES | This bit is set if casting to goal states (ompl::base::GoalStates) is possible. |
GOAL_LAZY_SAMPLES | This bit is set if casting to goal states (ompl::base::GoalLazySamples) is possible. |
Definition at line 109 of file GoalTypes.h.
◆ StateSpaceType
The type of a state space.
Definition at line 109 of file StateSpaceTypes.h.