RRTstar.h
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2011, Rice 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 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 /* Authors: Alejandro Perez, Sertac Karaman, Ryan Luna, Luis G. Torres, Ioan Sucan, Javier V Gomez */
36 
37 #ifndef OMPL_GEOMETRIC_PLANNERS_RRT_RRTSTAR_
38 #define OMPL_GEOMETRIC_PLANNERS_RRT_RRTSTAR_
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 <utility>
47 
48 
49 namespace ompl
50 {
51 
52  namespace geometric
53  {
54 
76  class RRTstar : public base::Planner
77  {
78  public:
79 
81 
82  virtual ~RRTstar();
83 
84  virtual void getPlannerData(base::PlannerData &data) const;
85 
87 
88  virtual void clear();
89 
99  void setGoalBias(double goalBias)
100  {
101  goalBias_ = goalBias;
102  }
103 
105  double getGoalBias() const
106  {
107  return goalBias_;
108  }
109 
115  void setRange(double distance)
116  {
117  maxDistance_ = distance;
118  }
119 
121  double getRange() const
122  {
123  return maxDistance_;
124  }
125 
127  template<template<typename T> class NN>
129  {
130  nn_.reset(new NN<Motion*>());
131  }
132 
140  void setDelayCC(bool delayCC)
141  {
142  delayCC_ = delayCC;
143  }
144 
146  bool getDelayCC() const
147  {
148  return delayCC_;
149  }
150 
152  void setPrune(const bool prune)
153  {
154  prune_ = prune;
155  }
156 
158  bool getPrune() const
159  {
160  return prune_;
161  }
162 
166  {
168  }
169 
172  {
173  return pruneStatesThreshold_;
174  }
175 
176  virtual void setup();
177 
179  // Planner progress property functions
180  std::string getIterationCount() const
181  {
182  return boost::lexical_cast<std::string>(iterations_);
183  }
184  std::string getBestCost() const
185  {
186  return boost::lexical_cast<std::string>(bestCost_);
187  }
188 
189  protected:
190 
192  class Motion
193  {
194  public:
197  state(si->allocState()),
198  parent(NULL)
199  {
200  }
201 
202  ~Motion()
203  {
204  }
205 
208 
211 
214 
217 
219  std::vector<Motion*> children;
220  };
221 
223  void freeMemory();
224 
225  // For sorting a list of costs and getting only their sorted indices
227  {
228  CostIndexCompare(const std::vector<base::Cost>& costs,
229  const base::OptimizationObjective &opt) :
230  costs_(costs), opt_(opt)
231  {}
232  bool operator()(unsigned i, unsigned j)
233  {
234  return opt_.isCostBetterThan(costs_[i],costs_[j]);
235  }
236  const std::vector<base::Cost>& costs_;
238  };
239 
241  double distanceFunction(const Motion *a, const Motion *b) const
242  {
243  return si_->distance(a->state, b->state);
244  }
245 
247  void removeFromParent(Motion *m);
248 
250  void updateChildCosts(Motion *m);
251 
254  int pruneTree(const base::Cost pruneTreeCost);
255 
257  void deleteBranch(Motion *motion);
258 
262  base::Cost costToGo(const Motion *motion, const bool shortest = true) const;
263 
266 
268  boost::shared_ptr< NearestNeighbors<Motion*> > nn_;
269 
271  double goalBias_;
272 
274  double maxDistance_;
275 
278 
280  bool delayCC_;
281 
284 
287 
289  std::vector<Motion*> goalMotions_;
290 
292  bool prune_;
293 
296 
297  struct PruneScratchSpace { std::vector<Motion*> newTree, toBePruned, candidates; } pruneScratchSpace_;
298 
301 
303  // Planner progress properties
305  unsigned int iterations_;
308  };
309  }
310 }
311 
312 #endif
double getRange() const
Get the range the planner is using.
Definition: RRTstar.h:121
bool getDelayCC() const
Get the state of the delayed collision checking option.
Definition: RRTstar.h:146
double getGoalBias() const
Get the goal bias the planner is using.
Definition: RRTstar.h:105
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:164
Optimal Rapidly-exploring Random Trees.
Definition: RRTstar.h:76
virtual void clear()
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: RRTstar.cpp:115
void setDelayCC(bool delayCC)
Option that delays collision checking procedures. When it is enabled, all neighbors are sorted by cos...
Definition: RRTstar.h:140
void updateChildCosts(Motion *m)
Updates the cost of the children of this node if the cost up to this node has changed.
Definition: RRTstar.cpp:533
base::OptimizationObjectivePtr opt_
Objective we&#39;re optimizing.
Definition: RRTstar.h:283
A boost shared pointer wrapper for ompl::base::StateSampler.
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: RRTstar.h:241
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)...
Definition: RRTstar.h:271
base::Cost cost
The cost up to this motion.
Definition: RRTstar.h:213
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
void setRange(double distance)
Set the range the planner is supposed to use.
Definition: RRTstar.h:115
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition: RRTstar.h:286
boost::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition: RRTstar.h:268
base::Cost bestCost_
Best cost found so far by algorithm.
Definition: RRTstar.h:307
virtual void setup()
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: RRTstar.cpp:79
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition: RRTstar.h:274
Representation of a motion.
Definition: RRTstar.h:192
base::State * state
The state contained by the motion.
Definition: RRTstar.h:207
void freeMemory()
Free the memory allocated by this planner.
Definition: RRTstar.cpp:542
void setPruneStatesImprovementThreshold(const double pp)
Set the percentage threshold (between 0 and 1) for pruning the tree. If the new tree has removed at l...
Definition: RRTstar.h:165
Main namespace. Contains everything in this library.
Definition: Cost.h:42
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition: RandomNumbers.h:54
Base class for a planner.
Definition: Planner.h:232
void deleteBranch(Motion *motion)
Deletes (frees memory) the motion and its children motions.
Definition: RRTstar.cpp:616
void setPrune(const bool prune)
Controls whether the tree is pruned during the search.
Definition: RRTstar.h:152
int pruneTree(const base::Cost pruneTreeCost)
Prunes all those states which estimated total cost is higher than pruneTreeCost. Returns the number o...
Definition: RRTstar.cpp:578
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
virtual void getPlannerData(base::PlannerData &data) const
Get information about the current run of the motion planner. Repeated calls to this function will upd...
Definition: RRTstar.cpp:557
A boost shared pointer wrapper for ompl::base::SpaceInformation.
Definition of an abstract state.
Definition: State.h:50
std::vector< Motion * > children
The set of motions descending from the current motion.
Definition: RRTstar.h:219
bool prune_
If this value is set to true, tree pruning will be enabled.
Definition: RRTstar.h:292
Abstract definition of optimization objectives.
base::StateSamplerPtr sampler_
State sampler.
Definition: RRTstar.h:265
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
Definition: RRTstar.h:128
A boost shared pointer wrapper for ompl::base::OptimizationObjective.
RNG rng_
The random number generator.
Definition: RRTstar.h:277
double getPruneStatesImprovementThreshold() const
Get the current prune states percentage threshold parameter.
Definition: RRTstar.h:171
base::Cost costToGo(const Motion *motion, const bool shortest=true) const
Computes the Cost To Go heuristically as the cost to come from start to motion plus the cost to go fr...
Definition: RRTstar.cpp:637
Motion * parent
The parent motion in the exploration tree.
Definition: RRTstar.h:210
bool delayCC_
Option to delay and reduce collision checking within iterations.
Definition: RRTstar.h:280
bool getPrune() const
Get the state of the pruning option.
Definition: RRTstar.h:158
virtual base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc)
Function that can solve the motion planning problem. This function can be called multiple times on th...
Definition: RRTstar.cpp:130
void removeFromParent(Motion *m)
Removes the given motion from the parent&#39;s child list.
Definition: RRTstar.cpp:522
void setGoalBias(double goalBias)
Set the goal bias.
Definition: RRTstar.h:99
SpaceInformationPtr si_
The space information for which planning is done.
Definition: Planner.h:397
Motion(const base::SpaceInformationPtr &si)
Constructor that allocates memory for the state. This constructor automatically allocates memory for ...
Definition: RRTstar.h:196
std::vector< Motion * > goalMotions_
A list of states in the tree that satisfy the goal condition.
Definition: RRTstar.h:289
double pruneStatesThreshold_
The tree is only pruned is the percentage of states to prune is above this threshold (between 0 and 1...
Definition: RRTstar.h:295
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition: Cost.h:47
base::Cost incCost
The incremental cost of this motion&#39;s parent to this motion (this is stored to save distance computat...
Definition: RRTstar.h:216
Motion * startMotion_
Stores the Motion containing the last added initial start state.
Definition: RRTstar.h:300
unsigned int iterations_
Number of iterations the algorithm performed.
Definition: RRTstar.h:305