LazyLBTRRT.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, Mark Moll */
36 
37 #ifndef OMPL_CONTRIB_LAZY_LBTRRT_
38 #define OMPL_CONTRIB_LAZY_LBTRRT_
39 
40 #include "ompl/geometric/planners/PlannerIncludes.h"
41 #include "ompl/datastructures/NearestNeighbors.h"
42 #include "ompl/base/goals/GoalSampleableRegion.h"
43 #include "ompl/datastructures/LPAstarOnGraph.h"
44 
45 #include <fstream>
46 #include <vector>
47 #include <tuple>
48 #include <cassert>
49 
50 #include <boost/graph/graph_traits.hpp>
51 #include <boost/graph/adjacency_list.hpp>
52 
53 namespace ompl
54 {
55  namespace geometric
56  {
58  class LazyLBTRRT : public base::Planner
59  {
60  public:
63 
64  ~LazyLBTRRT() override;
65 
66  void getPlannerData(base::PlannerData &data) const override;
67 
69 
70  void clear() override;
71 
81  void setGoalBias(double goalBias)
82  {
83  goalBias_ = goalBias;
84  }
85 
87  double getGoalBias() const
88  {
89  return goalBias_;
90  }
91 
97  void setRange(double distance)
98  {
99  maxDistance_ = distance;
100  }
101 
103  double getRange() const
104  {
105  return maxDistance_;
106  }
107 
109  template <template <typename T> class NN>
111  {
112  if (nn_ && nn_->size() != 0)
113  OMPL_WARN("Calling setNearestNeighbors will clear all states.");
114  clear();
115  nn_ = std::make_shared<NN<Motion *>>();
116  setup();
117  }
118 
119  void setup() override;
120 
122  void setApproximationFactor(double epsilon)
123  {
124  epsilon_ = epsilon;
125  }
126 
128  // Planner progress property functions
129  std::string getIterationCount() const
130  {
131  return std::to_string(iterations_);
132  }
133  std::string getBestCost() const
134  {
135  return std::to_string(bestCost_);
136  }
137 
138  protected:
140  class Motion
141  {
142  public:
143  Motion() : state_(nullptr)
144  {
145  }
146 
148  Motion(const base::SpaceInformationPtr &si) : state_(si->allocState())
149  {
150  }
151 
152  ~Motion() = default;
153 
155  std::size_t id_;
156 
159  };
160 
161  typedef boost::property<boost::edge_weight_t, double> WeightProperty;
162  typedef boost::adjacency_list<boost::vecS, // container type for the out edge list
163  boost::vecS, // container type for the vertex list
164  boost::undirectedS, // directedS / undirectedS / bidirectionalS.
165  std::size_t, // vertex properties
166  WeightProperty // edge properties
167  >
168  BoostGraph;
169 
170  friend class CostEstimatorApx; // allow CostEstimatorApx access to private members
172  {
173  public:
174  CostEstimatorApx(LazyLBTRRT *alg) : alg_(alg)
175  {
176  }
177  double operator()(std::size_t i)
178  {
179  double lb_estimate = (*(alg_->LPAstarLb_))(i);
180  if (lb_estimate != std::numeric_limits<double>::infinity())
181  return lb_estimate;
182 
183  return alg_->distanceFunction(alg_->idToMotionMap_[i], alg_->startMotion_);
184  }
185 
186  private:
187  LazyLBTRRT *alg_;
188  Motion *target_;
189  }; // CostEstimatorApx
190 
192  {
193  public:
194  CostEstimatorLb(base::Goal *goal, std::vector<Motion *> &idToMotionMap)
195  : goal_(goal), idToMotionMap_(idToMotionMap)
196  {
197  }
198  double operator()(std::size_t i)
199  {
200  double dist = 0.0;
201  goal_->isSatisfied(idToMotionMap_[i]->state_, &dist);
202 
203  return dist;
204  }
205 
206  private:
207  base::Goal *goal_;
208  std::vector<Motion *> &idToMotionMap_;
209  }; // CostEstimatorLb
210 
213 
215  void sampleBiased(const base::GoalSampleableRegion *goal_s, base::State *rstate);
216 
218  void freeMemory();
219 
221  double distanceFunction(const base::State *a, const base::State *b) const
222  {
223  return si_->distance(a, b);
224  }
225  double distanceFunction(const Motion *a, const Motion *b) const
226  {
227  return si_->distance(a->state_, b->state_);
228  }
229  bool checkMotion(const base::State *a, const base::State *b) const
230  {
231  return si_->checkMotion(a, b);
232  }
233  bool checkMotion(const Motion *a, const Motion *b) const
234  {
235  return si_->checkMotion(a->state_, b->state_);
236  }
237 
238  Motion *getMotion(std::size_t id) const
239  {
240  assert(idToMotionMap_.size() > id);
241  return idToMotionMap_[id];
242  }
243  void addVertex(const Motion *a)
244  {
245  boost::add_vertex(a->id_, graphApx_);
246  boost::add_vertex(a->id_, graphLb_);
247  }
248 
249  void addEdgeApx(Motion *a, Motion *b, double c)
250  {
251  WeightProperty w(c);
252  boost::add_edge(a->id_, b->id_, w, graphApx_);
253  LPAstarApx_->insertEdge(a->id_, b->id_, c);
254  LPAstarApx_->insertEdge(b->id_, a->id_, c);
255  }
256  void addEdgeLb(const Motion *a, const Motion *b, double c)
257  {
258  WeightProperty w(c);
259  boost::add_edge(a->id_, b->id_, w, graphLb_);
260  LPAstarLb_->insertEdge(a->id_, b->id_, c);
261  LPAstarLb_->insertEdge(b->id_, a->id_, c);
262  }
263  bool edgeExistsApx(std::size_t a, std::size_t b)
264  {
265  return boost::edge(a, b, graphApx_).second;
266  }
267  bool edgeExistsApx(const Motion *a, const Motion *b)
268  {
269  return edgeExistsApx(a->id_, b->id_);
270  }
271  bool edgeExistsLb(const Motion *a, const Motion *b)
272  {
273  return boost::edge(a->id_, b->id_, graphLb_).second;
274  }
275  void removeEdgeLb(const Motion *a, const Motion *b)
276  {
277  boost::remove_edge(a->id_, b->id_, graphLb_);
278  LPAstarLb_->removeEdge(a->id_, b->id_);
279  LPAstarLb_->removeEdge(b->id_, a->id_);
280  return;
281  }
282  std::tuple<Motion *, base::State *, double> rrtExtend(const base::GoalSampleableRegion *goal_s,
283  base::State *xstate, Motion *rmotion,
284  double &approxdif);
286  base::State *xstate, Motion *rmotion, double &approxdif);
287  Motion *createMotion(const base::GoalSampleableRegion *goal_s, const base::State *st);
288  Motion *createGoalMotion(const base::GoalSampleableRegion *goal_s);
289 
290  void closeBounds(const base::PlannerTerminationCondition &ptc);
291 
293  double getApproximationFactor() const
294  {
295  return epsilon_;
296  }
297 
300 
302  std::shared_ptr<NearestNeighbors<Motion *>> nn_;
303 
306  double goalBias_;
307 
309  double maxDistance_;
310 
313 
315  double epsilon_;
316 
319 
320  BoostGraph graphLb_;
321  BoostGraph graphApx_;
322  Motion *startMotion_;
323  Motion *goalMotion_; // root of LPAstarApx_
324  LPAstarApx *LPAstarApx_; // rooted at target
325  LPAstarLb *LPAstarLb_; // rooted at source
326  std::vector<Motion *> idToMotionMap_;
327 
329  // Planner progress properties
331  unsigned int iterations_;
333  double bestCost_;
334  };
335  }
336 }
337 
338 #endif // OMPL_CONTRIB_LAZY_LBTRRT_
base::State * state_
The state contained by the motion.
Definition: LazyLBTRRT.h:158
base::StateSamplerPtr sampler_
State sampler.
Definition: LazyLBTRRT.h:299
unsigned int iterations_
Number of iterations the algorithm performed.
Definition: LazyLBTRRT.h:331
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:174
void freeMemory()
Free the memory allocated by this planner.
Definition: LazyLBTRRT.cpp:114
A shared pointer wrapper for ompl::base::StateSampler.
Motion(const base::SpaceInformationPtr &si)
Constructor that allocates memory for the state.
Definition: LazyLBTRRT.h:148
void setGoalBias(double goalBias)
Set the goal bias.
Definition: LazyLBTRRT.h:81
Abstract definition of goals.
Definition: Goal.h:62
double getGoalBias() const
Get the goal bias the planner is using.
Definition: LazyLBTRRT.h:87
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition: LazyLBTRRT.h:318
double getRange() const
Get the range the planner is using.
Definition: LazyLBTRRT.h:103
Representation of a motion.
Definition: LazyLBTRRT.h:140
void setRange(double distance)
Set the range the planner is supposed to use.
Definition: LazyLBTRRT.h:97
Abstract definition of a goal region that can be sampled.
Main namespace. Contains everything in this library.
Definition: AppBase.h:21
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition: RandomNumbers.h:58
Base class for a planner.
Definition: Planner.h:232
Rapidly-exploring Random Trees.
Definition: LazyLBTRRT.h:58
std::size_t id_
The id of the motion.
Definition: LazyLBTRRT.h:155
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
A shared pointer wrapper for ompl::base::SpaceInformation.
Definition of an abstract state.
Definition: State.h:49
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition: Console.h:66
double epsilon_
approximation factor
Definition: LazyLBTRRT.h:315
LazyLBTRRT(const base::SpaceInformationPtr &si)
Constructor.
Definition: LazyLBTRRT.cpp:51
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)...
Definition: LazyLBTRRT.h:306
void setApproximationFactor(double epsilon)
Set the apprimation factor.
Definition: LazyLBTRRT.h:122
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
Definition: LazyLBTRRT.h:110
void sampleBiased(const base::GoalSampleableRegion *goal_s, base::State *rstate)
sample with goal biasing
Definition: LazyLBTRRT.cpp:352
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: LazyLBTRRT.cpp:326
double bestCost_
Best cost found so far by algorithm.
Definition: LazyLBTRRT.h:333
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition: LazyLBTRRT.h:302
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: LazyLBTRRT.cpp:100
SpaceInformationPtr si_
The space information for which planning is done.
Definition: Planner.h:415
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition: LazyLBTRRT.h:309
RNG rng_
The random number generator.
Definition: LazyLBTRRT.h:312
double getApproximationFactor() const
Get the apprimation factor.
Definition: LazyLBTRRT.h:293
double distanceFunction(const base::State *a, const base::State *b) const
Compute distance between motions (actually distance between contained states)
Definition: LazyLBTRRT.h:221
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: LazyLBTRRT.cpp:85
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: LazyLBTRRT.cpp:130