All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator

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

#include <BallTreeRRTstar.h>

Inheritance diagram for ompl::geometric::BallTreeRRTstar:

List of all members.

Classes

class  Motion
 Representation of a motion. More...

Public Member Functions

 BallTreeRRTstar (const base::SpaceInformationPtr &si)
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 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 void clear (void)
 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 (void) const
 Get the goal bias the planner is using.
void setRange (double distance)
 Set the range the planner is supposed to use.
double getRange (void) const
 Get the range the planner is using.
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.
double getBallRadiusConstant (void) const
 Get the multiplicative factor used in the computation of the radius whithin which tree rewiring is done.
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.
double getMaxBallRadius (void) const
 Get the maximum radius the planner uses in the tree rewiring step.
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.
double getInitialVolumeRadius (void) const
 Get the initial volume radius.
bool inVolume (base::State *state)
 Verify if a state is inside an existing volume.
template<template< typename T > class NN>
void setNearestNeighbors (void)
 Set a different nearest neighbors datastructure.
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.
bool getDelayCC (void) const
 Get the state of the delayed collision checking option.
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.

Protected Member Functions

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

Static Protected Member Functions

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

Protected Attributes

base::StateSamplerPtr sampler_
 State sampler.
boost::shared_ptr
< NearestNeighbors< Motion * > > 
nn_
 A nearest-neighbors datastructure containing the tree of motions.
std::vector< Motion * > motions_
 A copy of the list of motions in the tree used for faser verification of samples.
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.
RNG rng_
 The random number generator.
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 rO_
 Initial radius of volumes assigned to new vertices in the tree.

Detailed Description

Optimal Rapidly-exploring Random Trees with Ball Trees.

      @par Short description
      Implementation of \ref gRRTstar "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.

      @par 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.
      \n\n S. Karaman and E. Frazzoli, Sampling-based
      Algorithms for Optimal Motion Planning, International Journal of Robotics
      Research (to appear), 2011.
      <a href="http://arxiv.org/abs/1105.1186">http://arxiv.org/abs/1105.1186</a>

Definition at line 80 of file BallTreeRRTstar.h.


Member Function Documentation

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 117 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 133 of file BallTreeRRTstar.h.


The documentation for this class was generated from the following files: