Loading...
Searching...
No Matches

Modified RRT-Connect for AORRTC (AOXRRTConnect). More...

#include <ompl/geometric/planners/rrt/AOXRRTConnect.h>

Inheritance diagram for ompl::geometric::AOXRRTConnect:

Classes

class  Motion
 Representation of a motion. More...
struct  TreeGrowingInfo
 Information attached to growing a tree of motions (used internally). More...

Public Member Functions

 AOXRRTConnect (const base::SpaceInformationPtr &si)
 Constructor.
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 setFoundPath (const base::PathPtr &p)
base::PathPtr getFoundPath () const
void setRange (double distance)
 Set the range the planner is supposed to use.
double getRange () const
 Get the range the planner is using.
template<template< typename T > class NN>
void setNearestNeighbors ()
 Set a different nearest neighbors datastructure.
bool internalResetCondition ()
 Check if the inner loop planner met its condition to terminate.
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.
void reset (bool solvedProblem)
void setPathCost (double pc)
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.
template<class T>
const T * as () const
 Cast this instance to a desired type.
const SpaceInformationPtrgetSpaceInformation () const
 Get the space information this planner is using.
const ProblemDefinitionPtrgetProblemDefinition () const
 Get the problem definition the planner is trying to solve.
ProblemDefinitionPtrgetProblemDefinition ()
 Get the problem definition the planner is trying to solve.
const PlannerInputStatesgetPlannerInputStates () 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 clear ()
 Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
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().
virtual void getPlannerData (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).
const std::string & getName () const
 Get the name of the planner.
void setName (const std::string &name)
 Set the name of the planner.
const PlannerSpecsgetSpecs () 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.
ParamSetparams ()
 Get the parameters for this planner.
const ParamSetparams () const
 Get the parameters for this planner.
const PlannerProgressPropertiesgetPlannerProgressProperties () 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 euclideanDistanceFunction (const Motion *a, const Motion *b) const
 Compute euclidian distance between motions.
double aoxDistanceFunction (const Motion *a, const Motion *b) const
 Compute AOX distance between motions.
MotionfindNeighbour (Motion *sampled_motion, float rootDist, TreeData &tree)
 Find a valid neighbour with asymmetric distance funtion via iteration.
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::InformedSamplerPtr sampler_
 State sampler.
std::size_t sampleAttempts {0}
const float rootDistPadding = 0.00001
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.
long int maxResampleAttempts_ {100}
 Maximum allowed cost resampling iterations before moving on.
std::size_t maxInternalVertices {10000}
 Maximum allowed total vertices in trees before the search is restarted.
std::size_t maxInternalVerticesIncrement {10000}
 Increment by which maxVertices is increased.
std::size_t maxInternalSamples {10000000}
 Maximum samples tried before the search is restarted.
std::size_t maxInternalSamplesIncrement {10000000}
 Increment by which maxSamples is increased.
base::StatestartState {nullptr}
base::StategoalState {nullptr}
base::Cost bestCost_ {std::numeric_limits<double>::infinity()}
 Best cost found so far by algorithm.
base::PathPtr foundPath {nullptr}
 Path found by the algorithm.
base::PlannerTerminationCondition _ptc {nullptr}
 Outer loop termination condition for AORRTC.
base::OptimizationObjectivePtr opt_
 Objective we're optimizing.
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.
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

Modified RRT-Connect for AORRTC (AOXRRTConnect).

RRT-Connect

Short description
AORRTC leverages RRT-Connect to repeatedly search in a cost-augmented space, which is slowly constrained to force the planner to iteratively find better solutions. This modified RRT-Connect performs its search in the configuration space of the robot with an added cost dimension, and finds higher quality solutions than its current best solution by only allowing connections that could result in an improved solution. This is done by sampling a cost for each new sample uniformly from a range that is both reachable and can improve upon the current solution, and uses this sampled cost as an upper bound for the cost of connections to this sample/
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] T. S. Wilson, W. Thomason, Z. Kingston, and J. D. Gammell, AORRTC: Almost-surely asymptotically optimal planning with RRT-Connect, in IEEE Robotics and Automation Letters, Vol. 10, no. 12, pp. 13375-13382, Dec. 2025. DOI: 10.1109/LRA.2025.3615522
[PDF]

