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

Classes | |
class | Motion |
Representation of a motion. More... | |
Public Member Functions | |
RRT (const base::SpaceInformationPtr &si) | |
Constructor. | |
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. | |
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. | |
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) | |
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. | |
Motion * | lastGoalMotion_ |
The most recent goal motion. Used for PlannerData computation. |
Detailed Description
Rapidly-exploring Random Trees.
- Short description
- RRT is a tree-based motion planner that uses the following idea: RRT samples a random state qr in the state space, then finds the state qc among the previously seen states that is closest to qr and expands from qc towards qr, until a state qm is reached. qm is then added to the exploration tree.
- External documentation
- J. Kuffner and S.M. LaValle, RRT-connect: An efficient approach to single-query path planning, in Proc. 2000 IEEE Intl. Conf. on Robotics and Automation, pp. 995–1001, Apr. 2000. DOI: [10.1109/ROBOT.2000.844730](http://dx.doi.org/10.1109/ROBOT.2000.844730)
[[PDF]](http://ieeexplore.ieee.org/ielx5/6794/18246/00844730.pdf?tp=&arnumber=844730&isnumber=18246) [[more]](http://msl.cs.uiuc.edu/~lavalle/rrtpubs.html)
Member Function Documentation
void ompl::geometric::RRT::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::RRT::setRange | ( | double | distance | ) | [inline] |
The documentation for this class was generated from the following files: