ompl::geometric::BallTreeRRTstar Class Reference

Optimal Rapidly-exploring Random Trees with Ball Trees. More...

#include <BallTreeRRTstar.h>

Inheritance diagram for ompl::geometric::BallTreeRRTstar:
Inheritance graph
[legend]

List of all members.

Classes

class  Motion
 Representation of a motion. More...

Public Member Functions

 BallTreeRRTstar (const base::SpaceInformationPtr &si)
virtual void clear (void)
 Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
double getBallRadiusConstant (void) const
 Get the multiplicative factor used in the computation of the radius whithin which tree rewiring is done.
bool getDelayCC (void) const
 Get the state of the delayed collision checking option.
double getGoalBias (void) const
 Get the goal bias the planner is using.
double getInitialVolumeRadius (void) const
 Get the initial volume radius.
double getMaxBallRadius (void) const
 Get the maximum radius the planner uses in the tree rewiring step.
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).
double getRange (void) const
 Get the range the planner is using.
bool getTerminate (void) const
 Get the state of the termination option.
bool inVolume (base::State *state)
 Verify if a state is inside an existing volume.
void setBallRadiusConstant (double ballRadiusConstant)
 When the planner attempts to rewire the tree, it does so by looking at some of the neighbors within a computed radius. The computation of that radius depends on the multiplicative factor set here. Set this parameter should be set at least to the side length of the (bounded) state space. E.g., if the state space is a box with side length L, then this parameter should be set to at least L for rapid and efficient convergence in trajectory space.
void setDelayCC (bool delayCC)
 Option that delays collision checking procedures. When it is enabled, all neighbors are sorted by cost. The planner then goes through this list, starting with the lowest cost, checking for collisions in order to find a parent. The planner stops iterating through the list when a collision free parent is found. This prevents the planner from collsion checking each neighbor, reducing computation time in scenarios where collision checking procedures are expensive.
void setGoalBias (double goalBias)
 Set the goal bias.
void setInitialVolumeRadius (double rO)
 Each vertex in the tree has a volume (hyper-sphere) associated with it. The radius of said volume is decreased when collisions are found within it. Samples found within any of the existing volumes are rejected. The value set here is the initial radius assigned to volumes added to the tree.
void setMaxBallRadius (double maxBallRadius)
 When the planner attempts to rewire the tree, it does so by looking at some of the neighbors within a computed radius. That radius is bounded by the value set here. This parameter should ideally be equal longest straight line from the initial state to anywhere in the state space. In other words, this parameter should be "sqrt(d) L", where d is the dimensionality of space and L is the side length of a box containing the obstacle free space.
template<template< typename T > class NN>
void setNearestNeighbors (void)
 Set a different nearest neighbors datastructure.
void setRange (double distance)
 Set the range the planner is supposed to use.
void setTerminate (bool terminate)
 Option that specifies if the planner will terminate upon finding a solution or will continue to refine the solution until the time limit is reached. Set true to terminate when a solution is found.
virtual void setup (void)
 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.
virtual bool 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 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 ~BallTreeRRTstar (void)

Protected Member Functions

void addMotion (Motion *m)
 Add a motion to the tree.
double distanceFunction (const Motion *a, const Motion *b) const
 Distance calculation considering volumes.
void freeMemory (void)
 Free the memory allocated by this planner.

Static Protected Member Functions

static bool compareMotion (const Motion *a, const Motion *b)
 Sort the near neighbors by cost.

Protected Attributes

double ballRadiusConst_
 Shrink rate of radius the planner uses to find near neighbors and rewire.
double ballRadiusMax_
 Maximum radius the planner uses to find near neighbors and rewire.
bool delayCC_
 Option to delay and reduce collision checking within iterations.
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.
std::vector< Motion * > motions_
 A copy of the list of motions in the tree used for faser verification of samples.
boost::shared_ptr
< NearestNeighbors< Motion * > > 
nn_
 A nearest-neighbors datastructure containing the tree of motions.
RNG rng_
 The random number generator.
double rO_
 Initial radius of volumes assigned to new vertices in the tree.
base::StateSamplerPtr sampler_
 State sampler.
bool terminate_
 Option to terminate planning when a solution is found.

Detailed Description

Optimal Rapidly-exploring Random Trees with Ball Trees.

Short description
Implementation of RRT* that incorporates Ball Trees to approximate connected regions of free space with volumes in configuration space instead of points. Every vertex added to the tree has an initial volume of an infinite radius associated with it. This radius is gradually reduced as collisions are found. All samples within any of the existing volumes are discarded. However, discarded samples are collision checked. If a collision is found, the nearest volume is trimmed at the collision point. Information from all collision checking procedures within iterations is also used to trim volumes accordingly. The radii of volumes are considered when computing nearest/near neighbors. This implementation is suited for high-dimensional planning problems with narrow collision boundary passages.
External documentation
A. Perez, S. Karaman, M. Walter, A. Shkolnik, E. Frazzoli, S. Teller, Asymptotically-optimal Manipulation Planning using Incremental Sampling-based Algorithms, IEEE/RSJ International Conference on Intelligent Robots and Systems, 2011.

S. Karaman and E. Frazzoli, Sampling-based Algorithms for Optimal Motion Planning, International Journal of Robotics Research (to appear), 2011. http://arxiv.org/abs/1105.1186

Definition at line 71 of file BallTreeRRTstar.h.


Constructor & Destructor Documentation

ompl::geometric::BallTreeRRTstar::BallTreeRRTstar ( const base::SpaceInformationPtr si  )  [inline]

Definition at line 45 of file BallTreeRRTstar.h.

virtual ompl::geometric::BallTreeRRTstar::~BallTreeRRTstar ( void   )  [inline, virtual]

Definition at line 60 of file BallTreeRRTstar.h.


Member Function Documentation

void ompl::geometric::BallTreeRRTstar::addMotion ( Motion m  )  [inline, protected]

Add a motion to the tree.

Definition at line 256 of file BallTreeRRTstar.h.

virtual void ompl::geometric::BallTreeRRTstar::clear ( void   )  [virtual]

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

Reimplemented from ompl::base::Planner.

static bool ompl::geometric::BallTreeRRTstar::compareMotion ( const Motion a,
const Motion b 
) [inline, static, protected]

Sort the near neighbors by cost.

Definition at line 263 of file BallTreeRRTstar.h.

double ompl::geometric::BallTreeRRTstar::distanceFunction ( const Motion a,
const Motion b 
) const [inline, protected]

Distance calculation considering volumes.

Definition at line 268 of file BallTreeRRTstar.h.

void ompl::geometric::BallTreeRRTstar::freeMemory ( void   )  [protected]

Free the memory allocated by this planner.

double ompl::geometric::BallTreeRRTstar::getBallRadiusConstant ( void   )  const [inline]

Get the multiplicative factor used in the computation of the radius whithin which tree rewiring is done.

Definition at line 124 of file BallTreeRRTstar.h.

bool ompl::geometric::BallTreeRRTstar::getDelayCC ( void   )  const [inline]

Get the state of the delayed collision checking option.

Definition at line 196 of file BallTreeRRTstar.h.

double ompl::geometric::BallTreeRRTstar::getGoalBias ( void   )  const [inline]

Get the goal bias the planner is using.

Definition at line 86 of file BallTreeRRTstar.h.

double ompl::geometric::BallTreeRRTstar::getInitialVolumeRadius ( void   )  const [inline]

Get the initial volume radius.

Definition at line 159 of file BallTreeRRTstar.h.

double ompl::geometric::BallTreeRRTstar::getMaxBallRadius ( void   )  const [inline]

Get the maximum radius the planner uses in the tree rewiring step.

Definition at line 144 of file BallTreeRRTstar.h.

virtual void ompl::geometric::BallTreeRRTstar::getPlannerData ( base::PlannerData data  )  const [virtual]

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

Reimplemented from ompl::base::Planner.

double ompl::geometric::BallTreeRRTstar::getRange ( void   )  const [inline]

Get the range the planner is using.

Definition at line 102 of file BallTreeRRTstar.h.

bool ompl::geometric::BallTreeRRTstar::getTerminate ( void   )  const [inline]

Get the state of the termination option.

Definition at line 211 of file BallTreeRRTstar.h.

bool ompl::geometric::BallTreeRRTstar::inVolume ( base::State state  )  [inline]

Verify if a state is inside an existing volume.

Definition at line 165 of file BallTreeRRTstar.h.

void ompl::geometric::BallTreeRRTstar::setBallRadiusConstant ( double  ballRadiusConstant  )  [inline]

When the planner attempts to rewire the tree, it does so by looking at some of the neighbors within a computed radius. The computation of that radius depends on the multiplicative factor set here. Set this parameter should be set at least to the side length of the (bounded) state space. E.g., if the state space is a box with side length L, then this parameter should be set to at least L for rapid and efficient convergence in trajectory space.

Definition at line 116 of file BallTreeRRTstar.h.

void ompl::geometric::BallTreeRRTstar::setDelayCC ( bool  delayCC  )  [inline]

Option that delays collision checking procedures. When it is enabled, all neighbors are sorted by cost. The planner then goes through this list, starting with the lowest cost, checking for collisions in order to find a parent. The planner stops iterating through the list when a collision free parent is found. This prevents the planner from collsion checking each neighbor, reducing computation time in scenarios where collision checking procedures are expensive.

Definition at line 190 of file BallTreeRRTstar.h.

void ompl::geometric::BallTreeRRTstar::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.

Definition at line 80 of file BallTreeRRTstar.h.

void ompl::geometric::BallTreeRRTstar::setInitialVolumeRadius ( double  rO  )  [inline]

Each vertex in the tree has a volume (hyper-sphere) associated with it. The radius of said volume is decreased when collisions are found within it. Samples found within any of the existing volumes are rejected. The value set here is the initial radius assigned to volumes added to the tree.

Definition at line 153 of file BallTreeRRTstar.h.

void ompl::geometric::BallTreeRRTstar::setMaxBallRadius ( double  maxBallRadius  )  [inline]

When the planner attempts to rewire the tree, it does so by looking at some of the neighbors within a computed radius. That radius is bounded by the value set here. This parameter should ideally be equal longest straight line from the initial state to anywhere in the state space. In other words, this parameter should be "sqrt(d) L", where d is the dimensionality of space and L is the side length of a box containing the obstacle free space.

Definition at line 137 of file BallTreeRRTstar.h.

template<template< typename T > class NN>
void ompl::geometric::BallTreeRRTstar::setNearestNeighbors ( void   )  [inline]

Set a different nearest neighbors datastructure.

Definition at line 178 of file BallTreeRRTstar.h.

void ompl::geometric::BallTreeRRTstar::setRange ( double  distance  )  [inline]

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.

Definition at line 96 of file BallTreeRRTstar.h.

void ompl::geometric::BallTreeRRTstar::setTerminate ( bool  terminate  )  [inline]

Option that specifies if the planner will terminate upon finding a solution or will continue to refine the solution until the time limit is reached. Set true to terminate when a solution is found.

Definition at line 205 of file BallTreeRRTstar.h.

virtual void ompl::geometric::BallTreeRRTstar::setup ( void   )  [virtual]

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.

Reimplemented from ompl::base::Planner.

virtual bool ompl::geometric::BallTreeRRTstar::solve ( const base::PlannerTerminationCondition ptc  )  [virtual]

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

Implements ompl::base::Planner.


Member Data Documentation

Shrink rate of radius the planner uses to find near neighbors and rewire.

Definition at line 292 of file BallTreeRRTstar.h.

Maximum radius the planner uses to find near neighbors and rewire.

Definition at line 295 of file BallTreeRRTstar.h.

Option to delay and reduce collision checking within iterations.

Definition at line 298 of file BallTreeRRTstar.h.

The fraction of time the goal is picked as the state to expand towards (if such a state is available).

Definition at line 283 of file BallTreeRRTstar.h.

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

Definition at line 286 of file BallTreeRRTstar.h.

A copy of the list of motions in the tree used for faser verification of samples.

Definition at line 280 of file BallTreeRRTstar.h.

A nearest-neighbors datastructure containing the tree of motions.

Definition at line 277 of file BallTreeRRTstar.h.

The random number generator.

Definition at line 289 of file BallTreeRRTstar.h.

Initial radius of volumes assigned to new vertices in the tree.

Definition at line 301 of file BallTreeRRTstar.h.

State sampler.

Definition at line 274 of file BallTreeRRTstar.h.

Option to terminate planning when a solution is found.

Definition at line 304 of file BallTreeRRTstar.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


ompl
Author(s): Ioan Sucan/isucan@rice.edu, Mark Moll/mmoll@rice.edu, Lydia Kavraki/kavraki@rice.edu
autogenerated on Fri Jan 11 11:37:49 2013