Class BiRLRT

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

class BiRLRT : public ompl::base::Planner

Bi-directional Range-Limited Random Tree (Ryan Luna’s Random Tree)

BiRLRT is a basic bidirectional tree-based planner without any sophistic heuristics to guide the exploration. It should be used as a baseline for comparison against other bidirectional tree-based planners. In high-dimensional search spaces it can sometimes perform surprisingly well.

Associated publication:

R. Luna, M. Moll, J. Badger, and L. E. Kavraki, A Scalable Motion Planner for High-Dimensional Kinematic Systems, Intl. J. of Robotics Research, vol. 39, issue 4, pp. 361-388, Mar. 2020. DOI: 10.1177/0278364919890408[PDF]

Public Functions

BiRLRT(const base::SpaceInformationPtr &si)
virtual ~BiRLRT()
virtual void getPlannerData(base::PlannerData &data) const

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)

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

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

inline void setRange(double distance)

Set the maximum distance between states in the tree.

inline double getRange() const

Get the maximum distance between states in the tree.

inline void setMaxDistanceNear(double dNear)

Set the maximum distance (per dimension) when sampling near an existing state.

inline double getMaxDistanceNear() const

Get the maximum distance (per dimension) when sampling near an existing state.

inline bool getKeepLast() const

If true, the planner will not have the range limitation. Instead, if a collision is detected, the last valid state is retained.

inline void setKeepLast(bool keepLast)

Set whether the planner will use the range or keep last heuristic. If keepLast = false, motions are limited in distance to range_, otherwise the last valid state is retained when a collision is detected.

virtual void setup()

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.

bool growTreeRangeLimited(std::vector<Motion*> &tree, Motion *xmotion)

Try to grow the tree randomly. Return true if a new state was added xmotion is scratch space for sampling, etc.

bool growTreeKeepLast(std::vector<Motion*> &tree, Motion *xmotion, std::pair<base::State*, double> &lastValid)

Try to grow the tree randomly. Return true if a new state was added xmotion is scratch space for sampling, etc.

int connectToTree(const Motion *motion, std::vector<Motion*> &tree)

Attempt to connect the given motion (presumed to be in a tree) to a state in another tree (presumed to be different from the tree motion is in). If connection is successful, the index of the motion in the other tree that the motion connects to is returned. -1 for failed connection.

Protected Attributes

std::vector<Motion*> tStart_

Start tree.

std::vector<Motion*> tGoal_

Goal tree.

base::StateSamplerPtr sampler_

State sampler.

double range_ = {0.0}

The maximum total length of a motion to be added to a tree.

double maxDistNear_ = {0.0}

The maximum distance (per dimension) when sampling near an existing configuration.

RNG rng_

The random number generator.

std::pair<base::State*, base::State*> connectionPoint_ = {nullptr, nullptr}

The pair of states in each tree connected during planning. Used for PlannerData computation.

bool keepLast_ = {false}
class Motion

A motion (tree node) with parent pointer.

Public Functions

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.

const base::State *root = {nullptr}

Pointer to the root of the tree this motion is connected to.