Class RRT

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

class RRT : public ompl::base::Planner

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]

Public Functions

RRT(const SpaceInformationPtr &si)

Constructor.

~RRT() override
virtual base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override

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

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

inline void setGoalBias(double goalBias)

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 bool getIntermediateStates() const

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

inline void setIntermediateStates(bool addIntermediateStates)

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

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

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)

Protected Attributes

base::StateSamplerPtr sampler_

State sampler.

DirectedControlSamplerPtr controlSampler_

Control sampler.

const SpaceInformation *siC_

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.

Motion *lastGoalMotion_ = {nullptr}

The most recent goal motion. Used for PlannerData computation.

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 SpaceInformation *si)

Constructor that allocates memory for the state and the control.

~Motion() = default

Public Members

base::State *state = {nullptr}

The state contained by the motion.

Control *control = {nullptr}

The control contained by the motion.

unsigned int steps = {0}

The number of steps the control is applied for.

Motion *parent = {nullptr}

The parent motion in the exploration tree.