RRT-Connect (RRTConnect). More...
#include <RRTConnect.h>
Classes | |
class | Motion |
Representation of a motion. More... | |
struct | TreeGrowingInfo |
Information attached to growing a tree of motions (used internally). More... | |
Public Member Functions | |
virtual void | clear (void) |
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work. | |
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. | |
RRTConnect (const base::SpaceInformationPtr &si) | |
Constructor. | |
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. | |
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 | ~RRTConnect (void) |
Protected Types | |
enum | GrowState { TRAPPED, ADVANCED, REACHED } |
The state of the tree after an attempt to extend it. More... | |
typedef boost::shared_ptr < NearestNeighbors< Motion * > > | TreeData |
A nearest-neighbor datastructure representing a tree of motions. | |
Protected Member Functions | |
double | distanceFunction (const Motion *a, const Motion *b) const |
Compute distance between motions (actually distance between contained states). | |
void | freeMemory (void) |
Free the memory allocated by this planner. | |
GrowState | growTree (TreeData &tree, TreeGrowingInfo &tgi, Motion *rmotion) |
Grow a tree towards a random state. | |
Protected Attributes | |
double | maxDistance_ |
The maximum length of a motion to be added to a tree. | |
RNG | rng_ |
The random number generator. | |
base::StateSamplerPtr | sampler_ |
State sampler. | |
TreeData | tGoal_ |
The goal tree. | |
TreeData | tStart_ |
The start tree. |
RRT-Connect (RRTConnect).
Definition at line 63 of file RRTConnect.h.
typedef boost::shared_ptr< NearestNeighbors<Motion*> > ompl::geometric::RRTConnect::TreeData [protected] |
A nearest-neighbor datastructure representing a tree of motions.
Definition at line 139 of file RRTConnect.h.
enum ompl::geometric::RRTConnect::GrowState [protected] |
The state of the tree after an attempt to extend it.
TRAPPED |
no progress has been made |
ADVANCED |
progress has been made towards the randomly sampled state |
REACHED |
the randomly sampled state was reached |
Definition at line 149 of file RRTConnect.h.
ompl::geometric::RRTConnect::RRTConnect | ( | const base::SpaceInformationPtr & | si | ) | [inline] |
Constructor.
Definition at line 68 of file RRTConnect.h.
virtual ompl::geometric::RRTConnect::~RRTConnect | ( | void | ) | [inline, virtual] |
Definition at line 74 of file RRTConnect.h.
virtual void ompl::geometric::RRTConnect::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.
double ompl::geometric::RRTConnect::distanceFunction | ( | const Motion * | a, | |
const Motion * | b | |||
) | const [inline, protected] |
Compute distance between motions (actually distance between contained states).
Definition at line 163 of file RRTConnect.h.
void ompl::geometric::RRTConnect::freeMemory | ( | void | ) | [protected] |
Free the memory allocated by this planner.
virtual void ompl::geometric::RRTConnect::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::RRTConnect::getRange | ( | void | ) | const [inline] |
Get the range the planner is using.
Definition at line 96 of file RRTConnect.h.
GrowState ompl::geometric::RRTConnect::growTree | ( | TreeData & | tree, | |
TreeGrowingInfo & | tgi, | |||
Motion * | rmotion | |||
) | [protected] |
Grow a tree towards a random state.
void ompl::geometric::RRTConnect::setNearestNeighbors | ( | void | ) | [inline] |
Set a different nearest neighbors datastructure.
Definition at line 103 of file RRTConnect.h.
void ompl::geometric::RRTConnect::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 90 of file RRTConnect.h.
virtual void ompl::geometric::RRTConnect::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::RRTConnect::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.
double ompl::geometric::RRTConnect::maxDistance_ [protected] |
The maximum length of a motion to be added to a tree.
Definition at line 181 of file RRTConnect.h.
RNG ompl::geometric::RRTConnect::rng_ [protected] |
The random number generator.
Definition at line 184 of file RRTConnect.h.
State sampler.
Definition at line 172 of file RRTConnect.h.
TreeData ompl::geometric::RRTConnect::tGoal_ [protected] |
The goal tree.
Definition at line 178 of file RRTConnect.h.
TreeData ompl::geometric::RRTConnect::tStart_ [protected] |
The start tree.
Definition at line 175 of file RRTConnect.h.