Definition at line 80 of file AOXRRTConnect.h.

Member Typedef Documentation

◆ TreeData

using ompl::geometric::AOXRRTConnect::TreeData = std::shared_ptr<NearestNeighbors<Motion *>>
protected

A nearest-neighbor datastructure representing a tree of motions.

Definition at line 174 of file AOXRRTConnect.h.

Member Enumeration Documentation

◆ GrowState

The state of the tree after an attempt to extend it.

Definition at line 185 of file AOXRRTConnect.h.

Constructor & Destructor Documentation

◆ AOXRRTConnect()

ompl::geometric::AOXRRTConnect::AOXRRTConnect ( const base::SpaceInformationPtr & si)

Constructor.

Definition at line 47 of file AOXRRTConnect.cpp.

◆ ~AOXRRTConnect()

ompl::geometric::AOXRRTConnect::~AOXRRTConnect ( )
override

Definition at line 57 of file AOXRRTConnect.cpp.

Member Function Documentation

◆ aoxDistanceFunction()

double ompl::geometric::AOXRRTConnect::aoxDistanceFunction ( const Motion * a,
const Motion * b ) const
inlineprotected

Compute AOX distance between motions.

Definition at line 205 of file AOXRRTConnect.h.

◆ euclideanDistanceFunction()

double ompl::geometric::AOXRRTConnect::euclideanDistanceFunction ( const Motion * a,
const Motion * b ) const
inlineprotected

Compute euclidian distance between motions.

Definition at line 199 of file AOXRRTConnect.h.

◆ findNeighbour()

ompl::geometric::AOXRRTConnect::Motion * ompl::geometric::AOXRRTConnect::findNeighbour ( Motion * sampled_motion,
float rootDist,
TreeData & tree )
protected

Find a valid neighbour with asymmetric distance funtion via iteration.

Definition at line 166 of file AOXRRTConnect.cpp.

◆ freeMemory()

void ompl::geometric::AOXRRTConnect::freeMemory ( )
protected

Free the memory allocated by this planner.

Definition at line 94 of file AOXRRTConnect.cpp.

◆ getFoundPath()

base::PathPtr ompl::geometric::AOXRRTConnect::getFoundPath ( ) const
inline

Definition at line 95 of file AOXRRTConnect.h.

◆ getRange()

double ompl::geometric::AOXRRTConnect::getRange ( ) const
inline

Get the range the planner is using.

Definition at line 111 of file AOXRRTConnect.h.

◆ growTree()

ompl::geometric::AOXRRTConnect::GrowState ompl::geometric::AOXRRTConnect::growTree ( TreeData & tree,
TreeGrowingInfo & tgi,
Motion * rmotion )
protected

Grow a tree towards a random state.

Definition at line 195 of file AOXRRTConnect.cpp.

◆ internalResetCondition()

bool ompl::geometric::AOXRRTConnect::internalResetCondition ( )
inline

Check if the inner loop planner met its condition to terminate.

Definition at line 129 of file AOXRRTConnect.h.

◆ reset()

void ompl::geometric::AOXRRTConnect::reset ( bool solvedProblem)

Definition at line 121 of file AOXRRTConnect.cpp.

◆ setFoundPath()

void ompl::geometric::AOXRRTConnect::setFoundPath ( const base::PathPtr & p)
inline

Definition at line 90 of file AOXRRTConnect.h.

◆ setNearestNeighbors()

template<template< typename T > class NN>
void ompl::geometric::AOXRRTConnect::setNearestNeighbors ( )
inline

Set a different nearest neighbors datastructure.

Definition at line 118 of file AOXRRTConnect.h.

◆ setPathCost()

void ompl::geometric::AOXRRTConnect::setPathCost ( double pc)

Definition at line 160 of file AOXRRTConnect.cpp.

◆ setRange()

void ompl::geometric::AOXRRTConnect::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 105 of file AOXRRTConnect.h.

◆ setup()

void ompl::geometric::AOXRRTConnect::setup ( )
overridevirtual

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.

Definition at line 62 of file AOXRRTConnect.cpp.

◆ solve()

ompl::base::PlannerStatus ompl::geometric::AOXRRTConnect::solve ( const base::PlannerTerminationCondition & ptc)
overridevirtual

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.

