Classes |
Public Member Functions |
Protected Types |
Protected Member Functions |
Protected Attributes |
List of all members
ompl::geometric::RRTConnect Class Reference
RRT-Connect (RRTConnect) More...
#include <ompl/geometric/planners/rrt/RRTConnect.h>
Inheritance diagram for ompl::geometric::RRTConnect:
Classes | |
class | Motion |
Representation of a motion. More... | |
struct | TreeGrowingInfo |
Information attached to growing a tree of motions (used internally) More... | |
Public Member Functions | |
RRTConnect (const base::SpaceInformationPtr &si, bool addIntermediateStates=false) | |
Constructor. | |
void | getPlannerData (base::PlannerData &data) const override |
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). | |
base::PlannerStatus | solve (const base::PlannerTerminationCondition &ptc) override |
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). If clearQuery() is called, the planner may retain prior datastructures generated from a previous query on a new problem definition. The function terminates if the call to ptc returns true. | |
void | clear () override |
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work. | |
bool | getIntermediateStates () const |
Return true if the intermediate states generated along motions are to be added to the tree itself. | |
void | setIntermediateStates (bool addIntermediateStates) |
Specify whether the intermediate states generated along motions are to be added to the tree itself. | |
void | setRange (double distance) |
Set the range the planner is supposed to use. More... | |
double | getRange () const |
Get the range the planner is using. | |
template<template< typename T > class NN> | |
void | setNearestNeighbors () |
Set a different nearest neighbors datastructure. | |
void | setup () override |
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. | |
Public Member Functions inherited from ompl::base::Planner | |
Planner (const Planner &)=delete | |
Planner & | operator= (const Planner &)=delete |
Planner (SpaceInformationPtr si, std::string name) | |
Constructor. | |
virtual | ~Planner ()=default |
Destructor. | |
template<class T > | |
T * | as () |
Cast this instance to a desired type. More... | |
template<class T > | |
const T * | as () const |
Cast this instance to a desired type. More... | |
const SpaceInformationPtr & | getSpaceInformation () const |
Get the space information this planner is using. | |
const ProblemDefinitionPtr & | getProblemDefinition () const |
Get the problem definition the planner is trying to solve. | |
ProblemDefinitionPtr & | getProblemDefinition () |
Get the problem definition the planner is trying to solve. | |
const PlannerInputStates & | getPlannerInputStates () const |
Get the planner input states. | |
virtual void | setProblemDefinition (const ProblemDefinitionPtr &pdef) |
Set the problem definition for the planner. The problem needs to be set before calling solve(). Note: If this problem definition replaces a previous one, it may also be necessary to call clear() or clearQuery(). | |
PlannerStatus | solve (const PlannerTerminationConditionFn &ptc, double checkInterval) |
Same as above except the termination condition is only evaluated at a specified interval. | |
PlannerStatus | solve (double solveTime) |
Same as above except the termination condition is solely a time limit: the number of seconds the algorithm is allowed to spend planning. | |
virtual void | clearQuery () |
Clears internal datastructures of any query-specific information from the previous query. Planner settings are not affected. The planner, if able, should retain all datastructures generated from previous queries that can be used to help solve the next query. Note that clear() should also clear all query-specific information along with all other datastructures in the planner. By default clearQuery() calls clear(). | |
const std::string & | getName () const |
Get the name of the planner. | |
void | setName (const std::string &name) |
Set the name of the planner. | |
const PlannerSpecs & | getSpecs () const |
Return the specifications (capabilities of this planner) | |
virtual void | checkValidity () |
Check to see if the planner is in a working state (setup has been called, a goal was set, the input states seem to be in order). In case of error, this function throws an exception. | |
bool | isSetup () const |
Check if setup() was called for this planner. | |
ParamSet & | params () |
Get the parameters for this planner. | |
const ParamSet & | params () const |
Get the parameters for this planner. | |
const PlannerProgressProperties & | getPlannerProgressProperties () const |
Retrieve a planner's planner progress property map. | |
virtual void | printProperties (std::ostream &out) const |
Print properties of the motion planner. | |
virtual void | printSettings (std::ostream &out) const |
Print information about the motion planner's settings. | |
Protected Types | |
enum | GrowState { TRAPPED, ADVANCED, REACHED } |
The state of the tree after an attempt to extend it. More... | |
using | TreeData = std::shared_ptr< NearestNeighbors< Motion * > > |
A nearest-neighbor datastructure representing a tree of motions. | |
Protected Member Functions | |
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) | |
GrowState | growTree (TreeData &tree, TreeGrowingInfo &tgi, Motion *rmotion) |
Grow a tree towards a random state. | |
Protected Member Functions inherited from ompl::base::Planner | |
template<typename T , typename PlannerType , typename SetterType , typename GetterType > | |
void | declareParam (const std::string &name, const PlannerType &planner, const SetterType &setter, const GetterType &getter, const std::string &rangeSuggestion="") |
This function declares a parameter for this planner instance, and specifies the setter and getter functions. | |
template<typename T , typename PlannerType , typename SetterType > | |
void | declareParam (const std::string &name, const PlannerType &planner, const SetterType &setter, const std::string &rangeSuggestion="") |
This function declares a parameter for this planner instance, and specifies the setter function. | |
void | addPlannerProgressProperty (const std::string &progressPropertyName, const PlannerProgressProperty &prop) |
Add a planner progress property called progressPropertyName with a property querying function prop to this planner's progress property map. | |
Protected Attributes | |
base::StateSamplerPtr | sampler_ |
State sampler. | |
TreeData | tStart_ |
The start tree. | |
TreeData | tGoal_ |
The goal tree. | |
bool | startTree_ {true} |
A flag that toggles between expanding the start tree (true) or goal tree (false). | |
double | maxDistance_ {0.} |
The maximum length of a motion to be added to a tree. | |
bool | addIntermediateStates_ |
Flag indicating whether intermediate states are added to the built tree of motions. | |
RNG | rng_ |
The random number generator. | |
std::pair< base::State *, base::State * > | connectionPoint_ |
The pair of states in each tree connected during planning. Used for PlannerData computation. | |
double | distanceBetweenTrees_ |
Distance between the nearest pair of start tree and goal tree nodes. | |
Protected Attributes inherited from ompl::base::Planner | |
SpaceInformationPtr | si_ |
The space information for which planning is done. | |
ProblemDefinitionPtr | pdef_ |
The user set problem definition. | |
PlannerInputStates | pis_ |
Utility class to extract valid input states | |
std::string | name_ |
The name of this planner. | |
PlannerSpecs | specs_ |
The specifications of the planner (its capabilities) | |
ParamSet | params_ |
A map from parameter names to parameter instances for this planner. This field is populated by the declareParam() function. | |
PlannerProgressProperties | plannerProgressProperties_ |
A mapping between this planner's progress property names and the functions used for querying those progress properties. | |
bool | setup_ |
Flag indicating whether setup() has been called. | |
Additional Inherited Members | |
Public Types inherited from ompl::base::Planner | |
using | PlannerProgressProperty = std::function< std::string()> |
Definition of a function which returns a property about the planner's progress that can be queried by a benchmarking routine. | |
using | PlannerProgressProperties = std::map< std::string, PlannerProgressProperty > |
A dictionary which maps the name of a progress property to the function to be used for querying that property. | |
Detailed Description
RRT-Connect (RRTConnect)
- Short description
- The basic idea is to grow two RRTs, one from the start and one from the goal, and attempt to connect them.
- External documentation
- J. Kuffner and S.M. LaValle, RRT-connect: An efficient approach to single-query path planning, in Proc. 2000 IEEE Intl. Conf. on Robotics and Automation, pp. 995–1001, Apr. 2000. DOI: 10.1109/ROBOT.2000.844730
[PDF] [more]
Definition at line 125 of file RRTConnect.h.
Member Enumeration Documentation
◆ GrowState
|
protected |
The state of the tree after an attempt to extend it.
Enumerator | |
---|---|
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 245 of file RRTConnect.h.
Member Function Documentation
◆ setRange()
|
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 190 of file RRTConnect.h.
The documentation for this class was generated from the following files:
- ompl/geometric/planners/rrt/RRTConnect.h
- ompl/geometric/planners/rrt/src/RRTConnect.cpp