Classes |
Public Member Functions |
Protected Member Functions |
Protected Attributes |
Static Protected Attributes
ompl::geometric::LBTRRT Class Reference
Lower Bound Tree Rapidly-exploring Random Trees. More...
#include <ompl/geometric/planners/rrt/LBTRRT.h>
Inheritance diagram for ompl::geometric::LBTRRT:

Classes | |
struct | CostCompare |
class | Motion |
Representation of a motion. More... | |
Public Member Functions | |
LBTRRT (const base::SpaceInformationPtr &si) | |
Constructor. | |
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). 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. | |
void | setGoalBias (double goalBias) |
Set the goal bias. | |
double | getGoalBias () const |
Get the goal bias the planner is using. | |
void | setRange (double distance) |
Set the range the planner is supposed to use. | |
double | getRange () const |
Get the range the planner is using. | |
template<template< typename T > class NN> | |
void | setNearestNeighbors () |
Set a different nearest neighbors datastructure. | |
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. | |
void | setApproximationFactor (double epsilon) |
Set the apprimation factor. | |
double | getApproximationFactor () const |
Get the apprimation factor. | |
std::string | getIterationCount () const |
std::string | getBestCost () const |
Protected Member Functions | |
bool | attemptNodeUpdate (Motion *potentialParent, Motion *child) |
attempt to rewire the trees | |
void | updateChildCostsLb (Motion *m) |
update the child cost of the lower bound tree | |
void | updateChildCostsApx (Motion *m) |
update the child cost of the approximation tree | |
void | removeFromParentLb (Motion *m) |
remove motion from its parent in the lower bound tree | |
void | removeFromParentApx (Motion *m) |
remove motion from its parent in the approximation tree | |
void | removeFromParent (const Motion *m, std::vector< Motion * > &vec) |
remove motion from a vector | |
void | freeMemory () |
Free the memory allocated by this planner. | |
double | distanceFunction (const Motion *a, const Motion *b) const |
Compute distance between motions (actually distance between contained states) | |
base::Cost | costFunction (const Motion *a, const Motion *b) const |
Protected Attributes | |
base::StateSamplerPtr | sampler_ |
State sampler. | |
boost::shared_ptr < NearestNeighbors< Motion * > > | nn_ |
A nearest-neighbors datastructure containing the tree of motions. | |
double | goalBias_ |
The fraction of time the goal is picked as the state to expand towards (if such a state is available) | |
double | maxDistance_ |
The maximum length of a motion to be added to a tree. | |
double | epsilon_ |
approximation factor | |
RNG | rng_ |
The random number generator. | |
base::OptimizationObjectivePtr | opt_ |
Objective we're optimizing. | |
Motion * | lastGoalMotion_ |
The most recent goal motion. Used for PlannerData computation. | |
std::vector< Motion * > | goalMotions_ |
A list of states in the tree that satisfy the goal condition. | |
unsigned int | iterations_ |
Number of iterations the algorithm performed. | |
base::Cost | bestCost_ |
Best cost found so far by algorithm. | |
Static Protected Attributes | |
static const double | kRRG = 5.5 |
kRRG = 2e~5.5 is a valid choice for all problem instances |
Detailed Description
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]](http://arxiv.org/abs/1308.0189)
Member Function Documentation
void ompl::geometric::LBTRRT::setGoalBias | ( | double | goalBias | ) | [inline] |
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.
void ompl::geometric::LBTRRT::setRange | ( | double | distance | ) | [inline] |
The documentation for this class was generated from the following files:
- ompl/geometric/planners/rrt/LBTRRT.h
- ompl/geometric/planners/rrt/src/LBTRRT.cpp