ompl::geometric::RRTstar Class Reference
Optimal Rapidly-exploring Random Trees. More...
#include <ompl/geometric/planners/rrt/RRTstar.h>
Inheritance diagram for ompl::geometric::RRTstar:

Classes | |
struct | CostIndexCompare |
class | Motion |
Representation of a motion. More... | |
struct | PruneScratchSpace |
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 () |
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 () const |
Get the goal bias the planner is using. | |
void | setRange (double distance) |
Set the range the planner is supposed to use. | |
double | getRange () const |
Get the range the planner is using. | |
template<template< typename T > class NN> | |
void | setNearestNeighbors () |
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 () const |
Get the state of the delayed collision checking option. | |
void | setPrune (const bool prune) |
Controls whether the tree is pruned during the search. | |
bool | getPrune () const |
Get the state of the pruning option. | |
void | setPruneStatesImprovementThreshold (const double pp) |
Set the percentage threshold (between 0 and 1) for pruning the tree. If the new tree has removed at least this percentage of states, the tree will be finally pruned. | |
double | getPruneStatesImprovementThreshold () const |
Get the current prune states percentage threshold parameter. | |
virtual void | setup () |
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. | |
std::string | getIterationCount () const |
std::string | getBestCost () const |
Protected Member Functions | |
void | freeMemory () |
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) |
Updates the cost of the children of this node if the cost up to this node has changed. | |
int | pruneTree (const base::Cost pruneTreeCost) |
Prunes all those states which estimated total cost is higher than pruneTreeCost. Returns the number of motions pruned. Depends on the parameter set by setPruneStatesImprovementThreshold() | |
void | deleteBranch (Motion *motion) |
Deletes (frees memory) the motion and its children motions. | |
base::Cost | costToGo (const Motion *motion, const bool shortest=true) const |
Computes the Cost To Go heuristically as the cost to come from start to motion plus the cost to go from motion to goal. If shortest is true, the estimated cost to come start-motion is given. Otherwise, this cost to come is the current motion cost. | |
Protected Attributes | |
base::StateSamplerPtr | sampler_ |
State sampler. | |
boost::shared_ptr < NearestNeighbors< Motion * > > | nn_ |
A nearest-neighbors datastructure containing the tree of motions. | |
double | goalBias_ |
The fraction of time the goal is picked as the state to expand towards (if such a state is available) | |
double | maxDistance_ |
The maximum length of a motion to be added to a tree. | |
RNG | rng_ |
The random number generator. | |
bool | delayCC_ |
Option to delay and reduce collision checking within iterations. | |
base::OptimizationObjectivePtr | opt_ |
Objective we're optimizing. | |
Motion * | lastGoalMotion_ |
The most recent goal motion. Used for PlannerData computation. | |
std::vector< Motion * > | goalMotions_ |
A list of states in the tree that satisfy the goal condition. | |
bool | prune_ |
If this value is set to true, tree pruning will be enabled. | |
double | pruneStatesThreshold_ |
The tree is only pruned is the percentage of states to prune is above this threshold (between 0 and 1). | |
struct ompl::geometric::RRTstar::PruneScratchSpace | pruneScratchSpace_ |
Motion * | startMotion_ |
Stores the Motion containing the last added initial start state. | |
unsigned int | iterations_ |
Number of iterations the algorithm performed. | |
base::Cost | bestCost_ |
Best cost found so far by algorithm. |
Detailed Description
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, Vol 30, No 7, 2011. http://arxiv.org/abs/1105.1186
Member Function Documentation
void ompl::geometric::RRTstar::setGoalBias | ( | double | goalBias | ) | [inline] |
Set the goal bias.
In the process of randomly selecting states in the state space to attempt to go towards, the algorithm may in fact choose the actual goal state, if it knows it, with some probability. This probability is a real number between 0.0 and 1.0; its value should usually be around 0.05 and should not be too large. It is probably a good idea to use the default value.
void ompl::geometric::RRTstar::setRange | ( | double | distance | ) | [inline] |
The documentation for this class was generated from the following files:
- ompl/geometric/planners/rrt/RRTstar.h
- ompl/geometric/planners/rrt/src/RRTstar.cpp