Class TRRT

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

class TRRT : public ompl::base::Planner

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, 2013, pp. 4120-4125. DOI:

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]

Public Functions

TRRT(const base::SpaceInformationPtr &si)

Constructor.

~TRRT() override
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 &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.

virtual void clear() override

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

inline void setGoalBias(double goalBias)

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.

inline double getGoalBias() const

Get the goal bias the planner is using.

inline void setRange(double distance)

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.

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 rises based on current acceptance/rejection rate.

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 beginning of the algorithm. Should be high to allow for initial exploration.

inline double getInitTemperature() const

Get the temperature at the start of planning.

inline void setFrontierThreshold(double frontier_threshold)

Set the distance between a new state and the nearest neighbor that qualifies that state as being a frontier.

inline double getFrontierThreshold() const

Get the distance between a new state and the nearest neighbor that qualifies that state as being a frontier.

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

inline 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>
inline void setNearestNeighbors()

Set a different nearest neighbors datastructure.

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.

Protected Functions

void freeMemory()

Free the memory allocated by this planner.

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

Parameters:

motionCost – - cost of the motion to be evaluated

bool minExpansionControl(double randMotionDistance)

Use ratio to prefer frontier nodes to nonfrontier ones.

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.

Motion *lastGoalMotion_ = {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.

class Motion

Representation of a motion.

This only contains pointers to parent motions as we only need to go backwards in the tree.

Public Functions

Motion() = default
inline Motion(const base::SpaceInformationPtr &si)

Constructor that allocates memory for the state.

~Motion() = default

Public Members

base::State *state = {nullptr}

The state contained by the motion.

Motion *parent = {nullptr}

The parent motion in the exploration tree.

base::Cost cost

Cost of the state.