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

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

Inheritance diagram for ompl::geometric::BiTRRT:

Classes

class  Motion
 Representation of a motion in the search tree. More...
 

Public Member Functions

 BiTRRT (const base::SpaceInformationPtr &si)
 Constructor.
 
void clear () override
 Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
 
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.
 
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 &ptc) 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 setRange (double distance)
 Set the maximum possible length of any one motion in the search tree. Very short/long motions may inhibit the exploratory capabilities of the planner.
 
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 is increased after a failed transition.
 
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 start of planning. Should be high to allow for initial exploration.
 
double getInitTemperature () const
 Get the initial temperature at the start of planning.
 
void setFrontierThreshold (double frontierThreshold)
 Set the distance between a new state and the nearest neighbor that qualifies a state as being a frontier node.
 
double getFrontierThreshold () const
 Get the distance between a new state and the nearest neighbor that qualifies a state as being a frontier node.
 
void setFrontierNodeRatio (double frontierNodeRatio)
 Set the ratio between adding non-frontier nodes to frontier nodes. For example: .1 is one non-frontier node for every 10 frontier nodes added.
 
double getFrontierNodeRatio () const
 Get the ratio between adding non-frontier nodes to frontier nodes.
 
template<template< typename T > class NN>
void setNearestNeighbors ()
 Set a different nearest neighbors datastructure.
 
- 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 Types

enum  GrowResult { FAILED, ADVANCED, SUCCESS }
 The result of a call to extendTree. More...
 
using TreeData = std::shared_ptr< NearestNeighbors< Motion * > >
 The nearest-neighbors data structure that contains the entire the tree of motions generated during planning.
 

Protected Member Functions

void freeMemory ()
 Free all memory allocated during planning.
 
MotionaddMotion (const base::State *state, TreeData &tree, Motion *parent=nullptr)
 Add a state to the given tree. The motion created is returned.
 
bool transitionTest (const base::Cost &motionCost)
 Transition test that filters transitions based on the motion cost. If the motion cost is near or below zero, the motion is always accepted, otherwise a probabilistic criterion based on the temperature and motionCost is used.
 
bool minExpansionControl (double dist)
 Use frontier node ratio to filter nodes that do not add new information to the search tree.
 
GrowResult extendTree (Motion *toMotion, TreeData &tree, Motion *&result)
 Extend tree toward the state in rmotion. Store the result of the extension, if any, in result.
 
GrowResult extendTree (Motion *nearest, TreeData &tree, Motion *toMotion, Motion *&result)
 Extend tree from nearest toward toMotion. Store the result of the extension, if any, in result.
 
bool connectTrees (Motion *nmotion, TreeData &tree, Motion *xmotion)
 Attempt to connect tree to nmotion, which is in the other tree. xmotion is scratch space and will be overwritten.
 
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

double maxDistance_ {0.}
 The maximum length of a motion to be added to a tree.
 
double tempChangeFactor_
 The factor by which the temperature is increased after a failed transition test.
 
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_ {std::numeric_limits<double>::infinity()}
 All motion costs must be better than this cost (default is infinity)
 
double initTemperature_ {100.}
 The temperature that planning begins at.
 
double frontierThreshold_ {0.}
 The distance between an existing state and a new state that qualifies it as a frontier state.
 
double frontierNodeRatio_ {.1}
 The target ratio of non-frontier nodes to frontier nodes.
 
double temp_
 The current temperature.
 
double nonfrontierCount_
 A count of the number of non-frontier nodes in the trees.
 
double frontierCount_
 A count of the number of frontier nodes in the trees.
 
double connectionRange_
 The range at which the algorithm will attempt to connect the two trees.
 
std::pair< Motion *, Motion * > connectionPoint_ {nullptr, nullptr}
 The most recent connection point for the two trees. Used for PlannerData computation.
 
TreeData tStart_
 The start tree.
 
TreeData tGoal_
 The goal tree.
 
ompl::base::OptimizationObjectivePtr opt_
 The objective (cost function) being optimized.
 
- 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

Bi-directional Transition-based Rapidly-exploring Random Trees.

Short description
This planner grows two T-RRTs, one from the start and one from the goal, and attempts to connect the trees somewhere in the middle. 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.
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 (ICRA), 2013, pp. 4120-4125. DOI: 10.1109/ICRA.2013.6631158
[PDF]

Definition at line 133 of file BiTRRT.h.

Member Enumeration Documentation

◆ GrowResult

The result of a call to extendTree.

Enumerator
FAILED 

No extension was possible.

ADVANCED 

Progress was made toward extension.

SUCCESS 

The desired state was reached during extension.

Definition at line 328 of file BiTRRT.h.


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