LBTRRT.cpp
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 #include "ompl/geometric/planners/rrt/LBTRRT.h"
38 #include "ompl/base/goals/GoalSampleableRegion.h"
39 #include "ompl/tools/config/SelfConfig.h"
40 #include <limits>
41 #include <cmath>
42 #include <boost/math/constants/constants.hpp>
43 
45  : base::Planner(si, "LBTRRT")
46  , goalBias_(0.05)
47  , maxDistance_(0.0)
48  , epsilon_(0.4)
49  , lastGoalMotion_(nullptr)
50  , iterations_(0)
51 {
53  specs_.directed = true;
54 
55  Planner::declareParam<double>("range", this, &LBTRRT::setRange, &LBTRRT::getRange, "0.:1.:10000.");
56  Planner::declareParam<double>("goal_bias", this, &LBTRRT::setGoalBias, &LBTRRT::getGoalBias, "0.:.05:1.");
57  Planner::declareParam<double>("epsilon", this, &LBTRRT::setApproximationFactor, &LBTRRT::getApproximationFactor,
58  "0.:.1:10.");
59 
60  addPlannerProgressProperty("iterations INTEGER", [this]
61  {
62  return getIterationCount();
63  });
64  addPlannerProgressProperty("best cost REAL", [this]
65  {
66  return getBestCost();
67  });
68 }
69 
70 ompl::geometric::LBTRRT::~LBTRRT()
71 {
72  freeMemory();
73 }
74 
76 {
77  Planner::clear();
78  sampler_.reset();
79  freeMemory();
80  if (nn_)
81  nn_->clear();
82  lastGoalMotion_ = nullptr;
83 
84  iterations_ = 0;
85  bestCost_ = std::numeric_limits<double>::infinity();
86 }
87 
89 {
90  Planner::setup();
93 
94  if (!nn_)
95  nn_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion *>(this));
96  nn_->setDistanceFunction([this](const Motion *a, const Motion *b)
97  {
98  return distanceFunction(a, b);
99  });
100 }
101 
103 {
104  if (idToMotionMap_.size() > 0)
105  {
106  for (auto &i : idToMotionMap_)
107  {
108  if (i->state_)
109  si_->freeState(i->state_);
110  delete i;
111  }
112  }
113 }
114 
116 {
117  checkValidity();
118  // update goal and check validity
119  base::Goal *goal = pdef_->getGoal().get();
120  base::GoalSampleableRegion *goal_s = dynamic_cast<base::GoalSampleableRegion *>(goal);
121 
122  if (!goal)
123  {
124  OMPL_ERROR("%s: Goal undefined", getName().c_str());
126  }
127 
128  // update start and check validity
129  while (const base::State *st = pis_.nextStart())
130  {
131  auto *motion = new Motion(si_);
132  si_->copyState(motion->state_, st);
133  motion->id_ = nn_->size();
134  idToMotionMap_.push_back(motion);
135  nn_->add(motion);
136  lowerBoundGraph_.addVertex(motion->id_);
137  }
138 
139  if (nn_->size() == 0)
140  {
141  OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
143  }
144 
145  if (nn_->size() > 1)
146  {
147  OMPL_ERROR("%s: There are multiple start states - currently not supported!", getName().c_str());
149  }
150 
151  if (!sampler_)
152  sampler_ = si_->allocStateSampler();
153 
154  OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), nn_->size());
155 
156  Motion *solution = lastGoalMotion_;
157  Motion *approxSol = nullptr;
158  double approxdif = std::numeric_limits<double>::infinity();
159  // e*(1+1/d) K-nearest constant, as used in RRT*
160  double k_rrg =
161  boost::math::constants::e<double>() + boost::math::constants::e<double>() / (double)si_->getStateDimension();
162 
163  auto *rmotion = new Motion(si_);
164  base::State *rstate = rmotion->state_;
165  base::State *xstate = si_->allocState();
166  unsigned int statesGenerated = 0;
167 
168  bestCost_ = lastGoalMotion_ ? lastGoalMotion_->costApx_ : std::numeric_limits<double>::infinity();
169  while (ptc() == false)
170  {
171  iterations_++;
172  /* sample random state (with goal biasing) */
173  if (goal_s && rng_.uniform01() < goalBias_ && goal_s->canSample())
174  goal_s->sampleGoal(rstate);
175  else
176  sampler_->sampleUniform(rstate);
177 
178  /* find closest state in the tree */
179  Motion *nmotion = nn_->nearest(rmotion);
180  base::State *dstate = rstate;
181 
182  /* find state to add */
183  double d = si_->distance(nmotion->state_, rstate);
184  if (d == 0) // this takes care of the case that the goal is a single point and we re-sample it multiple times
185  continue;
186  if (d > maxDistance_)
187  {
188  si_->getStateSpace()->interpolate(nmotion->state_, rstate, maxDistance_ / d, xstate);
189  dstate = xstate;
190  }
191 
192  if (checkMotion(nmotion->state_, dstate))
193  {
194  statesGenerated++;
195  /* create a motion */
196  auto *motion = new Motion(si_);
197  si_->copyState(motion->state_, dstate);
198 
199  /* update fields */
200  double distN = distanceFunction(nmotion, motion);
201 
202  motion->id_ = nn_->size();
203  idToMotionMap_.push_back(motion);
204  lowerBoundGraph_.addVertex(motion->id_);
205  motion->parentApx_ = nmotion;
206 
207  std::list<std::size_t> dummy;
208  lowerBoundGraph_.addEdge(nmotion->id_, motion->id_, distN, false, dummy);
209 
210  motion->costLb_ = nmotion->costLb_ + distN;
211  motion->costApx_ = nmotion->costApx_ + distN;
212  nmotion->childrenApx_.push_back(motion);
213 
214  std::vector<Motion *> nnVec;
215  unsigned int k = std::ceil(k_rrg * log((double)(nn_->size() + 1)));
216  nn_->nearestK(motion, k, nnVec);
217  nn_->add(motion); // if we add the motion before the nearestK call, we will get ourselves...
218 
219  IsLessThan isLessThan(this, motion);
220  std::sort(nnVec.begin(), nnVec.end(), isLessThan);
221 
222  //-------------------------------------------------//
223  // Rewiring Part (i) - find best parent of motion //
224  //-------------------------------------------------//
225  if (motion->parentApx_ != nnVec.front())
226  {
227  for (auto potentialParent : nnVec)
228  {
229  double dist = distanceFunction(potentialParent, motion);
230  considerEdge(potentialParent, motion, dist);
231  }
232  }
233 
234  //------------------------------------------------------------------//
235  // Rewiring Part (ii) //
236  // check if motion may be a better parent to one of its neighbors //
237  //------------------------------------------------------------------//
238  for (auto child : nnVec)
239  {
240  double dist = distanceFunction(motion, child);
241  considerEdge(motion, child, dist);
242  }
243 
244  double dist = 0.0;
245  bool sat = goal->isSatisfied(motion->state_, &dist);
246 
247  if (sat)
248  {
249  approxdif = dist;
250  solution = motion;
251  }
252  if (dist < approxdif)
253  {
254  approxdif = dist;
255  approxSol = motion;
256  }
257 
258  if (solution != nullptr && bestCost_ != solution->costApx_)
259  {
260  OMPL_INFORM("%s: approximation cost = %g", getName().c_str(), solution->costApx_);
261  bestCost_ = solution->costApx_;
262  }
263  }
264  }
265 
266  bool solved = false;
267  bool approximate = false;
268 
269  if (solution == nullptr)
270  {
271  solution = approxSol;
272  approximate = true;
273  }
274 
275  if (solution != nullptr)
276  {
277  lastGoalMotion_ = solution;
278 
279  /* construct the solution path */
280  std::vector<Motion *> mpath;
281  while (solution != nullptr)
282  {
283  mpath.push_back(solution);
284  solution = solution->parentApx_;
285  }
286 
287  /* set the solution path */
288  auto path(std::make_shared<PathGeometric>(si_));
289  for (int i = mpath.size() - 1; i >= 0; --i)
290  path->append(mpath[i]->state_);
291  // Add the solution path.
292  base::PlannerSolution psol(path);
293  psol.setPlannerName(getName());
294  if (approximate)
295  psol.setApproximate(approxdif);
296  pdef_->addSolutionPath(psol);
297  solved = true;
298  }
299 
300  si_->freeState(xstate);
301  if (rmotion->state_)
302  si_->freeState(rmotion->state_);
303  delete rmotion;
304 
305  OMPL_INFORM("%s: Created %u states", getName().c_str(), statesGenerated);
306 
307  return base::PlannerStatus(solved, approximate);
308 }
309 
310 void ompl::geometric::LBTRRT::considerEdge(Motion *parent, Motion *child, double c)
311 {
312  // optimization - check if the bounded approximation invariant
313  // will be violated after the edge insertion (at least for the child node)
314  // if this is the case - perform the local planning
315  // this prevents the update of the graph due to the edge insertion and then the re-update as it is removed
316  double potential_cost = parent->costLb_ + c;
317  if (child->costApx_ > (1 + epsilon_) * potential_cost)
318  if (!checkMotion(parent, child))
319  return;
320 
321  // update lowerBoundGraph_
322  std::list<std::size_t> affected;
323 
324  lowerBoundGraph_.addEdge(parent->id_, child->id_, c, true, affected);
325 
326  // now, check if the bounded apprimation invariant has been violated for each affected vertex
327  // insert them into a priority queue ordered according to the lb cost
328  std::list<std::size_t>::iterator iter;
329  IsLessThanLB isLessThanLB(this);
330  Lb_queue queue(isLessThanLB);
331 
332  for (iter = affected.begin(); iter != affected.end(); ++iter)
333  {
334  Motion *m = getMotion(*iter);
335  m->costLb_ = lowerBoundGraph_.getShortestPathCost(*iter);
336  if (m->costApx_ > (1 + epsilon_) * m->costLb_)
337  queue.insert(m);
338  }
339 
340  while (queue.empty() == false)
341  {
342  Motion *motion = *(queue.begin());
343  queue.erase(queue.begin());
344 
345  if (motion->costApx_ > (1 + epsilon_) * motion->costLb_)
346  {
347  Motion *potential_parent = getMotion(lowerBoundGraph_.getShortestPathParent(motion->id_));
348  if (checkMotion(potential_parent, motion))
349  {
350  double delta = lazilyUpdateApxParent(motion, potential_parent);
351  updateChildCostsApx(motion, delta);
352  }
353  else
354  {
355  affected.clear();
356 
357  lowerBoundGraph_.removeEdge(potential_parent->id_, motion->id_, true, affected);
358 
359  for (iter = affected.begin(); iter != affected.end(); ++iter)
360  {
361  Motion *affected = getMotion(*iter);
362  auto lb_queue_iter = queue.find(affected);
363  if (lb_queue_iter != queue.end())
364  {
365  queue.erase(lb_queue_iter);
366  affected->costLb_ = lowerBoundGraph_.getShortestPathCost(affected->id_);
367  if (affected->costApx_ > (1 + epsilon_) * affected->costLb_)
368  queue.insert(affected);
369  }
370  else
371  {
372  affected->costLb_ = lowerBoundGraph_.getShortestPathCost(affected->id_);
373  }
374  }
375 
376  motion->costLb_ = lowerBoundGraph_.getShortestPathCost(motion->id_);
377  if (motion->costApx_ > (1 + epsilon_) * motion->costLb_)
378  queue.insert(motion);
379 
380  // optimization - we can remove the opposite edge
381  lowerBoundGraph_.removeEdge(motion->id_, potential_parent->id_, false, affected);
382  }
383  }
384  }
385 
386  return;
387 }
388 
390 {
391  Planner::getPlannerData(data);
392 
393  std::vector<Motion *> motions;
394  if (nn_)
395  nn_->list(motions);
396 
397  if (lastGoalMotion_)
399 
400  for (auto &motion : motions)
401  {
402  if (motion->parentApx_ == nullptr)
403  data.addStartVertex(base::PlannerDataVertex(motion->state_));
404  else
405  data.addEdge(base::PlannerDataVertex(motion->parentApx_->state_), base::PlannerDataVertex(motion->state_));
406  }
407 }
408 
410 {
411  for (auto child : m->childrenApx_)
412  {
413  child->costApx_ += delta;
414  updateChildCostsApx(child, delta);
415  }
416 }
417 
419 {
420  double dist = distanceFunction(parent, child);
421  removeFromParentApx(child);
422  double deltaApx = parent->costApx_ + dist - child->costApx_;
423  child->parentApx_ = parent;
424  parent->childrenApx_.push_back(child);
425  child->costApx_ = parent->costApx_ + dist;
426 
427  return deltaApx;
428 }
429 
431 {
432  std::vector<Motion *> &vec = m->parentApx_->childrenApx_;
433  for (auto it = vec.begin(); it != vec.end(); ++it)
434  if (*it == m)
435  {
436  vec.erase(it);
437  break;
438  }
439 }
void updateChildCostsApx(Motion *m, double delta)
update the child cost of the approximation tree
Definition: LBTRRT.cpp:409
bool approximateSolutions
Flag indicating whether the planner is able to compute approximate solutions.
Definition: Planner.h:212
void addPlannerProgressProperty(const std::string &progressPropertyName, const PlannerProgressProperty &prop)
Add a planner progress property called progressPropertyName with a property querying function prop to...
Definition: Planner.h:408
double costApx_
The approximation cost.
Definition: LBTRRT.h:190
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:389
comparator - metric is the lower bound cost
Definition: LBTRRT.h:217
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
void setApproximate(double difference)
Specify that the solution is approximate and set the difference to the goal.
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:115
void log(const char *file, int line, LogLevel level, const char *m,...)
Root level logging function. This should not be invoked directly, but rather used via a logging macro...
Definition: Console.cpp:120
void freeMemory()
Free the memory allocated by this planner.
Definition: LBTRRT.cpp:102
LBTRRT(const base::SpaceInformationPtr &si)
Constructor.
Definition: LBTRRT.cpp:44
Representation of a solution to a planning problem.
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: LBTRRT.h:249
base::State * state_
The state contained by the motion.
Definition: LBTRRT.h:178
unsigned int addGoalVertex(const PlannerDataVertex &v)
Adds the given vertex to the graph data, and marks it as a start vertex. The vertex index is returned...
Abstract definition of goals.
Definition: Goal.h:62
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:288
ProblemDefinitionPtr pdef_
The user set problem definition.
Definition: Planner.h:418
bool directed
Flag indicating whether the planner is able to account for the fact that the validity of a motion fro...
Definition: Planner.h:222
virtual void sampleGoal(State *st) const =0
Sample a state in the goal region.
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: LBTRRT.cpp:88
void removeFromParentApx(Motion *m)
remove motion from its parent in the approximation tree
Definition: LBTRRT.cpp:430
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:285
double uniform01()
Generate a random real between 0 and 1.
Definition: RandomNumbers.h:68
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition: PlannerData.h:58
Invalid start state or no start state specified.
Definition: PlannerStatus.h:56
Abstract definition of a goal region that can be sampled.
RNG rng_
The random number generator.
Definition: LBTRRT.h:294
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition: LBTRRT.h:297
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition: Console.h:64
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition: LBTRRT.h:275
bool canSample() const
Return true if maxSampleCount() > 0, since in this case samples can certainly be produced.
double getRange() const
Get the range the planner is using.
Definition: LBTRRT.h:116
DynamicSSSP lowerBoundGraph_
A graph of motions Glb.
Definition: LBTRRT.h:278
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
virtual bool addEdge(unsigned int v1, unsigned int v2, const PlannerDataEdge &edge=PlannerDataEdge(), Cost weight=Cost(1.0))
Adds a directed edge between the given vertex indexes. An optional edge structure and weight can be s...
A shared pointer wrapper for ompl::base::SpaceInformation.
double epsilon_
approximation factor
Definition: LBTRRT.h:291
bool checkMotion(const Motion *a, const Motion *b)
local planner
Definition: LBTRRT.h:255
std::vector< Motion * > idToMotionMap_
mapping between a motion id and the motion
Definition: LBTRRT.h:281
unsigned int addStartVertex(const PlannerDataVertex &v)
Adds the given vertex to the graph data, and marks it as a start vertex. The vertex index is returned...
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
virtual void checkValidity()
Check to see if the planner is in a working state (setup has been called, a goal was set...
Definition: Planner.cpp:101
virtual bool isSatisfied(const State *st) const =0
Return true if the state satisfies the goal constraints.
PlannerInputStates pis_
Utility class to extract valid input states.
Definition: Planner.h:421
void considerEdge(Motion *parent, Motion *child, double c)
consider an edge for addition to the roadmap
Definition: LBTRRT.cpp:310
Motion * parentApx_
The parent motion in the approximation tree.
Definition: LBTRRT.h:188
PlannerSpecs specs_
The specifications of the planner (its capabilities)
Definition: Planner.h:427
const State * nextStart()
Return the next valid start state or nullptr if no more valid start states are available.
Definition: Planner.cpp:230
Motion * getMotion(std::size_t i)
get motion from id
Definition: LBTRRT.h:266
double lazilyUpdateApxParent(Motion *child, Motion *parent)
lazily update the parent in the approximation tree without updating costs to cildren ...
Definition: LBTRRT.cpp:418
const std::string & getName() const
Get the name of the planner.
Definition: Planner.cpp:56
comparator - metric is the cost to reach state via a specific state
Definition: LBTRRT.h:196
void configurePlannerRange(double &range)
Compute what a good length for motion segments is.
Definition: SelfConfig.cpp:225
This class contains methods that automatically configure various parameters for motion planning...
Definition: SelfConfig.h:59
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: LBTRRT.cpp:75
double bestCost_
Best cost found so far by algorithm.
Definition: LBTRRT.h:304
double costLb_
The lower bound cost of the motion while it is stored in the lowerBoundGraph_ and this may seem redun...
Definition: LBTRRT.h:186
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:415
std::size_t id_
unique id of the motion
Definition: LBTRRT.h:180
std::vector< Motion * > childrenApx_
The children in the approximation tree.
Definition: LBTRRT.h:192
void setPlannerName(const std::string &name)
Set the name of the planner used to compute this solution.
unsigned int iterations_
Number of iterations the algorithm performed.
Definition: LBTRRT.h:302
base::StateSamplerPtr sampler_
State sampler.
Definition: LBTRRT.h:272
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68