Loading...
Searching...
No Matches
AOXRRTConnect.h
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#ifndef OMPL_GEOMETRIC_PLANNERS_RRT_AOX_RRT_CONNECT_
38#define OMPL_GEOMETRIC_PLANNERS_RRT_AOX_RRT_CONNECT_
39
40#include "ompl/datastructures/NearestNeighbors.h"
41#include "ompl/base/OptimizationObjective.h"
42#include "ompl/geometric/planners/PlannerIncludes.h"
43#include <ompl/geometric/planners/rrt/RRTConnect.h>
44
45#include "ompl/base/Path.h"
46
47namespace ompl
48{
49 namespace geometric
50 {
78
81 {
82 public:
84 AOXRRTConnect(const base::SpaceInformationPtr &si);
85
86 ~AOXRRTConnect() override;
87
89
90 void setFoundPath(const base::PathPtr &p)
91 {
92 foundPath = p;
93 }
94
95 base::PathPtr getFoundPath() const
96 {
97 return foundPath;
98 }
99
105 void setRange(double distance)
106 {
107 maxDistance_ = distance;
108 }
109
111 double getRange() const
112 {
113 return maxDistance_;
114 }
115
117 template <template <typename T> class NN>
119 {
120 if ((tStart_ && tStart_->size() != 0) || (tGoal_ && tGoal_->size() != 0))
121 OMPL_WARN("Calling setNearestNeighbors will clear all states.");
122 clear();
123 tStart_ = std::make_shared<NN<Motion *>>();
124 tGoal_ = std::make_shared<NN<Motion *>>();
125 setup();
126 }
127
130 {
131 bool shouldReset = false;
132 if (tStart_ && tGoal_)
133 {
134 /* Reset if we have met our maximum internal vertices */
135 shouldReset = shouldReset || (tStart_->size() + tGoal_->size() >= maxInternalVertices);
136 }
137 else
138 {
139 /* If our trees don't exist, we're not in the middle of a search anyways */
140 shouldReset = true;
141 }
142 /* Reset if we have attempted our maximum internal samples */
143 shouldReset = shouldReset || (sampleAttempts >= maxInternalSamples);
144 return shouldReset;
145 }
146
147 void setup() override;
148
149 void reset(bool solvedProblem);
150
151 void setPathCost(double pc);
152
153 protected:
155 class Motion
156 {
157 public:
158 Motion() = default;
159
160 Motion(const base::SpaceInformationPtr &si) : state(si->allocState())
161 {
162 }
163
164 ~Motion() = default;
165
166 const base::State *root{nullptr};
167 base::State *state{nullptr};
168 Motion *parent{nullptr};
169 double cost{0};
170 bool connecting{false};
171 };
172
174 using TreeData = std::shared_ptr<NearestNeighbors<Motion *>>;
175
178 {
179 base::State *xstate;
180 Motion *xmotion;
181 bool start;
182 };
183
186 {
187 /* no progress has been made */
188 TRAPPED,
189 /* progress has been made towards the randomly sampled state */
190 ADVANCED,
191 /* the randomly sampled state was reached */
192 REACHED
193 };
194
196 void freeMemory();
197
199 double euclideanDistanceFunction(const Motion *a, const Motion *b) const
200 {
201 return si_->distance(a->state, b->state);
202 }
203
205 double aoxDistanceFunction(const Motion *a, const Motion *b) const
206 {
207 auto space_diff = si_->distance(a->state, b->state);
208 auto cost_diff = a->cost - b->cost;
209
210 auto dist = sqrt(pow(space_diff, 2) + pow(cost_diff, 2));
211
212 return dist;
213 }
214
216 Motion *findNeighbour(Motion *sampled_motion, float rootDist, TreeData &tree);
217
219 GrowState growTree(TreeData &tree, TreeGrowingInfo &tgi, Motion *rmotion);
220
222 base::InformedSamplerPtr sampler_;
223
224 std::size_t sampleAttempts{0};
225
226 /* Pad rootDist to account for floating point error
227 Needed to make sure the root is included in nearest list
228 TODO: Should use some relative epsilon for padding
229 (FLT_EPSILON is good but does not scale with the magnitude of rootDist and may be too small) */
230 const float rootDistPadding = 0.00001;
231
234
237
239 bool startTree_{true};
240
242 double maxDistance_{0.};
243
245 long int maxResampleAttempts_{100};
246
248 std::size_t maxInternalVertices{10000};
249
252
254 std::size_t maxInternalSamples{10000000};
255
257 std::size_t maxInternalSamplesIncrement{10000000};
258
259 base::State *startState{nullptr};
260 base::State *goalState{nullptr};
261
263 base::Cost bestCost_{std::numeric_limits<double>::infinity()};
264
266 base::PathPtr foundPath{nullptr};
267
270
272 base::OptimizationObjectivePtr opt_;
273
276
278 std::pair<base::State *, base::State *> connectionPoint_;
279 };
280 } // namespace geometric
281} // namespace ompl
282
283#endif
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition Cost.h:48
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Base class for a planner.
Definition Planner.h:216
virtual void clear()
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition Planner.cpp:118
SpaceInformationPtr si_
The space information for which planning is done.
Definition Planner.h:401
Definition of an abstract state.
Definition State.h:50
Representation of a motion.
TreeData tStart_
The start tree.
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
void setRange(double distance)
Set the range the planner is supposed to use.
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
double getRange() const
Get the range the planner is using.
long int maxResampleAttempts_
Maximum allowed cost resampling iterations before moving on.
Motion * findNeighbour(Motion *sampled_motion, float rootDist, TreeData &tree)
Find a valid neighbour with asymmetric distance funtion via iteration.
double aoxDistanceFunction(const Motion *a, const Motion *b) const
Compute AOX distance between motions.
std::size_t maxInternalSamplesIncrement
Increment by which maxSamples is increased.
GrowState
The state of the tree after an attempt to extend it.
std::size_t maxInternalVertices
Maximum allowed total vertices in trees before the search is restarted.
std::pair< base::State *, base::State * > connectionPoint_
The pair of states in each tree connected during planning. Used for PlannerData computation.
TreeData tGoal_
The goal tree.
std::size_t maxInternalVerticesIncrement
Increment by which maxVertices is increased.
std::size_t maxInternalSamples
Maximum samples tried before the search is restarted.
bool startTree_
A flag that toggles between expanding the start tree (true) or goal tree (false).
bool internalResetCondition()
Check if the inner loop planner met its condition to terminate.
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...
double euclideanDistanceFunction(const Motion *a, const Motion *b) const
Compute euclidian distance between motions.
base::OptimizationObjectivePtr opt_
Objective we're optimizing.
RNG rng_
The random number generator.
base::PathPtr foundPath
Path found by the algorithm.
std::shared_ptr< NearestNeighbors< Motion * > > TreeData
A nearest-neighbor datastructure representing a tree of motions.
GrowState growTree(TreeData &tree, TreeGrowingInfo &tgi, Motion *rmotion)
Grow a tree towards a random state.
base::InformedSamplerPtr sampler_
State sampler.
void freeMemory()
Free the memory allocated by this planner.
base::Cost bestCost_
Best cost found so far by algorithm.
base::PlannerTerminationCondition _ptc
Outer loop termination condition for AORRTC.
double maxDistance_
The maximum length of a motion to be added to a tree.
AOXRRTConnect(const base::SpaceInformationPtr &si)
Constructor.
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition Console.h:66
This namespace contains code that is specific to planning under geometric constraints.
Main namespace. Contains everything in this library.
A class to store the exit status of Planner::solve().
Information attached to growing a tree of motions (used internally).