Class LazyLBTRRT

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

class LazyLBTRRT : public ompl::base::Planner

Rapidly-exploring Random Trees.

Public Functions

LazyLBTRRT(const base::SpaceInformationPtr &si)

Constructor.

~LazyLBTRRT() 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 std::string getIterationCount() const
inline std::string getBestCost() const

Protected Types

using WeightProperty = boost::property<boost::edge_weight_t, double>
using BoostGraph = boost::adjacency_list<boost::vecS, boost::vecS, boost::undirectedS, std::size_t, WeightProperty>
using LPAstarApx = LPAstarOnGraph<BoostGraph, CostEstimatorApx>
using LPAstarLb = LPAstarOnGraph<BoostGraph, CostEstimatorLb>

Protected Functions

void sampleBiased(const base::GoalSampleableRegion *goal_s, base::State *rstate)

sample with goal biasing

void freeMemory()

Free the memory allocated by this planner.

inline double distanceFunction(const base::State *a, const base::State *b) const

Compute distance between motions (actually distance between contained states)

inline double distanceFunction(const Motion *a, const Motion *b) const
inline bool checkMotion(const base::State *a, const base::State *b) const
inline bool checkMotion(const Motion *a, const Motion *b) const
inline Motion *getMotion(std::size_t id) const
inline void addVertex(const Motion *a)
inline void addEdgeApx(Motion *a, Motion *b, double c)
inline void addEdgeLb(const Motion *a, const Motion *b, double c)
inline bool edgeExistsApx(std::size_t a, std::size_t b)
inline bool edgeExistsApx(const Motion *a, const Motion *b)
inline bool edgeExistsLb(const Motion *a, const Motion *b)
inline void removeEdgeLb(const Motion *a, const Motion *b)
std::tuple<Motion*, base::State*, double> rrtExtend(const base::GoalSampleableRegion *goal_s, base::State *xstate, Motion *rmotion, double &approxdif)
void rrt(const base::PlannerTerminationCondition &ptc, base::GoalSampleableRegion *goal_s, base::State *xstate, Motion *rmotion, double &approxdif)
Motion *createMotion(const base::GoalSampleableRegion *goal_s, const base::State *st)
Motion *createGoalMotion(const base::GoalSampleableRegion *goal_s)
void closeBounds(const base::PlannerTerminationCondition &ptc)
inline double getApproximationFactor() const

Get the apprimation factor.

Protected Attributes

base::StateSamplerPtr sampler_

State sampler.

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)

double maxDistance_ = {0.}

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

RNG rng_

The random number generator.

double epsilon_ = {.4}

approximation factor

Motion *lastGoalMotion_ = {nullptr}

The most recent goal motion. Used for PlannerData computation.

BoostGraph graphLb_
BoostGraph graphApx_
Motion *startMotion_
Motion *goalMotion_ = {nullptr}
LPAstarApx *LPAstarApx_ = {nullptr}
LPAstarLb *LPAstarLb_ = {nullptr}
std::vector<Motion*> idToMotionMap_
unsigned int iterations_ = {0}

Number of iterations the algorithm performed.

double bestCost_

Best cost found so far by algorithm.

Friends

friend class CostEstimatorApx
class CostEstimatorApx

Public Functions

inline CostEstimatorApx(LazyLBTRRT *alg)
inline double operator()(std::size_t i)
class CostEstimatorLb

Public Functions

inline CostEstimatorLb(base::Goal *goal, std::vector<Motion*> &idToMotionMap)
inline double operator()(std::size_t i)
class Motion

Representation of a motion.

Public Functions

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

Constructor that allocates memory for the state.

~Motion() = default

Public Members

std::size_t id_

The id of the motion.

base::State *state_ = {nullptr}

The state contained by the motion.