RRTXstatic.h
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2016, Georgia Institute of Technology
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 Rice 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: Florian Hauer */
36 
37 #ifndef OMPL_GEOMETRIC_PLANNERS_RRT_RRTXSTATIC_
38 #define OMPL_GEOMETRIC_PLANNERS_RRT_RRTXSTATIC_
39 
40 #include <ompl/datastructures/BinaryHeap.h>
41 #include "ompl/base/OptimizationObjective.h"
42 #include "ompl/datastructures/NearestNeighbors.h"
43 #include "ompl/geometric/planners/PlannerIncludes.h"
44 
45 #include <deque>
46 #include <limits>
47 #include <list>
48 #include <queue>
49 #include <utility>
50 #include <vector>
51 
52 namespace ompl
53 {
54  namespace geometric
55  {
103  class RRTXstatic : public base::Planner
104  {
105  public:
106  RRTXstatic(const base::SpaceInformationPtr &si);
107 
108  ~RRTXstatic() override;
109 
110  void getPlannerData(base::PlannerData &data) const override;
111 
112  base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override;
113 
114  void clear() override;
115 
116  void setup() override;
117 
127  void setGoalBias(double goalBias)
128  {
129  goalBias_ = goalBias;
130  }
131 
133  double getGoalBias() const
134  {
135  return goalBias_;
136  }
137 
140  void setInformedSampling(bool informedSampling);
141 
143  bool getInformedSampling() const
144  {
145  return useInformedSampling_;
146  }
147 
149  void setSampleRejection(bool reject);
150 
152  bool getSampleRejection() const
153  {
154  return useRejectionSampling_;
155  }
156 
158  void setNumSamplingAttempts(unsigned int numAttempts)
159  {
160  numSampleAttempts_ = numAttempts;
161  }
162 
164  unsigned int getNumSamplingAttempts() const
165  {
166  return numSampleAttempts_;
167  }
168 
173  virtual void setEpsilon(double epsilon)
174  {
175  epsilonCost_ = base::Cost(epsilon);
176  }
177 
179  double getEpsilon() const
180  {
181  return epsilonCost_.value();
182  }
183 
189  void setRange(double distance)
190  {
191  maxDistance_ = distance;
192  }
193 
195  double getRange() const
196  {
197  return maxDistance_;
198  }
199 
202  void setRewireFactor(double rewireFactor)
203  {
204  rewireFactor_ = rewireFactor;
206  }
207 
210  double getRewireFactor() const
211  {
212  return rewireFactor_;
213  }
214 
216  template <template <typename T> class NN>
217  void setNearestNeighbors()
218  {
219  if (nn_ && nn_->size() != 0)
220  OMPL_WARN("Calling setNearestNeighbors will clear all states.");
221  clear();
222  nn_ = std::make_shared<NN<Motion *>>();
223  setup();
224  }
225 
227  void setKNearest(bool useKNearest)
228  {
229  useKNearest_ = useKNearest;
230  }
231 
233  bool getKNearest() const
234  {
235  return useKNearest_;
236  }
237 
239  void setUpdateChildren(bool val)
240  {
241  updateChildren_ = val;
242  }
243 
245  bool getUpdateChildren() const
246  {
247  return updateChildren_;
248  }
249 
251  void setVariant(const int variant)
252  {
253  if (variant < 0 || variant > 3)
254  throw Exception("Variant must be 0 (original RRT#) or in [1, 3]");
255  variant_ = variant;
256  }
257 
259  int getVariant() const
260  {
261  return variant_;
262  }
263 
265  void setAlpha(const double a)
266  {
267  alpha_ = a;
268  }
269 
271  double getAlpha() const
272  {
273  return alpha_;
274  }
275 
276  unsigned int numIterations() const
277  {
278  return iterations_;
279  }
280 
281  ompl::base::Cost bestCost() const
282  {
283  return bestCost_;
284  }
285 
286  protected:
287  class Motion;
288 
290  struct MotionCompare
291  {
293  MotionCompare(base::OptimizationObjectivePtr opt, base::ProblemDefinitionPtr pdef)
294  : opt_(std::move(opt)), pdef_(std::move(pdef))
295  {
296  }
297 
299  inline base::Cost costPlusHeuristic(const Motion *m) const
300  {
301  return opt_->combineCosts(m->cost, opt_->costToGo(m->state, pdef_->getGoal().get()));
302  }
303 
305  inline base::Cost alphaCostPlusHeuristic(const Motion *m, double alpha) const
306  {
307  return opt_->combineCosts(base::Cost(alpha * m->cost.value()),
308  opt_->costToGo(m->state, pdef_->getGoal().get()));
309  }
310 
312  inline bool operator()(const Motion *m1, const Motion *m2) const
313  {
314  // we use a max heap, to do a min heap so the operator < returns > in order to make it a min heap
315  return !opt_->isCostBetterThan(costPlusHeuristic(m1), costPlusHeuristic(m2));
316  }
317 
319  base::OptimizationObjectivePtr opt_;
320 
322  base::ProblemDefinitionPtr pdef_;
323  };
324 
326  class Motion
327  {
328  public:
331  Motion(const base::SpaceInformationPtr &si) : state(si->allocState()), parent(nullptr), handle(nullptr)
332  {
333  }
334 
335  ~Motion() = default;
336 
339 
342 
345 
347  std::vector<Motion *> children;
348 
351  std::vector<std::pair<Motion *, bool>> nbh;
352 
355  };
356 
358  void allocSampler();
359 
361  bool sampleUniform(base::State *statePtr);
362 
364  void freeMemory();
365 
367  double distanceFunction(const Motion *a, const Motion *b) const
368  {
369  return si_->distance(a->state, b->state);
370  }
371 
373  void updateQueue(Motion *x);
374 
376  void removeFromParent(Motion *m);
377 
379  void getNeighbors(Motion *motion) const;
380 
383 
385  void calculateRRG();
386 
388  bool includeVertex(const Motion *x) const;
389 
391  base::StateSamplerPtr sampler_;
392 
394  base::InformedSamplerPtr infSampler_;
395 
397  std::shared_ptr<NearestNeighbors<Motion *>> nn_;
398 
401  double goalBias_{.05};
402 
404  double maxDistance_{0.};
405 
407  RNG rng_;
408 
410  bool useKNearest_{true};
411 
414  double rewireFactor_{1.1};
415 
417  double k_rrt_{0u};
419  double r_rrt_{0.};
420 
422  base::OptimizationObjectivePtr opt_;
423 
425  Motion *lastGoalMotion_{nullptr};
426 
428  std::vector<Motion *> goalMotions_;
429 
431  base::Cost bestCost_{std::numeric_limits<double>::quiet_NaN()};
432 
434  unsigned int iterations_{0u};
435 
438 
441 
444 
446  bool updateChildren_{true};
447 
449  double rrg_r_;
450 
452  unsigned int rrg_k_;
453 
455  int variant_{0};
456 
458  double alpha_{1.};
459 
461  bool useInformedSampling_{false};
462 
464  bool useRejectionSampling_{false};
465 
467  unsigned int numSampleAttempts_{100u};
468 
470  // Planner progress property functions
471  std::string numIterationsProperty() const
472  {
473  return std::to_string(numIterations());
474  }
475  std::string bestCostProperty() const
476  {
477  return std::to_string(bestCost().value());
478  }
479  std::string numMotionsProperty() const
480  {
481  return std::to_string(nn_->size());
482  }
483  };
484  }
485 }
486 
487 #endif
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition: RandomNumbers.h:89
double alpha_
Alpha parameter, scaling the rejection sampling tests.
Definition: RRTXstatic.h:554
MotionCompare(base::OptimizationObjectivePtr opt, base::ProblemDefinitionPtr pdef)
Constructor.
Definition: RRTXstatic.h:389
bool useKNearest_
Option to use k-nearest search for rewiring.
Definition: RRTXstatic.h:506
std::vector< Motion * > goalMotions_
A list of states in the tree that satisfy the goal condition.
Definition: RRTXstatic.h:524
RNG rng_
The random number generator.
Definition: RRTXstatic.h:503
void setVariant(const int variant)
Set variant used for rejection sampling.
Definition: RRTXstatic.h:347
double getEpsilon() const
Get the threshold epsilon the planner is using.
Definition: RRTXstatic.h:275
std::vector< std::pair< Motion *, bool > > nbh
The set of neighbors of this motion with a boolean indicating if the feasibility of edge as been test...
Definition: RRTXstatic.h:447
MotionCompare mc_
Comparator of motions, used to order the queue.
Definition: RRTXstatic.h:533
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)
Definition: RRTXstatic.h:497
BinaryHeap< Motion *, MotionCompare > q_
Queue to order the nodes to update.
Definition: RRTXstatic.h:536
base::State * state
The state contained by the motion.
Definition: RRTXstatic.h:434
void setRange(double distance)
Set the range the planner is supposed to use.
Definition: RRTXstatic.h:285
Definition of an abstract state.
Definition: State.h:113
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: RRTXstatic.cpp:89
void allocSampler()
Create the samplers.
Definition: RRTXstatic.cpp:737
bool getKNearest() const
Get the state of using a k-nearest search for rewiring.
Definition: RRTXstatic.h:329
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
Definition: RRTXstatic.h:313
base::ProblemDefinitionPtr pdef_
Pointer to the Problem Definition.
Definition: RRTXstatic.h:418
unsigned int iterations_
Number of iterations the algorithm performed.
Definition: RRTXstatic.h:530
base::OptimizationObjectivePtr opt_
Pointer to the Optimization Objective.
Definition: RRTXstatic.h:415
bool getInformedSampling() const
Get the state direct heuristic sampling.
Definition: RRTXstatic.h:239
bool useInformedSampling_
Option to use informed sampling.
Definition: RRTXstatic.h:557
bool includeVertex(const Motion *x) const
Test if the vertex should be included according to the variant in use.
Definition: RRTXstatic.cpp:615
void setAlpha(const double a)
Set the value alpha used for rejection sampling.
Definition: RRTXstatic.h:361
double value() const
The value of the cost.
Definition: Cost.h:152
void getNeighbors(Motion *motion) const
Gets the neighbours of a given motion, using either k-nearest of radius as appropriate.
Definition: RRTXstatic.cpp:592
void setUpdateChildren(bool val)
Set whether or not to always propagate cost updates to children.
Definition: RRTXstatic.h:335
Representation of a motion (node of the tree)
Definition: RRTXstatic.h:422
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition: Cost.h:111
Motion * parent
The parent motion in the exploration tree.
Definition: RRTXstatic.h:437
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition: RRTXstatic.h:521
void setGoalBias(double goalBias)
Set the goal bias.
Definition: RRTXstatic.h:223
void calculateRewiringLowerBounds()
Calculate the k_RRG* and r_RRG* terms.
Definition: RRTXstatic.cpp:780
base::Cost bestCost_
Best cost found so far by algorithm.
Definition: RRTXstatic.h:527
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: RRTXstatic.h:298
base::StateSamplerPtr sampler_
State sampler.
Definition: RRTXstatic.h:487
base::Cost costPlusHeuristic(const Motion *m) const
Combines the current cost of a motion and the heuritic to the goal.
Definition: RRTXstatic.h:395
double k_rrt_
A constant for k-nearest rewiring calculations.
Definition: RRTXstatic.h:513
void setSampleRejection(bool reject)
Controls whether heuristic rejection is used on samples (e.g., x_rand)
Definition: RRTXstatic.cpp:701
base::InformedSamplerPtr infSampler_
An informed sampler.
Definition: RRTXstatic.h:490
This class provides an implementation of an updatable min-heap. Using it is a bit cumbersome,...
Definition: BinaryHeap.h:84
void setNumSamplingAttempts(unsigned int numAttempts)
Set the number of attempts to make while performing rejection or informed sampling.
Definition: RRTXstatic.h:254
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition: RRTXstatic.h:493
base::OptimizationObjectivePtr opt_
Objective we're optimizing.
Definition: RRTXstatic.h:518
void setKNearest(bool useKNearest)
Use a k-nearest search for rewiring instead of a r-disc search.
Definition: RRTXstatic.h:323
base::Cost epsilonCost_
Threshold for the propagation of information.
Definition: RRTXstatic.h:539
bool getSampleRejection() const
Get the state of the sample rejection option.
Definition: RRTXstatic.h:248
base::Cost cost
The cost up to this motion.
Definition: RRTXstatic.h:440
double getAlpha() const
Get the value alpha used for rejection sampling.
Definition: RRTXstatic.h:367
double rrg_r_
Current value of the radius used for the neighbors.
Definition: RRTXstatic.h:545
int variant_
Variant used for rejection sampling.
Definition: RRTXstatic.h:551
void removeFromParent(Motion *m)
Removes the given motion from the parent's child list.
Definition: RRTXstatic.cpp:572
BinaryHeap< Motion *, MotionCompare >::Element * handle
Handle to identify the motion in the queue.
Definition: RRTXstatic.h:450
void setInformedSampling(bool informedSampling)
Use direct sampling of the heuristic for the generation of random samples (e.g., x_rand)....
Definition: RRTXstatic.cpp:665
bool sampleUniform(base::State *statePtr)
Generate a sample.
Definition: RRTXstatic.cpp:759
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: RRTXstatic.cpp:645
unsigned int getNumSamplingAttempts() const
Get the number of attempts to make while performing rejection or informed sampling.
Definition: RRTXstatic.h:260
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition: Console.h:66
Defines the operator to compare motions.
Definition: RRTXstatic.h:386
unsigned int rrg_k_
Current value of the number of neighbors used.
Definition: RRTXstatic.h:548
virtual void setEpsilon(double epsilon)
Set the threshold epsilon.
Definition: RRTXstatic.h:269
bool getUpdateChildren() const
True if the cost is always propagate to children.
Definition: RRTXstatic.h:341
Motion(const base::SpaceInformationPtr &si)
Constructor that allocates memory for the state. This constructor automatically allocates memory for ...
Definition: RRTXstatic.h:427
double rewireFactor_
The rewiring factor, s, so that r_rrg = s \times r_rrg* > r_rrg* (or k_rrg = s \times k_rrg* > k_rrg*...
Definition: RRTXstatic.h:510
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: RRTXstatic.h:463
bool operator()(const Motion *m1, const Motion *m2) const
Ordering of motions.
Definition: RRTXstatic.h:408
bool useRejectionSampling_
The status of the sample rejection parameter.
Definition: RRTXstatic.h:560
SpaceInformationPtr si_
The space information for which planning is done.
Definition: Planner.h:474
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: RRTXstatic.h:306
double getRange() const
Get the range the planner is using.
Definition: RRTXstatic.h:291
void updateQueue(Motion *x)
Update (or add) a motion in the queue.
Definition: RRTXstatic.cpp:559
unsigned int numSampleAttempts_
The number of attempts to make at informed sampling.
Definition: RRTXstatic.h:563
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: RRTXstatic.cpp:137
void calculateRRG()
Calculate the rrg_r_ and rrg_k_ terms.
Definition: RRTXstatic.cpp:584
base::Cost alphaCostPlusHeuristic(const Motion *m, double alpha) const
Combines the current cost of a motion, weighted by alpha, and the heuritic to the goal.
Definition: RRTXstatic.h:401
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: RRTXstatic.cpp:154
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition: RRTXstatic.h:500
bool updateChildren_
Whether or not to propagate the cost to children if the update is less than epsilon.
Definition: RRTXstatic.h:542
The exception type for ompl.
Definition: Exception.h:78
double getGoalBias() const
Get the goal bias the planner is using.
Definition: RRTXstatic.h:229
int getVariant() const
Get variant used for rejection sampling.
Definition: RRTXstatic.h:355
void freeMemory()
Free the memory allocated by this planner.
Definition: RRTXstatic.cpp:630
double r_rrt_
A constant for r-disc rewiring calculations.
Definition: RRTXstatic.h:515
Main namespace. Contains everything in this library.
Definition: AppBase.h:21
std::vector< Motion * > children
The set of motions descending from the current motion.
Definition: RRTXstatic.h:443