Implements ompl::base::Planner.

Definition at line 302 of file AOXRRTConnect.cpp.

Member Data Documentation

◆ _ptc

base::PlannerTerminationCondition ompl::geometric::AOXRRTConnect::_ptc {nullptr}
protected

Outer loop termination condition for AORRTC.

Definition at line 269 of file AOXRRTConnect.h.

◆ bestCost_

base::Cost ompl::geometric::AOXRRTConnect::bestCost_ {std::numeric_limits<double>::infinity()}
protected

Best cost found so far by algorithm.

Definition at line 263 of file AOXRRTConnect.h.

◆ connectionPoint_

std::pair<base::State *, base::State *> ompl::geometric::AOXRRTConnect::connectionPoint_
protected

The pair of states in each tree connected during planning. Used for PlannerData computation.

Definition at line 278 of file AOXRRTConnect.h.

◆ foundPath

base::PathPtr ompl::geometric::AOXRRTConnect::foundPath {nullptr}
protected

Path found by the algorithm.

Definition at line 266 of file AOXRRTConnect.h.

◆ goalState

base::State* ompl::geometric::AOXRRTConnect::goalState {nullptr}
protected

Definition at line 260 of file AOXRRTConnect.h.

◆ maxDistance_

double ompl::geometric::AOXRRTConnect::maxDistance_ {0.}
protected

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

Definition at line 242 of file AOXRRTConnect.h.

◆ maxInternalSamples

std::size_t ompl::geometric::AOXRRTConnect::maxInternalSamples {10000000}
protected

Maximum samples tried before the search is restarted.

Definition at line 254 of file AOXRRTConnect.h.

◆ maxInternalSamplesIncrement

std::size_t ompl::geometric::AOXRRTConnect::maxInternalSamplesIncrement {10000000}
protected

Increment by which maxSamples is increased.

Definition at line 257 of file AOXRRTConnect.h.

◆ maxInternalVertices

std::size_t ompl::geometric::AOXRRTConnect::maxInternalVertices {10000}
protected

Maximum allowed total vertices in trees before the search is restarted.

Definition at line 248 of file AOXRRTConnect.h.

◆ maxInternalVerticesIncrement

std::size_t ompl::geometric::AOXRRTConnect::maxInternalVerticesIncrement {10000}
protected

Increment by which maxVertices is increased.

Definition at line 251 of file AOXRRTConnect.h.

◆ maxResampleAttempts_

long int ompl::geometric::AOXRRTConnect::maxResampleAttempts_ {100}
protected

Maximum allowed cost resampling iterations before moving on.

Definition at line 245 of file AOXRRTConnect.h.

◆ opt_

base::OptimizationObjectivePtr ompl::geometric::AOXRRTConnect::opt_
protected

Objective we're optimizing.

Definition at line 272 of file AOXRRTConnect.h.

◆ rng_

RNG ompl::geometric::AOXRRTConnect::rng_
protected

The random number generator.

Definition at line 275 of file AOXRRTConnect.h.

◆ rootDistPadding

const float ompl::geometric::AOXRRTConnect::rootDistPadding = 0.00001
protected

Definition at line 230 of file AOXRRTConnect.h.

◆ sampleAttempts

std::size_t ompl::geometric::AOXRRTConnect::sampleAttempts {0}
protected

Definition at line 224 of file AOXRRTConnect.h.

◆ sampler_

base::InformedSamplerPtr ompl::geometric::AOXRRTConnect::sampler_
protected

State sampler.

Definition at line 222 of file AOXRRTConnect.h.

◆ startState

base::State* ompl::geometric::AOXRRTConnect::startState {nullptr}
protected

Definition at line 259 of file AOXRRTConnect.h.

◆ startTree_

bool ompl::geometric::AOXRRTConnect::startTree_ {true}
protected

A flag that toggles between expanding the start tree (true) or goal tree (false).

Definition at line 239 of file AOXRRTConnect.h.

◆ tGoal_

TreeData ompl::geometric::AOXRRTConnect::tGoal_
protected

The goal tree.

Definition at line 236 of file AOXRRTConnect.h.

◆ tStart_

TreeData ompl::geometric::AOXRRTConnect::tStart_
protected

The start tree.

Definition at line 233 of file AOXRRTConnect.h.


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