Rapidly-exploring Random Tree. More...
#include <RRT.h>
Classes | |
class | Motion |
Representation of a motion. More... | |
Public Member Functions | |
RRT (const SpaceInformationPtr &si) | |
Constructor. | |
virtual bool | solve (const base::PlannerTerminationCondition &ptc) |
Continue solving for some amount of time. Return true if solution was found. | |
virtual void | clear (void) |
Clear datastructures. Call this function if the input data to the planner has changed and you do not want to continue planning. | |
void | setGoalBias (double goalBias) |
double | getGoalBias (void) const |
Get the goal bias the planner is using. | |
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). | |
template<template< typename T > class NN> | |
void | setNearestNeighbors (void) |
Set a different nearest neighbors datastructure. | |
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. | |
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) | |
Protected Attributes | |
base::StateSamplerPtr | sampler_ |
State sampler. | |
ControlSamplerPtr | controlSampler_ |
Control sampler. | |
const SpaceInformation * | siC_ |
The base::SpaceInformation cast as control::SpaceInformation, for convenience. | |
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) | |
RNG | rng_ |
The random number generator. |
Rapidly-exploring Random Tree.
@par Short description RRT is a tree-based motion planner that uses the following idea: RRT samples a random state @b qr in the state space, then finds the state @b qc among the previously seen states that is closest to @b qr and expands from @b qc towards @b qr, until a state @b qm is reached. @b qm is then added to the exploration tree. This implementation is intended for systems with differential constraints. @par External documentation S.M. LaValle and J.J. Kuffner, Randomized kinodynamic planning, <em>Intl. J. of Robotics Research</em>, vol. 20, pp. 378–400, May 2001. DOI: <a href="http://dx.doi.org/10.1177/02783640122067453">10.1177/02783640122067453</a><br> <a href="http://ijr.sagepub.com/content/20/5/378.full.pdf">[PDF]</a> <a href="http://msl.cs.uiuc.edu/~lavalle/rrtpubs.html">[more]</a>
void ompl::control::RRT::setGoalBias | ( | double | goalBias | ) | [inline] |
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.