Loading...
Searching...
No Matches

Rapidly-exploring Random Tree. More...

#include <ompl/control/planners/rrt/RRT.h>

Inheritance diagram for ompl::control::RRT:

Classes

class  Motion
 Representation of a motion. More...
 

Public Member Functions

 RRT (const SpaceInformationPtr &si)
 Constructor.
 
base::PlannerStatus solve (const base::PlannerTerminationCondition &ptc) override
 Continue solving for some amount of time. Return true if solution was found.
 
void clear () override
 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 () const
 Get the goal bias the planner is using.
 
bool getIntermediateStates () const
 Return true if the intermediate states generated along motions are to be added to the tree itself.
 
void setIntermediateStates (bool addIntermediateStates)
 Specify whether the intermediate states generated along motions are to be added to the tree itself.
 
void getPlannerData (base::PlannerData &data) const override
 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 ()
 Set a different nearest neighbors datastructure.
 
void setup () override
 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.
 
- Public Member Functions inherited from ompl::base::Planner
 Planner (const Planner &)=delete
 
Planneroperator= (const Planner &)=delete
 
 Planner (SpaceInformationPtr si, std::string name)
 Constructor.
 
virtual ~Planner ()=default
 Destructor.
 
template<class T >
T * as ()
 Cast this instance to a desired type.
 
template<class T >
const T * as () const
 Cast this instance to a desired type.
 
const SpaceInformationPtrgetSpaceInformation () const
 Get the space information this planner is using.
 
const ProblemDefinitionPtrgetProblemDefinition () const
 Get the problem definition the planner is trying to solve.
 
ProblemDefinitionPtrgetProblemDefinition ()
 Get the problem definition the planner is trying to solve.
 
const PlannerInputStatesgetPlannerInputStates () const
 Get the planner input states.
 
virtual void setProblemDefinition (const ProblemDefinitionPtr &pdef)
 Set the problem definition for the planner. The problem needs to be set before calling solve(). Note: If this problem definition replaces a previous one, it may also be necessary to call clear() or clearQuery().
 
virtual PlannerStatus solve (const PlannerTerminationCondition &ptc)=0
 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). If clearQuery() is called, the planner may retain prior datastructures generated from a previous query on a new problem definition. The function terminates if the call to ptc returns true.
 
PlannerStatus solve (const PlannerTerminationConditionFn &ptc, double checkInterval)
 Same as above except the termination condition is only evaluated at a specified interval.
 
PlannerStatus solve (double solveTime)
 Same as above except the termination condition is solely a time limit: the number of seconds the algorithm is allowed to spend planning.
 
virtual void clear ()
 Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
 
virtual void clearQuery ()
 Clears internal datastructures of any query-specific information from the previous query. Planner settings are not affected. The planner, if able, should retain all datastructures generated from previous queries that can be used to help solve the next query. Note that clear() should also clear all query-specific information along with all other datastructures in the planner. By default clearQuery() calls clear().
 
virtual void getPlannerData (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).

 
const std::string & getName () const
 Get the name of the planner.
 
void setName (const std::string &name)
 Set the name of the planner.
 
const PlannerSpecsgetSpecs () const
 Return the specifications (capabilities of this planner)
 
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.
 
virtual void checkValidity ()
 Check to see if the planner is in a working state (setup has been called, a goal was set, the input states seem to be in order). In case of error, this function throws an exception.
 
bool isSetup () const
 Check if setup() was called for this planner.
 
ParamSetparams ()
 Get the parameters for this planner.
 
const ParamSetparams () const
 Get the parameters for this planner.
 
const PlannerProgressPropertiesgetPlannerProgressProperties () const
 Retrieve a planner's planner progress property map.
 
virtual void printProperties (std::ostream &out) const
 Print properties of the motion planner.
 
virtual void printSettings (std::ostream &out) const
 Print information about the motion planner's settings.
 

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 Member Functions inherited from ompl::base::Planner
template<typename T , typename PlannerType , typename SetterType , typename GetterType >
void declareParam (const std::string &name, const PlannerType &planner, const SetterType &setter, const GetterType &getter, const std::string &rangeSuggestion="")
 This function declares a parameter for this planner instance, and specifies the setter and getter functions.
 
template<typename T , typename PlannerType , typename SetterType >
void declareParam (const std::string &name, const PlannerType &planner, const SetterType &setter, const std::string &rangeSuggestion="")
 This function declares a parameter for this planner instance, and specifies the setter function.
 
void addPlannerProgressProperty (const std::string &progressPropertyName, const PlannerProgressProperty &prop)
 Add a planner progress property called progressPropertyName with a property querying function prop to this planner's progress property map.
 

Protected Attributes

base::StateSamplerPtr sampler_
 State sampler.
 
DirectedControlSamplerPtr controlSampler_
 Control sampler.
 
const SpaceInformationsiC_
 The base::SpaceInformation cast as control::SpaceInformation, for convenience.
 
std::shared_ptr< NearestNeighbors< Motion * > > nn_
 A nearest-neighbors datastructure containing the tree of motions.
 
double goalBias_ {0.05}
 The fraction of time the goal is picked as the state to expand towards (if such a state is available)
 
bool addIntermediateStates_ {false}
 Flag indicating whether intermediate states are added to the built tree of motions.
 
RNG rng_
 The random number generator.
 
MotionlastGoalMotion_ {nullptr}
 The most recent goal motion. Used for PlannerData computation.
 
- Protected Attributes inherited from ompl::base::Planner
SpaceInformationPtr si_
 The space information for which planning is done.
 
