Transition-based Rapidly-exploring Random Trees. More...

#include <ompl/geometric/planners/rrt/TRRT.h>

Inheritance diagram for ompl::geometric::TRRT:

Classes

class  Motion
 Representation of a motion. More...
 

Public Member Functions

 TRRT (const base::SpaceInformationPtr &si)
 Constructor.
 
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).

 
base::PlannerStatus solve (const base::PlannerTerminationCondition &plannerTerminationCondition) override
 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.
 
void clear () override
 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. More...
 
double getGoalBias () const
 Get the goal bias the planner is using.
 
void setRange (double distance)
 Set the range the planner is supposed to use. More...
 
double getRange () const
 Get the range the planner is using.
 
void setTempChangeFactor (double factor)
 Set the factor by which the temperature is increased after a failed transition test. This value should be in the range (0, 1], typically close to zero (default is 0.1). This value is an exponential (e^factor) that is multiplied with the current temperature.
 
double getTempChangeFactor () const
 Get the factor by which the temperature rises based on current acceptance/rejection rate.
 
void setCostThreshold (double maxCost)
 Set the cost threshold (default is infinity). Any motion cost that is not better than this cost (according to the optimization objective) will not be expanded by the planner.
 
double getCostThreshold () const
 Get the cost threshold (default is infinity). Any motion cost that is not better than this cost (according to the optimization objective) will not be expanded by the planner.
 
void setInitTemperature (double initTemperature)
 Set the initial temperature at the beginning of the algorithm. Should be high to allow for initial exploration.
 
double getInitTemperature () const
 Get the temperature at the start of planning.
 
void setFrontierThreshold (double frontier_threshold)
 Set the distance between a new state and the nearest neighbor that qualifies that state as being a frontier.
 
double getFrontierThreshold () const
 Get the distance between a new state and the nearest neighbor that qualifies that state as being a frontier.
 
void setFrontierNodeRatio (double frontierNodeRatio)
 Set the ratio between adding nonfrontier nodes to frontier nodes, for example .1 is 1/10 or one nonfrontier node for every 10 frontier nodes added.
 
double getFrontierNodeRatio () const
 Get the ratio between adding nonfrontier nodes to frontier nodes, for example .1 is 1/10 or one nonfrontier node for every 10 frontier nodes added.
 
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. More...
 
template<class T >
const T * as () const
 Cast this instance to a desired type. More...
 
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().
 
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 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().
 
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 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)
 
bool transitionTest (const base::Cost &motionCost)
 Filter irrelevant configuration regarding the search of low-cost paths before inserting into tree. More...
 
bool minExpansionControl (double randMotionDistance)
 Use ratio to prefer frontier nodes to nonfrontier ones.
 
- 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.
 
std::shared_ptr< NearestNeighbors< Motion * > > nearestNeighbors_
 A nearest-neighbors datastructure containing the tree of motions.
 
double goalBias_ {.05}
 The fraction of time the goal is picked as the state to expand towards (if such a state is available)
 
double maxDistance_ {0.}
 The maximum length of a motion to be added to a tree.
 
RNG rng_
 The random number generator.
 
MotionlastGoalMotion_ {nullptr}
 The most recent goal motion. Used for PlannerData computation.
 
double temp_
 Temperature parameter used to control the difficulty level of transition tests. Low temperatures limit the expansion to a slightly positive slopes, high temps enable to climb the steeper slopes. Dynamically tuned according to the information acquired during exploration.
 
base::Cost bestCost_
 The most desirable (e.g., minimum) cost value in the search tree.
 
base::Cost worstCost_
 The least desirable (e.g., maximum) cost value in the search tree.
 
base::Cost costThreshold_
 All motion costs must be better than this cost (default is infinity)
 
double tempChangeFactor_
 The value of the expression exp^T_rate. The temperature is increased by this factor whenever the transition test fails.
 
double initTemperature_
 The initial value of temp_.
 
double nonfrontierCount_
 The number of non-frontier nodes in the search tree.
 
double frontierCount_
 The number of frontier nodes in the search tree.
 
double frontierThreshold_
 The distance between an old state and a new state that qualifies it as a frontier state.
 
double frontierNodeRatio_
 Target ratio of non-frontier nodes to frontier nodes. rho.
 
ompl::base::OptimizationObjectivePtr opt_
 The optimization objective being optimized by TRRT.
 
- 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

Transition-based Rapidly-exploring Random Trees.

Short description
T-RRT is an RRT variant and tree-based motion planner that takes into consideration state costs to compute low-cost paths that follow valleys and saddle points of the configuration-space costmap. It uses transition tests from stochastic optimization methods to accept or reject new potential states.
Example usage
Please see Dave Coleman's example to see how TRRT can be used.
External documentation
L. Jaillet, J. Cortés, T. Siméon, Sampling-Based Path Planning on Configuration-Space Costmaps, in IEEE TRANSACTIONS ON ROBOTICS, VOL. 26, NO. 4, AUGUST 2010. DOI: 10.1109/TRO.2010.2049527
[PDF]

D. Devaurs, T. Siméon, J. Cortés, Enhancing the Transition-based RRT to Deal with Complex Cost Spaces, in IEEE International Conference on Robotics and Automation, 2013, pp. 4120-4125. DOI: 10.1109/ICRA.2013.6631158
[PDF]

Definition at line 147 of file TRRT.h.

Member Function Documentation

◆ setGoalBias()

void ompl::geometric::TRRT::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 202 of file TRRT.h.

◆ setRange()

void ompl::geometric::TRRT::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 218 of file TRRT.h.

◆ transitionTest()

bool ompl::geometric::TRRT::transitionTest ( const base::Cost motionCost)
protected

Filter irrelevant configuration regarding the search of low-cost paths before inserting into tree.

Parameters
motionCost- cost of the motion to be evaluated

Definition at line 385 of file TRRT.cpp.


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