Class BiTRRT
Defined in File BiTRRT.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public ompl::base::Planner
(Class Planner)
Class Documentation
-
class BiTRRT : public ompl::base::Planner
Bi-directional Transition-based Rapidly-exploring Random Trees.
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:
- 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]
Public Functions
-
BiTRRT(const base::SpaceInformationPtr &si)
Constructor.
-
~BiTRRT() override
-
virtual void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
-
virtual 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.
-
virtual 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).
-
virtual 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.
-
inline 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.
-
inline double getRange() const
Get the range the planner is using.
-
inline 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.
-
inline double getTempChangeFactor() const
Get the factor by which the temperature is increased after a failed transition.
-
inline 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.
-
inline 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. */.
-
inline void setInitTemperature(double initTemperature)
Set the initial temperature at the start of planning. Should be high to allow for initial exploration.
-
inline double getInitTemperature() const
Get the initial temperature at the start of planning.
-
inline void setFrontierThreshold(double frontierThreshold)
Set the distance between a new state and the nearest neighbor that qualifies a state as being a frontier node.
-
inline double getFrontierThreshold() const
Get the distance between a new state and the nearest neighbor that qualifies a state as being a frontier node.
-
inline 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.
-
inline double getFrontierNodeRatio() const
Get the ratio between adding non-frontier nodes to frontier nodes.
-
template<template<typename T> class NN>
inline void setNearestNeighbors() Set a different nearest neighbors datastructure.
Protected Types
-
enum GrowResult
The result of a call to extendTree.
Values:
-
enumerator FAILED
No extension was possible.
-
enumerator ADVANCED
Progress was made toward extension.
-
enumerator SUCCESS
The desired state was reached during extension.
-
enumerator FAILED
-
using TreeData = std::shared_ptr<NearestNeighbors<Motion*>>
The nearest-neighbors data structure that contains the entire the tree of motions generated during planning.
Protected Functions
-
void freeMemory()
Free all memory allocated during planning.
-
Motion *addMotion(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.
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 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.
-
ompl::base::OptimizationObjectivePtr opt_
The objective (cost function) being optimized.
-
class Motion
Representation of a motion in the search tree.
Public Functions
-
Motion() = default
Default constructor.
-
inline Motion(const base::SpaceInformationPtr &si)
Constructor that allocates memory for the state.
-
~Motion() = default
-
Motion() = default