Rapidly-exploring Random Tree. More...
#include <RRT.h>
Classes | |
class | Motion |
Representation of a motion. More... | |
Public Member Functions | |
virtual void | clear (void) |
Clear datastructures. Call this function if the input data to the planner has changed and you do not want to continue planning. | |
double | getGoalBias (void) const |
Get the goal bias the planner is using. | |
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). | |
RRT (const SpaceInformationPtr &si) | |
Constructor. | |
void | setGoalBias (double goalBias) |
template<template< typename T > class NN> | |
void | setNearestNeighbors (void) |
Set a different nearest neighbors datastructure. | |
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) |
Continue solving for some amount of time. Return true if solution was found. | |
virtual | ~RRT (void) |
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. | |
Protected Attributes | |
ControlSamplerPtr | controlSampler_ |
Control sampler. | |
double | goalBias_ |
The fraction of time the goal is picked as the state to expand towards (if such a state is available). | |
boost::shared_ptr < NearestNeighbors< Motion * > > | nn_ |
A nearest-neighbors datastructure containing the tree of motions. | |
RNG | rng_ |
The random number generator. | |
base::StateSamplerPtr | sampler_ |
State sampler. | |
const SpaceInformation * | siC_ |
The base::SpaceInformation cast as control::SpaceInformation, for convenience. |
Rapidly-exploring Random Tree.
Definition at line 69 of file control/planners/rrt/RRT.h.
ompl::control::RRT::RRT | ( | const SpaceInformationPtr & | si | ) | [inline] |
Constructor.
Definition at line 74 of file control/planners/rrt/RRT.h.
virtual ompl::control::RRT::~RRT | ( | void | ) | [inline, virtual] |
Definition at line 82 of file control/planners/rrt/RRT.h.
virtual void ompl::control::RRT::clear | ( | void | ) | [virtual] |
Clear datastructures. Call this function if the input data to the planner has changed and you do not want to continue planning.
Reimplemented from ompl::base::Planner.
double ompl::control::RRT::distanceFunction | ( | const Motion * | a, | |
const Motion * | b | |||
) | const [inline, protected] |
Compute distance between motions (actually distance between contained states).
Definition at line 165 of file control/planners/rrt/RRT.h.
void ompl::control::RRT::freeMemory | ( | void | ) | [protected] |
Free the memory allocated by this planner.
double ompl::control::RRT::getGoalBias | ( | void | ) | const [inline] |
Get the goal bias the planner is using.
Definition at line 108 of file control/planners/rrt/RRT.h.
virtual void ompl::control::RRT::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.
void ompl::control::RRT::setGoalBias | ( | double | goalBias | ) | [inline] |
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 102 of file control/planners/rrt/RRT.h.
void ompl::control::RRT::setNearestNeighbors | ( | void | ) | [inline] |
Set a different nearest neighbors datastructure.
Definition at line 117 of file control/planners/rrt/RRT.h.
virtual void ompl::control::RRT::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::control::RRT::solve | ( | const base::PlannerTerminationCondition & | ptc | ) | [virtual] |
Continue solving for some amount of time. Return true if solution was found.
Implements ompl::base::Planner.
ControlSamplerPtr ompl::control::RRT::controlSampler_ [protected] |
Control sampler.
Definition at line 174 of file control/planners/rrt/RRT.h.
double ompl::control::RRT::goalBias_ [protected] |
The fraction of time the goal is picked as the state to expand towards (if such a state is available).
Definition at line 183 of file control/planners/rrt/RRT.h.
boost::shared_ptr< NearestNeighbors<Motion*> > ompl::control::RRT::nn_ [protected] |
A nearest-neighbors datastructure containing the tree of motions.
Definition at line 180 of file control/planners/rrt/RRT.h.
RNG ompl::control::RRT::rng_ [protected] |
The random number generator.
Definition at line 186 of file control/planners/rrt/RRT.h.
base::StateSamplerPtr ompl::control::RRT::sampler_ [protected] |
State sampler.
Definition at line 171 of file control/planners/rrt/RRT.h.
const SpaceInformation* ompl::control::RRT::siC_ [protected] |
The base::SpaceInformation cast as control::SpaceInformation, for convenience.
Definition at line 177 of file control/planners/rrt/RRT.h.