ompl::geometric::RRT Class Reference

Rapidly-exploring Random Trees. More...

#include <RRT.h>

Inheritance diagram for ompl::geometric::RRT:
Inheritance graph
[legend]

List of all members.

Classes

class  Motion
 Representation of a motion. More...

Public Member Functions

virtual void clear (void)
 Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
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).
double getRange (void) const
 Get the range the planner is using.
 RRT (const base::SpaceInformationPtr &si)
 Constructor.
void setGoalBias (double goalBias)
 Set the goal bias.
template<template< typename T > class NN>
void setNearestNeighbors (void)
 Set a different nearest neighbors datastructure.
void setRange (double distance)
 Set the range the planner is supposed to use.
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.
virtual bool 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 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 ~RRT (void)

Protected Member Functions

double distanceFunction (const Motion *a, const Motion *b) const
 Compute distance between motions (actually distance between contained states).
void freeMemory (void)
 Free the memory allocated by this planner.

Protected Attributes

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.
boost::shared_ptr
< NearestNeighbors< Motion * > > 
nn_
 A nearest-neighbors datastructure containing the tree of motions.
RNG rng_
 The random number generator.
base::StateSamplerPtr sampler_
 State sampler.

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
[PDF] [more]

Definition at line 68 of file geometric/planners/rrt/RRT.h.


Constructor & Destructor Documentation

ompl::geometric::RRT::RRT ( const base::SpaceInformationPtr si  )  [inline]

Constructor.

Definition at line 73 of file geometric/planners/rrt/RRT.h.

virtual ompl::geometric::RRT::~RRT ( void   )  [inline, virtual]

Definition at line 81 of file geometric/planners/rrt/RRT.h.


Member Function Documentation

virtual void ompl::geometric::RRT::clear ( void   )  [virtual]

Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.

Reimplemented from ompl::base::Planner.

double ompl::geometric::RRT::distanceFunction ( const Motion a,
const Motion b 
) const [inline, protected]

Compute distance between motions (actually distance between contained states).

Definition at line 173 of file geometric/planners/rrt/RRT.h.

void ompl::geometric::RRT::freeMemory ( void   )  [protected]

Free the memory allocated by this planner.

double ompl::geometric::RRT::getGoalBias ( void   )  const [inline]

Get the goal bias the planner is using.

Definition at line 107 of file geometric/planners/rrt/RRT.h.

virtual void ompl::geometric::RRT::getPlannerData ( base::PlannerData data  )  const [virtual]

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).

Reimplemented from ompl::base::Planner.

double ompl::geometric::RRT::getRange ( void   )  const [inline]

Get the range the planner is using.

Definition at line 123 of file geometric/planners/rrt/RRT.h.

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.

Definition at line 101 of file geometric/planners/rrt/RRT.h.

template<template< typename T > class NN>
void ompl::geometric::RRT::setNearestNeighbors ( void   )  [inline]

Set a different nearest neighbors datastructure.

Definition at line 130 of file geometric/planners/rrt/RRT.h.

void ompl::geometric::RRT::setRange ( double  distance  )  [inline]

Set the range the planner is supposed to use.

This parameter greatly influences the runtime of the algorithm. It represents the maximum length of a motion to be added in the tree of motions.

Definition at line 117 of file geometric/planners/rrt/RRT.h.

virtual void ompl::geometric::RRT::setup ( void   )  [virtual]

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.

Reimplemented from ompl::base::Planner.

virtual bool ompl::geometric::RRT::solve ( const base::PlannerTerminationCondition ptc  )  [virtual]

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 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.

Implements ompl::base::Planner.


Member Data Documentation

double ompl::geometric::RRT::goalBias_ [protected]

The fraction of time the goal is picked as the state to expand towards (if such a state is available).

Definition at line 185 of file geometric/planners/rrt/RRT.h.

The maximum length of a motion to be added to a tree.

Definition at line 188 of file geometric/planners/rrt/RRT.h.

boost::shared_ptr< NearestNeighbors<Motion*> > ompl::geometric::RRT::nn_ [protected]

A nearest-neighbors datastructure containing the tree of motions.

Definition at line 182 of file geometric/planners/rrt/RRT.h.

The random number generator.

Definition at line 191 of file geometric/planners/rrt/RRT.h.

State sampler.

Definition at line 179 of file geometric/planners/rrt/RRT.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


ompl
Author(s): Ioan Sucan/isucan@rice.edu, Mark Moll/mmoll@rice.edu, Lydia Kavraki/kavraki@rice.edu
autogenerated on Fri Jan 11 09:34:03 2013