Loading...
Searching...
No Matches
TRRTstar.h
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2025, Joris Chomarat
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 copyright holder 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: Joris Chomarat */
36
37#ifndef OMPL_GEOMETRIC_PLANNERS_RRT_TRRTstar_
38#define OMPL_GEOMETRIC_PLANNERS_RRT_TRRTstar_
39
40#include "ompl/geometric/planners/PlannerIncludes.h"
41#include "ompl/base/OptimizationObjective.h"
42#include "ompl/datastructures/NearestNeighbors.h"
43
44#include <limits>
45#include <vector>
46#include <queue>
47#include <deque>
48#include <utility>
49#include <list>
50
51namespace ompl
52{
53 namespace geometric
54 {
79
81 class TRRTstar : public base::Planner
82 {
83 public:
84 TRRTstar(const base::SpaceInformationPtr &si);
85
86 ~TRRTstar() override;
87
88 void getPlannerData(base::PlannerData &data) const override;
89
91
92 void clear() override;
93
94 void setup() override;
95
105 void setGoalBias(double goalBias)
106 {
107 goalBias_ = goalBias;
108 }
109
111 double getGoalBias() const
112 {
113 return goalBias_;
114 }
115
121 void setRange(double distance)
122 {
123 maxDistance_ = distance;
124 }
125
127 double getRange() const
128 {
129 return maxDistance_;
130 }
131
134 void setRewireFactor(double rewireFactor)
135 {
136 rewireFactor_ = rewireFactor;
138 }
139
142 double getRewireFactor() const
143 {
144 return rewireFactor_;
145 }
146
148 template <template <typename T> class NN>
150 {
151 if (nn_ && nn_->size() != 0)
152 OMPL_WARN("Calling setNearestNeighbors will clear all states.");
153 clear();
154 nn_ = std::make_shared<NN<Motion *>>();
155 setup();
156 }
157
165 void setDelayCC(bool delayCC)
166 {
167 delayCC_ = delayCC;
168 }
169
171 bool getDelayCC() const
172 {
173 return delayCC_;
174 }
175
183 void setTreePruning(bool prune);
184
186 bool getTreePruning() const
187 {
188 return useTreePruning_;
189 }
190
194 void setPruneThreshold(const double pp)
195 {
196 pruneThreshold_ = pp;
197 }
198
200 double getPruneThreshold() const
201 {
202 return pruneThreshold_;
203 }
204
207 void setAdmissibleCostToCome(const bool admissible)
208 {
209 useAdmissibleCostToCome_ = admissible;
210 }
211
214 {
216 }
217
219 void setBatchSize(unsigned int batchSize)
220 {
221 batchSize_ = batchSize;
222 }
223
225 unsigned int getBatchSize() const
226 {
227 return batchSize_;
228 }
229
231 void setKNearest(bool useKNearest)
232 {
233 useKNearest_ = useKNearest;
234 }
235
237 bool getKNearest() const
238 {
239 return useKNearest_;
240 }
241
243 void setNumSamplingAttempts(unsigned int numAttempts)
244 {
245 numSampleAttempts_ = numAttempts;
246 }
247
249 unsigned int getNumSamplingAttempts() const
250 {
251 return numSampleAttempts_;
252 }
253
254 unsigned int numIterations() const
255 {
256 return iterations_;
257 }
258
259 ompl::base::Cost bestCost() const
260 {
261 return bestCost_;
262 }
263
269 void setTempChangeFactor(double factor)
270 {
271 tempChangeFactor_ = exp(factor);
272 }
273
275 double getTempChangeFactor() const
276 {
277 return log(tempChangeFactor_);
278 }
279
283 void setCostThreshold(double maxCost)
284 {
285 costThreshold_ = base::Cost(maxCost);
286 }
287
291 double getCostThreshold() const
292 {
293 return costThreshold_.value();
294 }
295
298 void setInitTemperature(double initTemperature)
299 {
300 initTemperature_ = initTemperature;
302 }
303
305 double getInitTemperature() const
306 {
307 return initTemperature_;
308 }
309
310 protected:
312 class Motion
313 {
314 public:
317 Motion(const base::SpaceInformationPtr &si) : state(si->allocState()), parent(nullptr), inGoal(false)
318 {
319 }
320
321 ~Motion() = default;
322
325
328
330 bool inGoal;
331
334
338
340 std::vector<Motion *> children;
341 };
342
344 void allocSampler();
345
347 bool sampleUniform(base::State *statePtr);
348
350 void freeMemory();
351
352 // For sorting a list of costs and getting only their sorted indices
353 struct CostIndexCompare
354 {
355 CostIndexCompare(const std::vector<base::Cost> &costs, const base::OptimizationObjective &opt)
356 : costs_(costs), opt_(opt)
357 {
358 }
359 bool operator()(unsigned i, unsigned j)
360 {
361 return opt_.isCostBetterThan(costs_[i], costs_[j]);
362 }
363 const std::vector<base::Cost> &costs_;
364 const base::OptimizationObjective &opt_;
365 };
366
368 double distanceFunction(const Motion *a, const Motion *b) const
369 {
370 return si_->distance(a->state, b->state);
371 }
372
376 bool transitionTest(const base::Cost &motionCost);
377
379 void getNeighbors(Motion *motion, std::vector<Motion *> &nbh) const;
380
382 void removeFromParent(Motion *m);
383
385 void updateChildCosts(Motion *m);
386
390 int pruneTree(const base::Cost &pruneTreeCost);
391
397 base::Cost solutionHeuristic(const Motion *motion) const;
398
400 void addChildrenToList(std::queue<Motion *, std::deque<Motion *>> *motionList, Motion *motion);
401
404 bool keepCondition(const Motion *motion, const base::Cost &threshold) const;
405
408
410 base::StateSamplerPtr sampler_;
411
413 base::InformedSamplerPtr infSampler_;
414
416 std::shared_ptr<NearestNeighbors<Motion *>> nn_;
417
420 double goalBias_{.05};
421
423 double maxDistance_{0.};
424
427
429 bool useKNearest_{true};
430
433 double rewireFactor_{1.1};
434
436 double k_rrt_{0u};
437
439 double r_rrt_{0.};
440
442 bool delayCC_{true};
443
445 base::OptimizationObjectivePtr opt_;
446
449
451 std::vector<Motion *> goalMotions_;
452
454 bool useTreePruning_{false};
455
457 double pruneThreshold_{.05};
458
461
463 unsigned int numSampleAttempts_{100u};
464
466 unsigned int batchSize_{1u};
467
469 std::vector<Motion *> startMotions_;
470
472 base::Cost bestCost_{std::numeric_limits<double>::quiet_NaN()};
473
475 base::Cost prunedCost_{std::numeric_limits<double>::quiet_NaN()};
476
479 double prunedMeasure_{0.};
480
482 unsigned int iterations_{0u};
483
484 // *********************************************************************************************************
485 // TRRTstar-Specific Variables
486 // *********************************************************************************************************
487
488 // Transition Test -----------------------------------------------------------------------
489
493 double temp_;
494
496 base::Cost worstCost_{base::Cost(std::numeric_limits<double>::infinity())};
497
499 base::Cost costThreshold_{base::Cost(std::numeric_limits<double>::infinity())};
500
504
506 double initTemperature_{100.0};
507
509 // Planner progress property functions
510 std::string numIterationsProperty() const
511 {
512 return std::to_string(numIterations());
513 }
514 std::string bestCostProperty() const
515 {
516 return std::to_string(bestCost().value());
517 }
518 };
519
520 } // namespace geometric
521} // namespace ompl
522
523#endif // OMPL_GEOMETRIC_PLANNERS_RRT_TRRTstar_
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
Abstract definition of optimization objectives.
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...
Base class for a planner.
Definition Planner.h:216
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.
Definition TRRTstar.h:313
base::State * state
The state contained by the motion.
Definition TRRTstar.h:324
base::Cost incCost
The incremental cost of this motion's parent to this motion (this is stored to save distance computat...
Definition TRRTstar.h:337
base::Cost cost
The cost up to this motion.
Definition TRRTstar.h:333
Motion(const base::SpaceInformationPtr &si)
Constructor that allocates memory for the state. This constructor automatically allocates memory for ...
Definition TRRTstar.h:317
bool inGoal
Set to true if this vertex is in the goal region.
Definition TRRTstar.h:330
Motion * parent
The parent motion in the exploration tree.
Definition TRRTstar.h:327
std::vector< Motion * > children
The set of motions descending from the current motion.
Definition TRRTstar.h:340
base::Cost worstCost_
The least desirable (e.g., maximum) cost value in the search tree.
Definition TRRTstar.h:496
double getGoalBias() const
Get the goal bias the planner is using.
Definition TRRTstar.h:111
void setAdmissibleCostToCome(const bool admissible)
Controls whether pruning and new-state rejection uses an admissible cost-to-come estimate or not.
Definition TRRTstar.h:207
void setTempChangeFactor(double factor)
Set the factor by which the temperature is increased after a failed transition test....
Definition TRRTstar.h:269
void setNumSamplingAttempts(unsigned int numAttempts)
Set the number of attempts to make while performing rejection or informed sampling.
Definition TRRTstar.h:243
bool useKNearest_
Option to use k-nearest search for rewiring.
Definition TRRTstar.h:429
base::Cost solutionHeuristic(const Motion *motion) const
Computes the solution cost heuristically as the cost to come from start to the motion plus the cost t...
Definition TRRTstar.cpp:888
bool getTreePruning() const
Get the state of the pruning option.
Definition TRRTstar.h:186
base::Cost bestCost_
Best cost found so far by algorithm.
Definition TRRTstar.h:472
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 TRRTstar.cpp:659
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition TRRTstar.h:416
double r_rrt_
A constant for r-disc rewiring calculations.
Definition TRRTstar.h:439
base::OptimizationObjectivePtr opt_
Objective we're optimizing.
Definition TRRTstar.h:445
void calculateRewiringLowerBounds()
Calculate the k_RRG* and r_RRG* terms.
Definition TRRTstar.cpp:943
double getRange() const
Get the range the planner is using.
Definition TRRTstar.h:127
bool delayCC_
Option to delay and reduce collision checking within iterations.
Definition TRRTstar.h:442
bool useTreePruning_
The status of the tree pruning option.
Definition TRRTstar.h:454
double pruneThreshold_
The tree is pruned when the change in solution cost is greater than this fraction.
Definition TRRTstar.h:457
bool sampleUniform(base::State *statePtr)
Generate a sample.
Definition TRRTstar.cpp:934
std::vector< Motion * > startMotions_
Stores the start states as Motions.
Definition TRRTstar.h:469
void allocSampler()
Create the samplers.
Definition TRRTstar.cpp:928
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
Definition TRRTstar.h:149
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)...
Definition TRRTstar.h:420
std::vector< Motion * > goalMotions_
A list of states in the tree that satisfy the goal condition.
Definition TRRTstar.h:451
bool useAdmissibleCostToCome_
The admissibility of the new-state rejection heuristic.
Definition TRRTstar.h:460
RNG rng_
The random number generator.
Definition TRRTstar.h:426
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition TRRTstar.cpp:85
double getPruneThreshold() const
Get the current prune states percentage threshold parameter.
Definition TRRTstar.h:200
double getRewireFactor() const
Set the rewiring scale factor, s, such that r_rrg = s \times r_rrg* > r_rrg* (or k_rrg = s \times k_r...
Definition TRRTstar.h:142
unsigned int iterations_
Number of iterations the algorithm performed.
Definition TRRTstar.h:482
void removeFromParent(Motion *m)
Removes the given motion from the parent's child list.
Definition TRRTstar.cpp:623
bool getDelayCC() const
Get the state of the delayed collision checking option.
Definition TRRTstar.h:171
bool getAdmissibleCostToCome() const
Get the admissibility of the pruning and new-state rejection heuristic.
Definition TRRTstar.h:213
void setRewireFactor(double rewireFactor)
Set the rewiring scale factor, s, such that r_rrg = s \times r_rrg* (or k_rrg = s \times k_rrg*).
Definition TRRTstar.h:134
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition TRRTstar.h:423
double rewireFactor_
The rewiring factor, s, so that r_rrt = s \times r_rrt* > r_rrt* (or k_rrt = s \times k_rrt* > k_rrt*...
Definition TRRTstar.h:433
base::StateSamplerPtr sampler_
State sampler.
Definition TRRTstar.h:410
void setKNearest(bool useKNearest)
Use a k-nearest search for rewiring instead of a r-disc search.
Definition TRRTstar.h:231
void freeMemory()
Free the memory allocated by this planner.
Definition TRRTstar.cpp:644
double getInitTemperature() const
Get the temperature at the start of planning.
Definition TRRTstar.h:305
double prunedMeasure_
The measure of the problem when we pruned it (if this isn't in use, it will be set to si_->getSpaceMe...
Definition TRRTstar.h:479
void getNeighbors(Motion *motion, std::vector< Motion * > &nbh) const
Gets the neighbours of a given motion, using either k-nearest of radius as appropriate.
Definition TRRTstar.cpp:606
Motion * bestGoalMotion_
The best goal motion.
Definition TRRTstar.h:448
bool keepCondition(const Motion *motion, const base::Cost &threshold) const
Check whether the given motion passes the specified cost threshold, meaning it will be kept during pr...
Definition TRRTstar.cpp:874
double k_rrt_
A constant for k-nearest rewiring calculations.
Definition TRRTstar.h:436
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition TRRTstar.cpp:135
void addChildrenToList(std::queue< Motion *, std::deque< Motion * > > *motionList, Motion *motion)
Add the children of a vertex to the given list.
Definition TRRTstar.cpp:865
int pruneTree(const base::Cost &pruneTreeCost)
Prunes all those states which estimated total cost is higher than pruneTreeCost. Returns the number o...
Definition TRRTstar.cpp:679
double getTempChangeFactor() const
Get the factor by which the temperature rises based on current acceptance/rejection rate.
Definition TRRTstar.h:275
double temp_
Temperature parameter used to control the difficulty level of transition tests. Low temperatures limi...
Definition TRRTstar.h:493
bool getKNearest() const
Get the state of using a k-nearest search for rewiring.
Definition TRRTstar.h:237
void setCostThreshold(double maxCost)
Set the cost threshold (default is infinity). Any motion cost that is not better than this cost (acco...
Definition TRRTstar.h:283
base::Cost costThreshold_
All motion costs must be better than this cost (default is infinity).
Definition TRRTstar.h:499
void setDelayCC(bool delayCC)
Option that delays collision checking procedures. When it is enabled, all neighbors are sorted by cos...
Definition TRRTstar.h:165
unsigned int getNumSamplingAttempts() const
Get the number of attempts to make while performing rejection or informed sampling.
Definition TRRTstar.h:249
void setGoalBias(double goalBias)
Set the goal bias.
Definition TRRTstar.h:105
void setPruneThreshold(const double pp)
Set the fractional change in solution cost necessary for pruning to occur, i.e., prune if the new sol...
Definition TRRTstar.h:194
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states).
Definition TRRTstar.h:368
void setInitTemperature(double initTemperature)
Set the initial temperature at the beginning of the algorithm. Should be high to allow for initial ex...
Definition TRRTstar.h:298
void setRange(double distance)
Set the range the planner is supposed to use.
Definition TRRTstar.h:121
void updateChildCosts(Motion *m)
Updates the cost of the children of this node if the cost up to this node has changed.
Definition TRRTstar.cpp:635
void setTreePruning(bool prune)
Controls whether the tree is pruned during the search. This pruning removes a vertex if and only if i...
Definition TRRTstar.cpp:914
base::Cost prunedCost_
The cost at which the graph was last pruned.
Definition TRRTstar.h:475
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 TRRTstar.cpp:157
double initTemperature_
The initial value of temp_.
Definition TRRTstar.h:506
void setBatchSize(unsigned int batchSize)
Set the batch size used for sample ordering.
Definition TRRTstar.h:219
unsigned int numSampleAttempts_
The number of attempts to make at informed sampling.
Definition TRRTstar.h:463
unsigned int batchSize_
The size of the batches.
Definition TRRTstar.h:466
unsigned int getBatchSize() const
Get the batch size used for sample ordering.
Definition TRRTstar.h:225
base::InformedSamplerPtr infSampler_
An informed sampler.
Definition TRRTstar.h:413
double tempChangeFactor_
The value of the expression exp^T_rate. The temperature is increased by this factor whenever the tran...
Definition TRRTstar.h:503
bool transitionTest(const base::Cost &motionCost)
Filter irrelevant configuration regarding the search of low-cost paths before inserting into tree.
Definition TRRTstar.cpp:957
double getCostThreshold() const
Get the cost threshold (default is infinity). Any motion cost that is not better than this cost (acco...
Definition TRRTstar.h:291
#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().