Loading...
Searching...
No Matches
AORRTC.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2025, Queen's University
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Queen's University nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Tyler Wilson */
36
37#include "ompl/geometric/planners/rrt/AORRTC.h"
38#include <limits>
39#include "ompl/base/goals/GoalSampleableRegion.h"
40#include "ompl/tools/config/SelfConfig.h"
41
42ompl::geometric::AORRTC::AORRTC(const base::SpaceInformationPtr &si) : base::Planner(si, "AORRTC")
43{
44 specs_.approximateSolutions = true;
45 specs_.directed = true;
46}
47
48ompl::geometric::AORRTC::~AORRTC()
49{
50 freeMemory();
51}
52
54{
55 setup_ = false;
56 Planner::clear();
57 freeMemory();
58}
59
61{
62 return bestCost_;
63}
64
66{
67 Planner::setup();
68
69 aox_planner = std::make_shared<ompl::geometric::AOXRRTConnect>(si_);
70 aox_planner->setProblemDefinition(pdef_);
71 aox_planner->setName("AOXRRTConnect");
72 aox_planner->setRange(getRange());
73
74 aox_planner->setup();
75
76 psk_ = std::make_shared<PathSimplifier>(si_);
77 initCost_ = std::numeric_limits<double>::infinity();
78 solve_status = base::PlannerStatus::TIMEOUT;
79}
80
81/* Reset our planner to begin a new search */
82void ompl::geometric::AORRTC::reset(bool solvedProblem)
83{
84 aox_planner->clearQuery();
85 aox_planner->setFoundPath(nullptr);
86 aox_planner->reset(solvedProblem);
87 solve_status = base::PlannerStatus::TIMEOUT;
88}
89
90void ompl::geometric::AORRTC::setProblemDefinition(const base::ProblemDefinitionPtr &pdef)
91{
92 pdef_ = pdef;
93
94 if (aox_planner != nullptr)
95 {
96 aox_planner->setProblemDefinition(pdef);
97 }
98}
99
101{
102 aox_planner->clear();
103}
104
106{
107 if (pdef_)
108 {
109 if (p)
110 {
111 auto &path = static_cast<PathGeometric &>(*p);
112 psk_->simplify(path, ptc);
113 return;
114 }
115 }
116 OMPL_WARN("No solution to simplify");
117}
118
120{
121 do
122 {
123 /* If we already have a solution (and therefore a reasonable cost range) */
124 if (pdef_->hasExactSolution())
125 {
126 /* Inform the planner about our cost bound */
127 aox_planner->setPathCost(bestCost_.value());
128
129 /* Try to solve the planning problem */
130 solve_status = aox_planner->solve(ptc);
131
132 if (solve_status == base::PlannerStatus::EXACT_SOLUTION)
133 {
134 /* If we found a solution, extract it and update our path */
135 const base::PathPtr path = aox_planner->getFoundPath();
136
137 /* Update our best path if our new path is better */
138 if (path->length() < bestCost_.value())
139 {
140 bestPath_ = path;
141 bestCost_ = ompl::base::Cost(path->length());
142
143 pdef_->addSolutionPath(bestPath_, false, 0.0, getName());
144 }
145
146 /* Simplify our solution */
147 simplifySolution(path, ptc);
148
149 /* Again, update our best path if our new (simplified) path is better */
150 if (path->length() < bestCost_.value())
151 {
152 OMPL_INFORM("%s: AOX search simplified to cost %.5f", getName().c_str(), path->length());
153
154 bestPath_ = path;
155 bestCost_ = ompl::base::Cost(path->length());
156
157 pdef_->addSolutionPath(bestPath_, false, 0.0, getName());
158 }
159 }
160 }
161
162 /* Find an initial solution */
163 else
164 {
165 solve_status = aox_planner->solve(ptc);
166
167 /* If we found a solution, extract it and update our path */
168 if (solve_status == base::PlannerStatus::EXACT_SOLUTION)
169 {
170 initCost_ = pdef_->getSolutionPath()->length();
171 bestPath_ = pdef_->getSolutionPath();
172
173 bestCost_ = ompl::base::Cost(bestPath_->length());
174 pdef_->addSolutionPath(bestPath_, false, 0.0, getName());
175
176 simplifySolution(bestPath_, ptc);
177 OMPL_INFORM("%s: Initial search simplified to cost %.5f", getName().c_str(),
178 pdef_->getSolutionPath()->length());
179
180 bestCost_ = ompl::base::Cost(bestPath_->length());
181 pdef_->addSolutionPath(bestPath_, false, 0.0, getName());
182 }
183 }
184
185 /* If we ran into errors, exit early */
188 {
189 return solve_status;
190 }
191
192 /* If we found a solution, we can reset our planner */
193 if (solve_status == base::PlannerStatus::EXACT_SOLUTION)
194 {
195 reset(true);
196 }
197
198 /* If we didn't find a solution on this iteration of solve, reset our planner.
199 (PDT visualize calls solve for each iteration of the search,
200 so we need to check if our planner actually needs to reset) */
201 else if (aox_planner->internalResetCondition())
202 {
203 OMPL_INFORM("%s: Restarted before finding a solution", getName().c_str());
204 reset(false);
205 }
206
207 /* Something has surely gone wrong if you have found a zero-length path */
208 if (bestCost_.value() == 0)
209 {
210 OMPL_ERROR("%s: Zero-length path found. May have a common start/goal.", getName().c_str());
212 }
213 } while (!ptc);
214
215 /* Now that we're done, return whether or not we timed out */
216 if (pdef_->hasExactSolution())
217 {
219 }
220 else
221 {
223 }
224}
225
227{
228 aox_planner->getPlannerData(data);
229}
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition Cost.h:48
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
PlannerSpecs specs_
The specifications of the planner (its capabilities).
Definition Planner.h:413
ProblemDefinitionPtr pdef_
The user set problem definition.
Definition Planner.h:404
const std::string & getName() const
Get the name of the planner.
Definition Planner.cpp:56
SpaceInformationPtr si_
The space information for which planning is done.
Definition Planner.h:401
bool setup_
Flag indicating whether setup() has been called.
Definition Planner.h:424
ompl::base::Cost bestCost() const
Retrieve the best exact-solution cost found.
Definition AORRTC.cpp:60
PathSimplifierPtr psk_
The instance of the path simplifier.
Definition AORRTC.h:139
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition AORRTC.cpp:53
AORRTC(const base::SpaceInformationPtr &si)
Constructor.
Definition AORRTC.cpp:42
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition AORRTC.cpp:65
void freeMemory()
Free the memory allocated by this planner.
Definition AORRTC.cpp:100
void getPlannerData(base::PlannerData &data) const override
Get information about the current run of the motion planner. Repeated calls to this function will upd...
Definition AORRTC.cpp:226
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.
Definition AORRTC.cpp:105
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Function that can solve the motion planning problem. This function can be called multiple times on th...
Definition AORRTC.cpp:119
double getRange() const
Get the range the planner is using.
Definition AORRTC.h:100
Definition of a geometric path.
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition Console.h:68
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition Console.h:64
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition Console.h:66
This namespace contains sampling based planning routines shared by both planning under geometric cons...
A class to store the exit status of Planner::solve().
@ INVALID_START
Invalid start state or no start state specified.
@ EXACT_SOLUTION
The planner found an exact solution.
@ INVALID_GOAL
Invalid goal state.
@ UNRECOGNIZED_GOAL_TYPE
The goal is of a type that a planner does not recognize.
@ TIMEOUT
The planner failed to find a solution.