ProblemDefinitionPtr pdef_
 The user set problem definition.
 
PlannerInputStates pis_
 Utility class to extract valid input states

 
std::string name_
 The name of this planner.
 
PlannerSpecs specs_
 The specifications of the planner (its capabilities)
 
ParamSet params_
 A map from parameter names to parameter instances for this planner. This field is populated by the declareParam() function.
 
PlannerProgressProperties plannerProgressProperties_
 A mapping between this planner's progress property names and the functions used for querying those progress properties.
 
bool setup_
 Flag indicating whether setup() has been called.
 

Additional Inherited Members

- Public Types inherited from ompl::base::Planner
using PlannerProgressProperty = std::function< std::string()>
 Definition of a function which returns a property about the planner's progress that can be queried by a benchmarking routine.
 
using PlannerProgressProperties = std::map< std::string, PlannerProgressProperty >
 A dictionary which maps the name of a progress property to the function to be used for querying that property.
 

Detailed Description

Rapidly-exploring Random Tree.

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. This implementation is intended for systems with differential constraints.
External documentation
S.M. LaValle and J.J. Kuffner, Randomized kinodynamic planning, Intl. J. of Robotics Research, vol. 20, pp. 378–400, May 2001. DOI: 10.1177/02783640122067453
[PDF] [more]

Definition at line 65 of file RRT.h.

Constructor & Destructor Documentation

◆ RRT()

ompl::control::RRT::RRT ( const SpaceInformationPtr si)

Constructor.

Definition at line 42 of file RRT.cpp.

◆ ~RRT()

ompl::control::RRT::~RRT ( )
override

Definition at line 52 of file RRT.cpp.

Member Function Documentation

◆ clear()

void ompl::control::RRT::clear ( )
overridevirtual

Clear datastructures. Call this function if the input data to the planner has changed and you do not want to continue planning.

Reimplemented from ompl::base::Planner.

Definition at line 65 of file RRT.cpp.

◆ distanceFunction()

double ompl::control::RRT::distanceFunction ( const Motion a,
const Motion b 
) const
inlineprotected

Compute distance between motions (actually distance between contained states)

Definition at line 163 of file RRT.h.

◆ freeMemory()

void ompl::control::RRT::freeMemory ( )
protected

Free the memory allocated by this planner.

Definition at line 76 of file RRT.cpp.

◆ getGoalBias()

double ompl::control::RRT::getGoalBias ( ) const
inline

Get the goal bias the planner is using.

Definition at line 94 of file RRT.h.

◆ getIntermediateStates()

bool ompl::control::RRT::getIntermediateStates ( ) const
inline

Return true if the intermediate states generated along motions are to be added to the tree itself.

Definition at line 101 of file RRT.h.

◆ getPlannerData()

void ompl::control::RRT::getPlannerData ( base::PlannerData data) const
overridevirtual

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.

Definition at line 263 of file RRT.cpp.

◆ setGoalBias()

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.

Definition at line 88 of file RRT.h.

◆ setIntermediateStates()

void ompl::control::RRT::setIntermediateStates ( bool  addIntermediateStates)
inline

Specify whether the intermediate states generated along motions are to be added to the tree itself.

Definition at line 108 of file RRT.h.

◆ setNearestNeighbors()

template<template< typename T > class NN>
void ompl::control::RRT::setNearestNeighbors ( )
inline

Set a different nearest neighbors datastructure.

Definition at line 117 of file RRT.h.

◆ setup()

void ompl::control::RRT::setup ( )
overridevirtual

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.

Definition at line 57 of file RRT.cpp.

◆ solve()

ompl::base::PlannerStatus ompl::control::RRT::solve ( const base::PlannerTerminationCondition ptc)
overridevirtual

Continue solving for some amount of time. Return true if solution was found.

Implements ompl::base::Planner.

Definition at line 93 of file RRT.cpp.

Member Data Documentation

◆ addIntermediateStates_

bool ompl::control::RRT::addIntermediateStates_ {false}
protected

Flag indicating whether intermediate states are added to the built tree of motions.

Definition at line 185 of file RRT.h.

◆ controlSampler_

DirectedControlSamplerPtr ompl::control::RRT::controlSampler_
protected

Control sampler.

Definition at line 172 of file RRT.h.

◆ goalBias_

double ompl::control::RRT::goalBias_ {0.05}
protected

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

Definition at line 182 of file RRT.h.

◆ lastGoalMotion_

Motion* ompl::control::RRT::lastGoalMotion_ {nullptr}
protected

The most recent goal motion. Used for PlannerData computation.

Definition at line 191 of file RRT.h.

◆ nn_

std::shared_ptr<NearestNeighbors<Motion *> > ompl::control::RRT::nn_
protected

A nearest-neighbors datastructure containing the tree of motions.

Definition at line 178 of file RRT.h.

◆ rng_

RNG ompl::control::RRT::rng_
protected

The random number generator.

Definition at line 188 of file RRT.h.

◆ sampler_

base::StateSamplerPtr ompl::control::RRT::sampler_
protected

State sampler.

Definition at line 169 of file RRT.h.

◆ siC_

const SpaceInformation* ompl::control::RRT::siC_
protected

The base::SpaceInformation cast as control::SpaceInformation, for convenience.

Definition at line 175 of file RRT.h.


The documentation for this class was generated from the following files:
  • ompl/control/planners/rrt/RRT.h
  • ompl/control/planners/rrt/src/RRT.cpp