STRRTstar.h
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2021, Technische Universität Berlin (TU Berlin)
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 TU Berlin 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: Francesco Grothe */
36 
37 #ifndef OMPL_GEOMETRIC_PLANNERS_RRT_STRRT_STAR_
38 #define OMPL_GEOMETRIC_PLANNERS_RRT_STRRT_STAR_
39 
40 #include <ompl/datastructures/NearestNeighbors.h>
41 #include <ompl/base/goals/GoalSampleableRegion.h>
42 #include <ompl/geometric/planners/PlannerIncludes.h>
43 #include <ompl/base/OptimizationObjective.h>
44 #include <ompl/base/spaces/SpaceTimeStateSpace.h>
45 #include <ompl/base/objectives/MinimizeArrivalTime.h>
46 #include <ompl/base/samplers/ConditionalStateSampler.h>
47 #include <ompl/tools/config/SelfConfig.h>
48 #include <ompl/util/GeometricEquations.h>
49 #include <boost/math/constants/constants.hpp>
50 
51 namespace ompl
52 {
53  namespace geometric
54  {
65  class STRRTstar : public base::Planner
66  {
67  public:
68  using Motion = base::ConditionalStateSampler::Motion;
69 
71  explicit STRRTstar(const ompl::base::SpaceInformationPtr &si);
72 
73  ~STRRTstar() override;
74 
75  void clear() override;
76 
77  void getPlannerData(base::PlannerData &data) const override;
78 
79  base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override;
80 
86  void setRange(double distance);
87 
89  double getRange() const;
90 
92  double getOptimumApproxFactor() const;
93 
96  void setOptimumApproxFactor(double optimumApproxFactor);
97 
98  std::string getRewiringState() const;
99 
101  void setRewiringToOff();
102 
104  void setRewiringToRadius();
105 
107  void setRewiringToKNearest();
108 
109  double getRewireFactor() const;
110 
111  void setRewireFactor(double v);
112 
114  unsigned int getBatchSize() const;
115 
116  void setBatchSize(int v);
117 
119  void setTimeBoundFactorIncrease(double f);
120 
122  void setInitialTimeBoundFactor(double f);
123 
125  void setSampleUniformForUnboundedTime(bool uniform);
126 
127  void setup() override;
128 
130  using TreeData = std::shared_ptr<ompl::NearestNeighbors<Motion *>>;
131  protected:
132 
134  struct TreeGrowingInfo
135  {
136  base::State *xstate;
137  Motion *xmotion;
138  bool start;
139  };
140 
142  enum GrowState
143  {
145  TRAPPED,
147  ADVANCED,
149  REACHED
150  };
151 
153  GrowState growTreeSingle(TreeData &tree, TreeGrowingInfo &tgi, Motion *rmotion, Motion *nmotion);
154 
160  GrowState growTree(TreeData &tree, TreeGrowingInfo &tgi, Motion *rmotion, std::vector<Motion *> &nbh,
161  bool connect);
162 
164  void increaseTimeBound(bool hasEqualBounds, double &oldBatchTimeBoundFactor, double &newBatchTimeBoundFactor,
165  bool &startTree, unsigned int &batchSize, int &numBatchSamples);
166 
168  void getNeighbors(TreeData &tree, Motion *motion, std::vector<Motion *> &nbh) const;
169 
171  void freeMemory();
172 
174  double distanceFunction(const Motion *a, const Motion *b) const
175  {
176  return si_->distance(a->state, b->state);
177  }
178 
180  void pruneStartTree();
181 
185  Motion *pruneGoalTree();
186 
188  static Motion *computeSolutionMotion(Motion *motion);
189 
191  void removeInvalidGoals(const std::vector<Motion *> &invalidGoals);
192 
194  base::ConditionalStateSampler sampler_;
195 
198 
201 
203  double maxDistance_{0.};
204 
206  double distanceBetweenTrees_;
207 
209  base::PathPtr bestSolution_{nullptr};
210 
212  double bestTime_ = std::numeric_limits<double>::infinity();
213 
215  unsigned int numIterations_ = 0;
216 
218  int numSolutions_ = 0;
219 
221  double minimumTime_ = std::numeric_limits<double>::infinity();
222 
224  double upperTimeBound_;
225 
227  double optimumApproxFactor_ = 1.0;
228 
230  Motion *startMotion_{nullptr};
231 
233  std::vector<Motion *> goalMotions_{};
234 
237  std::vector<Motion *> newBatchGoalMotions_{};
238 
245  base::State *tempState_{nullptr}; // temporary sampled goal states are stored here.
246 
248  base::State *nextGoal(int n, double oldBatchTimeBoundFactor, double newBatchTimeBoundFactor);
249 
251  base::State *nextGoal(const base::PlannerTerminationCondition &ptc, double oldBatchTimeBoundFactor,
252  double newBatchTimeBoundFactor);
253 
255  base::State *nextGoal(const base::PlannerTerminationCondition &ptc, int n, double oldBatchTimeBoundFactor,
256  double newBatchTimeBoundFactor);
257 
260  bool sampleGoalTime(base::State *goal, double oldBatchTimeBoundFactor, double newBatchTimeBoundFactor);
261 
263  static void removeFromParent(Motion *m);
264 
267  static void addDescendants(Motion *m, const TreeData &tree);
268 
269  void constructSolution(Motion *startMotion, Motion *goalMotion,
270  const base::ReportIntermediateSolutionFn &intermediateSolutionCallback,
272 
273  enum RewireState
274  {
275  // use r-disc search for rewiring
276  RADIUS,
277  // use k-nearest for rewiring
278  KNEAREST,
279  // don't use any rewiring
280  OFF
281  };
282 
283  RewireState rewireState_ = KNEAREST;
284 
287  double rewireFactor_{1.1};
288 
290  double k_rrt_{0u};
291 
293  double r_rrt_{0.};
294 
297 
298  bool rewireGoalTree(Motion *addedMotion);
299 
301  bool isTimeBounded_;
302 
304  double initialTimeBound_;
305 
307  unsigned int initialBatchSize_ = 512;
308 
312 
315 
316  bool sampleOldBatch_ = true;
317 
321 
324 
327  };
328  } // namespace geometric
329 } // namespace ompl
330 
331 #endif
void setSampleUniformForUnboundedTime(bool uniform)
Whether the state space is sampled uniformly or centered at lower time values.
Definition: STRRTstar.cpp:1226
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition: RandomNumbers.h:88
void removeInvalidGoals(const std::vector< Motion * > &invalidGoals)
Remove invalid goal states from the goal set.
Definition: STRRTstar.cpp:854
double k_rrt_
A constant for k-nearest rewiring calculations.
Definition: STRRTstar.h:386
bool isTimeBounded_
Whether the time is bounded or not. The first solution automatically bounds the time.
Definition: STRRTstar.h:397
unsigned int numIterations_
The number of while loop iterations.
Definition: STRRTstar.h:311
A shared pointer wrapper for ompl::base::SpaceInformation.
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: STRRTstar.cpp:896
double timeBoundFactorIncrease_
The factor, the time bound is increased with after the batch is full.
Definition: STRRTstar.h:410
static void addDescendants(Motion *m, const TreeData &tree)
Adds given all descendants of the given motion to given tree and checks whether one of the added moti...
Definition: STRRTstar.cpp:957
static Motion * computeSolutionMotion(Motion *motion)
Find the solution (connecting) motion for a motion that is indirectly connected.
Definition: STRRTstar.cpp:833
unsigned int initialBatchSize_
Number of samples of the first batch.
Definition: STRRTstar.h:403
Definition of an abstract state.
Definition: State.h:113
bool sampleUniformForUnboundedTime_
Whether the samples are uniformly distributed over the whole space or are centered at lower times.
Definition: STRRTstar.h:416
void setRewiringToKNearest()
Rewire by k-nearest.
Definition: STRRTstar.cpp:1175
unsigned int getBatchSize() const
The number of samples before the time bound is increased.
Definition: STRRTstar.cpp:1194
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: STRRTstar.h:270
TreeData tStart_
The start tree.
Definition: STRRTstar.h:293
bool sampleGoalTime(base::State *goal, double oldBatchTimeBoundFactor, double newBatchTimeBoundFactor)
Samples the time component of a goal state dependant on its space component. Returns false,...
Definition: STRRTstar.cpp:1060
void setTimeBoundFactorIncrease(double f)
The value by which the time bound factor is multiplied in each increase step.
Definition: STRRTstar.cpp:1208
@ REACHED
the randomly sampled state was reached
Definition: STRRTstar.h:245
void increaseTimeBound(bool hasEqualBounds, double &oldBatchTimeBoundFactor, double &newBatchTimeBoundFactor, bool &startTree, unsigned int &batchSize, int &numBatchSamples)
Definition: STRRTstar.cpp:552
double getRange() const
Get the range the planner is using.
Definition: STRRTstar.cpp:1140
double initialTimeBound_
The time bound the planner is initialized with. Used to reset for repeated planning.
Definition: STRRTstar.h:400
base::State * tempState_
Definition: STRRTstar.h:341
base::ConditionalStateSampler sampler_
State sampler.
Definition: STRRTstar.h:290
GrowState
The state of the tree after an attempt to extend it.
Definition: STRRTstar.h:238
@ TRAPPED
no progress has been made
Definition: STRRTstar.h:241
double getOptimumApproxFactor() const
The Optimum Approximation factor (0 - 1).
Definition: STRRTstar.cpp:1145
TreeData tGoal_
The goal tree.
Definition: STRRTstar.h:296
Motion * pruneGoalTree()
Prune the goal tree after a solution was found. Return the goal motion, that is connected to the star...
Definition: STRRTstar.cpp:715
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
base::PathPtr bestSolution_
The current best solution path with respect to shortest time.
Definition: STRRTstar.h:305
double initialTimeBoundFactor_
Initial factor, the minimum time of each goal is multiplied with to calculate the upper time bound.
Definition: STRRTstar.h:407
void getNeighbors(TreeData &tree, Motion *motion, std::vector< Motion * > &nbh) const
Gets the neighbours of a given motion, using either k-nearest or radius_ as appropriate.
Definition: STRRTstar.cpp:972
std::vector< Motion * > newBatchGoalMotions_
The goal Motions, that were added in the current expansion step, used for uniform sampling over a gro...
Definition: STRRTstar.h:333
Motion * startMotion_
The start Motion, used for conditional sampling and start tree pruning.
Definition: STRRTstar.h:326
base::State * nextGoal(int n, double oldBatchTimeBoundFactor, double newBatchTimeBoundFactor)
N tries to sample a goal.
Definition: STRRTstar.cpp:1090
double distanceBetweenTrees_
Distance between the nearest pair of start tree and goal tree nodes.
Definition: STRRTstar.h:302
double upperTimeBound_
Upper bound for the time up to which solutions are searched for.
Definition: STRRTstar.h:320
int goalStateSampleRatio_
The ratio, a goal state is sampled compared to the size of the goal tree.
Definition: STRRTstar.h:419
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: STRRTstar.cpp:120
@ ADVANCED
progress has been made towards the randomly sampled state
Definition: STRRTstar.h:243
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition: STRRTstar.h:299
GrowState growTree(TreeData &tree, TreeGrowingInfo &tgi, Motion *rmotion, std::vector< Motion * > &nbh, bool connect)
Attempt to grow a tree towards a random state for the neighborhood of the random state....
Definition: STRRTstar.cpp:443
void calculateRewiringLowerBounds()
Calculate the k_RRG* and r_RRG* terms.
Definition: STRRTstar.cpp:1046
std::shared_ptr< ompl::NearestNeighbors< Motion * > > TreeData
A nearest-neighbor datastructure representing a tree of motions.
Definition: STRRTstar.h:226
void setRange(double distance)
Set the range the planner is supposed to use.
Definition: STRRTstar.cpp:1135
std::vector< Motion * > goalMotions_
The goal Motions, used for conditional sampling and pruning.
Definition: STRRTstar.h:329
void freeMemory()
Free the memory allocated by this planner.
Definition: STRRTstar.cpp:90
void setRewiringToRadius()
Rewire by radius.
Definition: STRRTstar.cpp:1170
double bestTime_
The current best time i.e. cost of all found solutions.
Definition: STRRTstar.h:308
double r_rrt_
A constant for r-disc rewiring calculations.
Definition: STRRTstar.h:389
double minimumTime_
Minimum Time at which any goal can be reached, if moving on a straight line.
Definition: STRRTstar.h:317
void setRewiringToOff()
Do not rewire at all.
Definition: STRRTstar.cpp:1165
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: STRRTstar.h:383
SpaceInformationPtr si_
The space information for which planning is done.
Definition: Planner.h:474
std::function< void(const Planner *, const std::vector< const base::State * > &, const Cost)> ReportIntermediateSolutionFn
When a planner has an intermediate solution (e.g., optimizing planners), a function with this signatu...
ompl::RNG rng_
The random number generator.
Definition: STRRTstar.h:422
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: STRRTstar.cpp:872
int numSolutions_
The number of found solutions.
Definition: STRRTstar.h:314
static void removeFromParent(Motion *m)
Removes the given motion from the parent's child list.
Definition: STRRTstar.cpp:938
void pruneStartTree()
Prune the start tree after a solution was found.
Definition: STRRTstar.cpp:651
GrowState growTreeSingle(TreeData &tree, TreeGrowingInfo &tgi, Motion *rmotion, Motion *nmotion)
Grow a tree towards a random state for a single nearest state.
Definition: STRRTstar.cpp:512
void setOptimumApproxFactor(double optimumApproxFactor)
Set the Optimum Approximation factor. This allows the planner to converge more quickly,...
Definition: STRRTstar.cpp:1150
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: STRRTstar.cpp:59
STRRTstar(const ompl::base::SpaceInformationPtr &si)
Constructor.
Definition: STRRTstar.cpp:40
void setInitialTimeBoundFactor(double f)
The initial time bound factor.
Definition: STRRTstar.cpp:1217
Main namespace. Contains everything in this library.
Definition: AppBase.h:21
double optimumApproxFactor_
The factor to which found solution times need to be reduced compared to minimum time,...
Definition: STRRTstar.h:323