Main Page   Class Hierarchy   Compound List   File List   Compound Members   File Members  

RRT Class Reference

The base class, which generates a single Rapidly-exploring Random Tree. More...

#include <rrt.h>

Inheritance diagram for RRT:

Planner Solver PlannerHsu RandomTree RRTDual RRTGoalBias RRTGoalPull RRTGoalZoom RRTHull RRTPolar RRTStar List of all members.

Public Methods

 RRT (Problem *problem)
 A constructor that initializes data members.

virtual ~RRT ()
 Empty destructor.

virtual void Reset ()
 Reset the planner.

virtual void Construct ()
 Generate an RRT.

virtual bool Plan ()
 Attempt to solve an Initial-Goal query by growing an RRT.


Public Attributes

bool UseANN
 If true, then the ANN package is used for nearest neighbors. It assumes R^n topology and Euclidean metric. The default is false.

double GoalDist
 The distance of the closest RRT node to the goal.

vector BestState
 The closest state to the goal so far (not used in dual-tree planners).

double ConnectTimeLimit
 The maximum amount of time to move in a Connect step (default = INFINITY).

int SatisfiedCount
 Number of times the collision checker has been called.


Protected Methods

virtual vector SelectBestInput (const vector &x1, const vector &x2, vector &nx_best, bool &success, bool forward)
 Select the input that gets closest to x2 from x1.

virtual vector SelectRandomInput (const vector &x1, const vector &x2, vector &nx_best, bool &success, bool forward)
 A replacement of Extend.

virtual node NearestNeighbor (const vector &x, const GRAPH<vector,vector> &g, bool forward)
 Return the nearest neighbor in the graph.

virtual bool Extend (const vector &x, GRAPH<vector,vector> &g, node &nn, bool forward)
 Incrementally extend the RRT.

virtual bool Connect (const vector &x, GRAPH<vector,vector> &g, node &nn, bool forward)
 Iterated Extend.

virtual bool Project (const vector &x, GRAPH<vector,vector> &g, node &nn, bool forward)
 Like Extend, except it adds a node for each input (not used).

virtual vector ChooseState ()
 Pick a state using some sampling technique.

list<node> PathToLeaf (const node &n, const GRAPH<vector,vector> &g)
 Pull the path out of the tree.


Protected Attributes

node_map<double> GEdgeTime
node_map<double> G2EdgeTime

Detailed Description

The base class, which generates a single Rapidly-exploring Random Tree.

The base class for the planners based on Rapidly-exploring Random Trees. In the base class, a single tree is generated without any regard to the GoalState. The best planners to try are RRTGoalBias and RRTGoalZoom for single trees, and RRTConCon and RRTExtExt for dual trees. Dual tree approaches are much more efficient than single tree approaches, assuming dual trees can be applied.


Constructor & Destructor Documentation

RRT::RRT ( Problem * problem )
 

A constructor that initializes data members.

RRT::~RRT ( ) [inline, virtual]
 

Empty destructor.


Member Function Documentation

vector RRT::ChooseState ( ) [protected, virtual]
 

Pick a state using some sampling technique.

Reimplemented in RRTGoalBias, RRTGoalZoom, RRTPolar, and RRTHull.

bool RRT::Connect ( const vector & x,
GRAPH< vector,vector >& g,
node & nn,
bool forward = true ) [protected, virtual]
 

Iterated Extend.

void RRT::Construct ( ) [virtual]
 

Generate an RRT.

Reimplemented from Planner.

Reimplemented in RRTGoalPull, and RRTCon.

bool RRT::Extend ( const vector & x,
GRAPH< vector,vector >& g,
node & nn,
bool forward = true ) [protected, virtual]
 

Incrementally extend the RRT.

Reimplemented in RRTStar, and PlannerHsu.

node RRT::NearestNeighbor ( const vector & x,
const GRAPH< vector,vector >& g,
bool forward = true ) [protected, virtual]
 

Return the nearest neighbor in the graph.

Reimplemented in RRTStar, and RandomTree.

list< node > RRT::PathToLeaf ( const node & n,
const GRAPH< vector,vector >& g ) [protected]
 

Pull the path out of the tree.

bool RRT::Plan ( ) [virtual]
 

Attempt to solve an Initial-Goal query by growing an RRT.

Reimplemented from Planner.

Reimplemented in RRTCon, RRTDual, RRTExtExt, RRTExtCon, and RRTConCon.

bool RRT::Project ( const vector & x,
GRAPH< vector,vector >& g,
node & nn,
bool forward = true ) [protected, virtual]
 

Like Extend, except it adds a node for each input (not used).

void RRT::Reset ( ) [virtual]
 

Reset the planner.

Reimplemented from Planner.

vector RRT::SelectBestInput ( const vector & x1,
const vector & x2,
vector & nx_best,
bool & success,
bool forward = true ) [protected, virtual]
 

Select the input that gets closest to x2 from x1.

Reimplemented in RandomTree.

vector RRT::SelectRandomInput ( const vector & x1,
const vector & x2,
vector & nx_best,
bool & success,
bool forward = true ) [protected, virtual]
 

A replacement of Extend.


Member Data Documentation

vector RRT::BestState
 

The closest state to the goal so far (not used in dual-tree planners).

double RRT::ConnectTimeLimit
 

The maximum amount of time to move in a Connect step (default = INFINITY).

node_map< double > RRT::G2EdgeTime [protected]
 

node_map< double > RRT::GEdgeTime [protected]
 

double RRT::GoalDist
 

The distance of the closest RRT node to the goal.

int RRT::SatisfiedCount
 

Number of times the collision checker has been called.

bool RRT::UseANN
 

If true, then the ANN package is used for nearest neighbors. It assumes R^n topology and Euclidean metric. The default is false.


The documentation for this class was generated from the following files: Motion Strategy Library


Web page maintained by Steve LaValle
Partial support provided by NSF CAREER Award IRI-970228 (LaValle), Honda Research, and Iowa State University.
Contributors: Anna Atramentov, Peng Cheng, James Kuffner, Steve LaValle, and Libo Yang.