Class AOXRRTConnect

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

class AOXRRTConnect : public ompl::base::Planner

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]

Public Functions

AOXRRTConnect(const base::SpaceInformationPtr &si)

Constructor.

~AOXRRTConnect() override
virtual 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.

inline void setFoundPath(const base::PathPtr &p)
inline base::PathPtr getFoundPath() const
inline void setRange(double distance)

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.

inline double getRange() const

Get the range the planner is using.

template<template<typename T> class NN>
inline void setNearestNeighbors()

Set a different nearest neighbors datastructure.

inline bool internalResetCondition()

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

virtual 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)

Protected Types

enum GrowState

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

Values:

enumerator TRAPPED
enumerator ADVANCED
enumerator REACHED
using TreeData = std::shared_ptr<NearestNeighbors<Motion*>>

A nearest-neighbor datastructure representing a tree of motions.

Protected Functions

void freeMemory()

Free the memory allocated by this planner.

inline double euclideanDistanceFunction(const Motion *a, const Motion *b) const

Compute euclidian distance between motions.

inline double aoxDistanceFunction(const Motion *a, const Motion *b) const

Compute AOX distance between motions.

Motion *findNeighbour(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 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::State *startState = {nullptr}
base::State *goalState = {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.

class Motion

Representation of a motion.

Public Functions

Motion() = default
inline Motion(const base::SpaceInformationPtr &si)
~Motion() = default

Public Members

const base::State *root = {nullptr}
base::State *state = {nullptr}
Motion *parent = {nullptr}
double cost = {0}
bool connecting = {false}
struct TreeGrowingInfo

Information attached to growing a tree of motions (used internally)

Public Members

base::State *xstate
Motion *xmotion
bool start