Loading...
Searching...
No Matches

Asymptotically Optimal RRT-Connect. More...

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

Inheritance diagram for ompl::geometric::AORRTC:

Public Member Functions

 AORRTC (const base::SpaceInformationPtr &si)
 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.
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 setProblemDefinition (const base::ProblemDefinitionPtr &pdef) override
void setRange (double distance)
double getRange () const
 Get the range the planner is using.
const PathSimplifierPtrgetPathSimplifier () const
 Get the path simplifier.
PathSimplifierPtrgetPathSimplifier ()
 Get the path simplifier.
void simplifySolution (const base::PathPtr &p, const base::PlannerTerminationCondition &ptc)
 Attempt to simplify the current solution path. Stop computation when ptc becomes true at the latest.
ompl::base::Cost bestCost () const
 Retrieve the best exact-solution cost found.
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 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 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 Member Functions

void freeMemory ()
 Free the memory allocated by this planner.
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

RNG rng_
 The random number generator.
std::shared_ptr< ompl::geometric::AOXRRTConnectaox_planner
double maxDistance_ {0.}
 The maximum length of a motion to be added to a tree.
double inflationFactor_ {1.}
PathSimplifierPtr psk_
 The instance of the path simplifier.
base::PathPtr bestPath_ {nullptr}
ompl::base::Cost bestCost_ {std::numeric_limits<double>::infinity()}
base::OptimizationObjectivePtr opt_
 Objective we're optimizing.
double initCost_
ompl::base::PlannerStatus solve_status
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

Asymptotically Optimal 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 meta algorithm repeatedly runs the underlying RRT-Connect search (AOXRRTConnect) and constrains each consecutive search by the cost of the current best solution.
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 74 of file AORRTC.h.

Constructor & Destructor Documentation

◆ AORRTC()

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

Constructor.

Definition at line 42 of file AORRTC.cpp.

◆ ~AORRTC()

ompl::geometric::AORRTC::~AORRTC ( )
override

Definition at line 48 of file AORRTC.cpp.

Member Function Documentation

◆ bestCost()

ompl::base::Cost ompl::geometric::AORRTC::bestCost ( ) const

Retrieve the best exact-solution cost found.

Definition at line 60 of file AORRTC.cpp.

◆ clear()

void ompl::geometric::AORRTC::clear ( )
overridevirtual

Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.

Reimplemented from ompl::base::Planner.

Definition at line 53 of file AORRTC.cpp.

◆ freeMemory()

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

Free the memory allocated by this planner.

Definition at line 100 of file AORRTC.cpp.

◆ getPathSimplifier() [1/2]

PathSimplifierPtr & ompl::geometric::AORRTC::getPathSimplifier ( )
inline

Get the path simplifier.

Definition at line 112 of file AORRTC.h.

◆ getPathSimplifier() [2/2]

const PathSimplifierPtr & ompl::geometric::AORRTC::getPathSimplifier ( ) const
inline

Get the path simplifier.

Definition at line 106 of file AORRTC.h.

◆ getPlannerData()

void ompl::geometric::AORRTC::getPlannerData ( base::PlannerData & data) const
overridevirtual

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.

Definition at line 226 of file AORRTC.cpp.

◆ getRange()

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

Get the range the planner is using.

Definition at line 100 of file AORRTC.h.

◆ reset()

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

Definition at line 82 of file AORRTC.cpp.

◆ setProblemDefinition()

void ompl::geometric::AORRTC::setProblemDefinition ( const base::ProblemDefinitionPtr & pdef)
override

Definition at line 90 of file AORRTC.cpp.

◆ setRange()

void ompl::geometric::AORRTC::setRange ( double distance)
inline

Definition at line 94 of file AORRTC.h.

◆ setup()

void ompl::geometric::AORRTC::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 65 of file AORRTC.cpp.

◆ simplifySolution()

void ompl::geometric::AORRTC::simplifySolution ( const base::PathPtr & p,
const base::PlannerTerminationCondition & ptc )

Attempt to simplify the current solution path. Stop computation when ptc becomes true at the latest.

Definition at line 105 of file AORRTC.cpp.

◆ solve()

ompl::base::PlannerStatus ompl::geometric::AORRTC::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 119 of file AORRTC.cpp.

Member Data Documentation

◆ aox_planner

std::shared_ptr<ompl::geometric::AOXRRTConnect> ompl::geometric::AORRTC::aox_planner
protected

Definition at line 128 of file AORRTC.h.

◆ bestCost_

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

Definition at line 143 of file AORRTC.h.

◆ bestPath_

base::PathPtr ompl::geometric::AORRTC::bestPath_ {nullptr}
protected

Definition at line 141 of file AORRTC.h.

◆ inflationFactor_

double ompl::geometric::AORRTC::inflationFactor_ {1.}
protected

Definition at line 136 of file AORRTC.h.

◆ initCost_

double ompl::geometric::AORRTC::initCost_
protected

Definition at line 148 of file AORRTC.h.

◆ maxDistance_

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

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

Definition at line 134 of file AORRTC.h.

◆ opt_

base::OptimizationObjectivePtr ompl::geometric::AORRTC::opt_
protected

Objective we're optimizing.

Definition at line 146 of file AORRTC.h.

◆ psk_

PathSimplifierPtr ompl::geometric::AORRTC::psk_
protected

The instance of the path simplifier.

Definition at line 139 of file AORRTC.h.

◆ rng_

RNG ompl::geometric::AORRTC::rng_
protected

The random number generator.

Definition at line 126 of file AORRTC.h.

◆ solve_status

ompl::base::PlannerStatus ompl::geometric::AORRTC::solve_status
protected

Definition at line 149 of file AORRTC.h.


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