Public Member Functions |
| RRTstar (const base::SpaceInformationPtr &si) |
virtual void | getPlannerData (base::PlannerData &data) const |
| Get information about the current run of the motion planner. Repeated calls to this function will update data (only additions are made). This is useful to see what changed in the exploration datastructure, between calls to solve(), for example (without calling clear() in between).
|
virtual base::PlannerStatus | solve (const base::PlannerTerminationCondition &ptc) |
| Function that can solve the motion planning problem. This function can be called multiple times on the same problem, without calling clear() in between. This allows the planner to continue work for more time on an unsolved problem, for example. If this option is used, it is assumed the problem definition is not changed (unpredictable results otherwise). The only change in the problem definition that is accounted for is the addition of starting or goal states (but not changing previously added start/goal states). The function terminates if the call to ptc returns true.
|
virtual void | clear (void) |
| Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
|
void | setGoalBias (double goalBias) |
| Set the goal bias.
|
double | getGoalBias (void) const |
| Get the goal bias the planner is using.
|
void | setRange (double distance) |
| Set the range the planner is supposed to use.
|
double | getRange (void) const |
| Get the range the planner is using.
|
void | setBallRadiusConstant (double ballRadiusConstant) |
| When the planner attempts to rewire the tree, it does so by looking at some of the neighbors within a computed radius. The computation of that radius depends on the multiplicative factor set here. Set this parameter should be set at least to the side length of the (bounded) state space. E.g., if the state space is a box with side length L, then this parameter should be set to at least L for rapid and efficient convergence in trajectory space.
|
double | getBallRadiusConstant (void) const |
| Get the multiplicative factor used in the computation of the radius whithin which tree rewiring is done.
|
void | setMaxBallRadius (double maxBallRadius) |
| When the planner attempts to rewire the tree, it does so by looking at some of the neighbors within a computed radius. That radius is bounded by the value set here. This parameter should ideally be equal longest straight line from the initial state to anywhere in the state space. In other words, this parameter should be "sqrt(d) L", where d is the dimensionality of space and L is the side length of a box containing the obstacle free space.
|
double | getMaxBallRadius (void) const |
| Get the maximum radius the planner uses in the tree rewiring step.
|
template<template< typename T > class NN> |
void | setNearestNeighbors (void) |
| Set a different nearest neighbors datastructure.
|
void | setDelayCC (bool delayCC) |
| Option that delays collision checking procedures. When it is enabled, all neighbors are sorted by cost. The planner then goes through this list, starting with the lowest cost, checking for collisions in order to find a parent. The planner stops iterating through the list when a collision free parent is found. This prevents the planner from collsion checking each neighbor, reducing computation time in scenarios where collision checking procedures are expensive.
|
bool | getDelayCC (void) const |
| Get the state of the delayed collision checking option.
|
virtual void | setup (void) |
| Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceInformation::setup() if needed. This must be called before solving.
|
| Planner (const SpaceInformationPtr &si, const std::string &name) |
| Constructor.
|
virtual | ~Planner (void) |
| Destructor.
|
template<class T > |
T * | as (void) |
| Cast this instance to a desired type.
|
template<class T > |
const T * | as (void) const |
| Cast this instance to a desired type.
|
const SpaceInformationPtr & | getSpaceInformation (void) const |
| Get the space information this planner is using.
|
const ProblemDefinitionPtr & | getProblemDefinition (void) const |
| Get the problem definition the planner is trying to solve.
|
const PlannerInputStates & | getPlannerInputStates (void) const |
| Get the planner input states.
|
virtual void | setProblemDefinition (const ProblemDefinitionPtr &pdef) |
| Set the problem definition for the planner. The problem needs to be set before calling solve(). Note: If this problem definition replaces a previous one, it may also be necessary to call clear().
|
PlannerStatus | solve (const PlannerTerminationConditionFn &ptc, double checkInterval) |
| Same as above except the termination condition is only evaluated at a specified interval.
|
PlannerStatus | solve (double solveTime) |
| Same as above except the termination condition is solely a time limit: the number of seconds the algorithm is allowed to spend planning.
|
const std::string & | getName (void) const |
| Get the name of the planner.
|
void | setName (const std::string &name) |
| Set the name of the planner.
|
const PlannerSpecs & | getSpecs (void) const |
| Return the specifications (capabilities of this planner)
|
virtual void | checkValidity (void) |
| Check to see if the planner is in a working state (setup has been called, a goal was set, the input states seem to be in order). In case of error, this function throws an exception.
|
bool | isSetup (void) const |
| Check if setup() was called for this planner.
|
ParamSet & | params (void) |
| Get the parameters for this planner.
|
const ParamSet & | params (void) const |
| Get the parameters for this planner.
|
virtual void | printProperties (std::ostream &out) const |
| Print properties of the motion planner.
|
virtual void | printSettings (std::ostream &out) const |
| Print information about the motion planner's settings.
|
Protected Member Functions |
void | freeMemory (void) |
| Free the memory allocated by this planner.
|
double | distanceFunction (const Motion *a, const Motion *b) const |
| Compute distance between motions (actually distance between contained states)
|
void | removeFromParent (Motion *m) |
| Removes the given motion from the parent's child list.
|
void | updateChildCosts (Motion *m, double delta) |
| Updates the cost of the children of this node by adding the delta.
|
template<typename T , typename PlannerType , typename SetterType , typename GetterType > |
void | declareParam (const std::string &name, const PlannerType &planner, const SetterType &setter, const GetterType &getter) |
| This function declares a parameter for this planner instance, and specifies the setter and getter functions.
|
template<typename T , typename PlannerType , typename SetterType > |
void | declareParam (const std::string &name, const PlannerType &planner, const SetterType &setter) |
| This function declares a parameter for this planner instance, and specifies the setter function.
|
Optimal Rapidly-exploring Random Trees.
- Short description
- RRT* (optimal RRT) is an asymptotically-optimal incremental sampling-based motion planning algorithm. RRT* algorithm is guaranteed to converge to an optimal solution, while its running time is guaranteed to be a constant factor of the running time of the RRT. The notion of optimality is with respect to the distance function defined on the state space we are operating on. See ompl::base::Goal::setMaximumPathLength() for how to set the maximally allowed path length to reach the goal. If a solution path that is shorter than ompl::base::Goal::getMaximumPathLength() is found, the algorithm terminates before the elapsed time.
- External documentation
- S. Karaman and E. Frazzoli, Sampling-based Algorithms for Optimal Motion Planning, International Journal of Robotics Research (to appear), 2011. http://arxiv.org/abs/1105.1186
Definition at line 74 of file RRTstar.h.