Class LBTRRT

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

class LBTRRT : public ompl::base::Planner

Lower Bound Tree Rapidly-exploring Random Trees.

Short description

LBTRRT (Lower Bound Tree RRT) is a near asymptotically-optimal incremental sampling-based motion planning algorithm. LBTRRT algorithm is guaranteed to converge to a solution that is within a constant factor of the optimal solution. The notion of optimality is with respect to the distance function defined on the state space we are operating on.

External documentation

O. Salzman and D. Halperin, Sampling-based Asymptotically near-optimal RRT for fast, high-quality, motion planning, 2013. [PDF]

Public Functions

LBTRRT(const base::SpaceInformationPtr &si)

Constructor.

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

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.

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.

inline void setApproximationFactor(double epsilon)

Set the apprimation factor.

inline double getApproximationFactor() const

Get the apprimation factor.

inline std::string getIterationCount() const
inline std::string getBestCost() const

Protected Functions

void considerEdge(Motion *parent, Motion *child, double c)

consider an edge for addition to the roadmap

double lazilyUpdateApxParent(Motion *child, Motion *parent)

lazily update the parent in the approximation tree without updating costs to cildren

void updateChildCostsApx(Motion *m, double delta)

update the child cost of the approximation tree

void removeFromParentApx(Motion *m)

remove motion from its parent in the approximation tree

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)

inline bool checkMotion(const Motion *a, const Motion *b)

local planner

inline bool checkMotion(const base::State *a, const base::State *b)

local planner

inline Motion *getMotion(std::size_t i)

get motion from id

Protected Attributes

base::StateSamplerPtr sampler_

State sampler.

std::shared_ptr<NearestNeighbors<Motion*>> nn_

A nearest-neighbors datastructure containing the tree of motions.

DynamicSSSP lowerBoundGraph_

A graph of motions Glb.

std::vector<Motion*> idToMotionMap_

mapping between a motion id and the motion

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.

double epsilon_ = {.4}

approximation factor

RNG rng_

The random number generator.

Motion *lastGoalMotion_ = {nullptr}

The most recent goal motion. Used for PlannerData computation.

unsigned int iterations_ = {0u}

Number of iterations the algorithm performed.

double bestCost_

Best cost found so far by algorithm.

struct IsLessThan

comparator - metric is the cost to reach state via a specific state

Public Functions

inline IsLessThan(LBTRRT *plannerPtr, Motion *motion)
inline bool operator()(const Motion *motionA, const Motion *motionB)

Public Members

LBTRRT *plannerPtr_
Motion *motion_
struct IsLessThanLB

comparator - metric is the lower bound cost

Public Functions

inline IsLessThanLB(LBTRRT *plannerPtr)
inline bool operator()(const Motion *motionA, const Motion *motionB) const

Public Members

LBTRRT *plannerPtr_
class Motion

Representation of a motion.

a motion is a simultunaeous represntation of the two trees used by LBT-RRT a lower bound tree named Tlb and an approximaion tree named Tapx.

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.

std::size_t id_

unique id of the motion

double costLb_

The lower bound cost of the motion while it is stored in the lowerBoundGraph_ and this may seem redundant, the cost in lowerBoundGraph_ may change causing ordering according to it inconsistencies.

Motion *parentApx_ = {nullptr}

The parent motion in the approximation tree.

double costApx_ = {0.0}

The approximation cost.

std::vector<Motion*> childrenApx_

The children in the approximation tree.