Class AORRTC
Defined in File AORRTC.h
Inheritance Relationships
Base Type
public ompl::base::Planner(Class Planner)
Class Documentation
-
class AORRTC : public ompl::base::Planner
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]
Public Functions
-
AORRTC(const base::SpaceInformationPtr &si)
Constructor.
-
~AORRTC() override
-
virtual 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).
-
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.
-
virtual void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
-
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 setProblemDefinition(const base::ProblemDefinitionPtr &pdef) override
-
inline void setRange(double distance)
-
inline double getRange() const
Get the range the planner is using.
-
inline const PathSimplifierPtr &getPathSimplifier() const
Get the path simplifier.
-
inline PathSimplifierPtr &getPathSimplifier()
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.
Protected Functions
-
void freeMemory()
Free the memory allocated by this planner.
Protected Attributes
-
std::shared_ptr<ompl::geometric::AOXRRTConnect> aox_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::OptimizationObjectivePtr opt_
Objective we’re optimizing.
-
double initCost_
-
ompl::base::PlannerStatus solve_status