LBTRRT.h
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2015, Tel Aviv 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 Tel Aviv 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: Oren Salzman, Sertac Karaman, Ioan Sucan, Mark Moll */
36 
37 #ifndef OMPL_GEOMETRIC_PLANNERS_RRT_LBT_RRT_
38 #define OMPL_GEOMETRIC_PLANNERS_RRT_LBT_RRT_
39 
40 #include "ompl/geometric/planners/PlannerIncludes.h"
41 #include "ompl/base/OptimizationObjective.h"
42 #include "ompl/datastructures/NearestNeighbors.h"
43 #include "ompl/datastructures/DynamicSSSP.h"
44 
45 #include <fstream>
46 
47 namespace ompl
48 {
49  namespace geometric
50  {
71  class LBTRRT : public base::Planner
72  {
73  public:
76 
77  ~LBTRRT() override;
78 
79  void getPlannerData(base::PlannerData &data) const override;
80 
82 
83  void clear() override;
84 
94  void setGoalBias(double goalBias)
95  {
96  goalBias_ = goalBias;
97  }
98 
100  double getGoalBias() const
101  {
102  return goalBias_;
103  }
104 
110  void setRange(double distance)
111  {
112  maxDistance_ = distance;
113  }
114 
116  double getRange() const
117  {
118  return maxDistance_;
119  }
120 
122  template <template <typename T> class NN>
124  {
125  if (nn_ && nn_->size() != 0)
126  OMPL_WARN("Calling setNearestNeighbors will clear all states.");
127  clear();
128  nn_ = std::make_shared<NN<Motion *>>();
129  setup();
130  }
131 
132  void setup() override;
133 
135  void setApproximationFactor(double epsilon)
136  {
137  epsilon_ = epsilon;
138  }
139 
141  double getApproximationFactor() const
142  {
143  return epsilon_;
144  }
145 
147  // Planner progress property functions
148  std::string getIterationCount() const
149  {
150  return std::to_string(iterations_);
151  }
152  std::string getBestCost() const
153  {
154  return std::to_string(bestCost_);
155  }
156 
157  protected:
162  class Motion
163  {
164  public:
165  Motion() = default;
166 
169  : state_(si->allocState())
170  {
171  }
172 
173  ~Motion() = default;
174 
176  base::State *state_{nullptr};
178  std::size_t id_;
184  double costLb_;
186  Motion *parentApx_{nullptr};
188  double costApx_{0.0};
190  std::vector<Motion *> childrenApx_;
191  };
192 
194  struct IsLessThan
195  {
196  IsLessThan(LBTRRT *plannerPtr, Motion *motion) : plannerPtr_(plannerPtr), motion_(motion)
197  {
198  }
199 
200  bool operator()(const Motion *motionA, const Motion *motionB)
201  {
202  double costA = motionA->costLb_;
203  double costB = motionB->costLb_;
204 
205  double distA = plannerPtr_->distanceFunction(motionA, motion_);
206  double distB = plannerPtr_->distanceFunction(motionB, motion_);
207 
208  return costA + distA < costB + distB;
209  }
210  LBTRRT *plannerPtr_;
211  Motion *motion_;
212  }; // IsLessThan
213 
216  {
217  IsLessThanLB(LBTRRT *plannerPtr) : plannerPtr_(plannerPtr)
218  {
219  }
220 
221  bool operator()(const Motion *motionA, const Motion *motionB) const
222  {
223  return motionA->costLb_ < motionB->costLb_;
224  }
225  LBTRRT *plannerPtr_;
226  }; // IsLessThanLB
227 
228  typedef std::set<Motion *, IsLessThanLB> Lb_queue;
229  typedef Lb_queue::iterator Lb_queue_iter;
230 
232  void considerEdge(Motion *parent, Motion *child, double c);
233 
235  double lazilyUpdateApxParent(Motion *child, Motion *parent);
236 
238  void updateChildCostsApx(Motion *m, double delta);
239 
241  void removeFromParentApx(Motion *m);
242 
244  void freeMemory();
245 
247  double distanceFunction(const Motion *a, const Motion *b) const
248  {
249  return si_->distance(a->state_, b->state_);
250  }
251 
253  bool checkMotion(const Motion *a, const Motion *b)
254  {
255  return checkMotion(a->state_, b->state_);
256  }
258  bool checkMotion(const base::State *a, const base::State *b)
259  {
260  return si_->checkMotion(a, b);
261  }
262 
264  Motion *getMotion(std::size_t i)
265  {
266  return idToMotionMap_[i];
267  }
268 
271 
273  std::shared_ptr<NearestNeighbors<Motion *>> nn_;
274 
277 
279  std::vector<Motion *> idToMotionMap_;
280 
283  double goalBias_{.05};
284 
286  double maxDistance_{0.};
287 
289  double epsilon_{.4};
290 
293 
296 
298  // Planner progress properties
300  unsigned int iterations_{0u};
302  double bestCost_;
303  };
304  }
305 }
306 
307 #endif // OMPL_GEOMETRIC_PLANNERS_RRT_LBT_RRT_
void updateChildCostsApx(Motion *m, double delta)
update the child cost of the approximation tree
Definition: LBTRRT.cpp:403
double costApx_
The approximation cost.
Definition: LBTRRT.h:188
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: LBTRRT.cpp:383
comparator - metric is the lower bound cost
Definition: LBTRRT.h:215
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:174
void setApproximationFactor(double epsilon)
Set the apprimation factor.
Definition: LBTRRT.h:135
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: LBTRRT.cpp:110
void freeMemory()
Free the memory allocated by this planner.
Definition: LBTRRT.cpp:97
LBTRRT(const base::SpaceInformationPtr &si)
Constructor.
Definition: LBTRRT.cpp:44
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: LBTRRT.h:247
base::State * state_
The state contained by the motion.
Definition: LBTRRT.h:176
A shared pointer wrapper for ompl::base::StateSampler.
double getGoalBias() const
Get the goal bias the planner is using.
Definition: LBTRRT.h:100
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition: LBTRRT.h:286
Lower Bound Tree Rapidly-exploring Random Trees.
Definition: LBTRRT.h:71
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: LBTRRT.cpp:83
void removeFromParentApx(Motion *m)
remove motion from its parent in the approximation tree
Definition: LBTRRT.cpp:424
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)...
Definition: LBTRRT.h:283
Main namespace. Contains everything in this library.
Definition: AppBase.h:21
RNG rng_
The random number generator.
Definition: LBTRRT.h:292
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition: RandomNumbers.h:58
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition: LBTRRT.h:295
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition: LBTRRT.h:273
Base class for a planner.
Definition: Planner.h:223
bool checkMotion(const base::State *a, const base::State *b)
local planner
Definition: LBTRRT.h:258
double getRange() const
Get the range the planner is using.
Definition: LBTRRT.h:116
DynamicSSSP lowerBoundGraph_
A graph of motions Glb.
Definition: LBTRRT.h:276
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
A shared pointer wrapper for ompl::base::SpaceInformation.
double epsilon_
approximation factor
Definition: LBTRRT.h:289
bool checkMotion(const Motion *a, const Motion *b)
local planner
Definition: LBTRRT.h:253
std::vector< Motion * > idToMotionMap_
mapping between a motion id and the motion
Definition: LBTRRT.h:279
Definition of an abstract state.
Definition: State.h:49
void setRange(double distance)
Set the range the planner is supposed to use.
Definition: LBTRRT.h:110
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition: Console.h:66
void considerEdge(Motion *parent, Motion *child, double c)
consider an edge for addition to the roadmap
Definition: LBTRRT.cpp:305
Motion * parentApx_
The parent motion in the approximation tree.
Definition: LBTRRT.h:186
Motion(const base::SpaceInformationPtr &si)
Constructor that allocates memory for the state.
Definition: LBTRRT.h:168
Motion * getMotion(std::size_t i)
get motion from id
Definition: LBTRRT.h:264
double lazilyUpdateApxParent(Motion *child, Motion *parent)
lazily update the parent in the approximation tree without updating costs to cildren ...
Definition: LBTRRT.cpp:412
comparator - metric is the cost to reach state via a specific state
Definition: LBTRRT.h:194
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: LBTRRT.cpp:70
double bestCost_
Best cost found so far by algorithm.
Definition: LBTRRT.h:302
double costLb_
The lower bound cost of the motion while it is stored in the lowerBoundGraph_ and this may seem redun...
Definition: LBTRRT.h:184
double getApproximationFactor() const
Get the apprimation factor.
Definition: LBTRRT.h:141
void setGoalBias(double goalBias)
Set the goal bias.
Definition: LBTRRT.h:94
Representation of a motion.
Definition: LBTRRT.h:162
SpaceInformationPtr si_
The space information for which planning is done.
Definition: Planner.h:406
std::size_t id_
unique id of the motion
Definition: LBTRRT.h:178
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
Definition: LBTRRT.h:123
std::vector< Motion * > childrenApx_
The children in the approximation tree.
Definition: LBTRRT.h:190
unsigned int iterations_
Number of iterations the algorithm performed.
Definition: LBTRRT.h:300
base::StateSamplerPtr sampler_
State sampler.
Definition: LBTRRT.h:270