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 {
48  specs_.directed = true;
49 
50  Planner::declareParam<double>("range", this, &LBTRRT::setRange, &LBTRRT::getRange, "0.:1.:10000.");
51  Planner::declareParam<double>("goal_bias", this, &LBTRRT::setGoalBias, &LBTRRT::getGoalBias, "0.:.05:1.");
52  Planner::declareParam<double>("epsilon", this, &LBTRRT::setApproximationFactor, &LBTRRT::getApproximationFactor,
53  "0.:.1:10.");
54 
55  addPlannerProgressProperty("iterations INTEGER", [this]
56  {
57  return getIterationCount();
58  });
59  addPlannerProgressProperty("best cost REAL", [this]
60  {
61  return getBestCost();
62  });
63 }
64 
65 ompl::geometric::LBTRRT::~LBTRRT()
66 {
67  freeMemory();
68 }
69 
71 {
72  Planner::clear();
73  sampler_.reset();
74  freeMemory();
75  if (nn_)
76  nn_->clear();
77  lastGoalMotion_ = nullptr;
78 
79  iterations_ = 0;
80  bestCost_ = std::numeric_limits<double>::infinity();
81 }
82 
84 {
85  Planner::setup();
88 
89  if (!nn_)
90  nn_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion *>(this));
91  nn_->setDistanceFunction([this](const Motion *a, const Motion *b)
92  {
93  return distanceFunction(a, b);
94  });
95 }
96 
98 {
99  if (!idToMotionMap_.empty())
100  {
101  for (auto &i : idToMotionMap_)
102  {
103  if (i->state_ != nullptr)
104  si_->freeState(i->state_);
105  delete i;
106  }
107  }
108 }
109 
111 {
112  checkValidity();
113  // update goal and check validity
114  base::Goal *goal = pdef_->getGoal().get();
115  auto *goal_s = dynamic_cast<base::GoalSampleableRegion *>(goal);
116 
117  if (goal == nullptr)
118  {
119  OMPL_ERROR("%s: Goal undefined", getName().c_str());
121  }
122 
123  // update start and check validity
124  while (const base::State *st = pis_.nextStart())
125  {
126  auto *motion = new Motion(si_);
127  si_->copyState(motion->state_, st);
128  motion->id_ = nn_->size();
129  idToMotionMap_.push_back(motion);
130  nn_->add(motion);
131  lowerBoundGraph_.addVertex(motion->id_);
132  }
133 
134  if (nn_->size() == 0)
135  {
136  OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
138  }
139 
140  if (nn_->size() > 1)
141  {
142  OMPL_ERROR("%s: There are multiple start states - currently not supported!", getName().c_str());
144  }
145 
146  if (!sampler_)
147  sampler_ = si_->allocStateSampler();
148 
149  OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), nn_->size());
150 
151  Motion *solution = lastGoalMotion_;
152  Motion *approxSol = nullptr;
153  double approxdif = std::numeric_limits<double>::infinity();
154  // e*(1+1/d) K-nearest constant, as used in RRT*
155  double k_rrg =
156  boost::math::constants::e<double>() + boost::math::constants::e<double>() / (double)si_->getStateDimension();
157 
158  auto *rmotion = new Motion(si_);
159  base::State *rstate = rmotion->state_;
160  base::State *xstate = si_->allocState();
161  unsigned int statesGenerated = 0;
162 
163  bestCost_ = lastGoalMotion_ != nullptr ? lastGoalMotion_->costApx_ : std::numeric_limits<double>::infinity();
164  while (!ptc())
165  {
166  iterations_++;
167  /* sample random state (with goal biasing) */
168  if ((goal_s != nullptr) && rng_.uniform01() < goalBias_ && goal_s->canSample())
169  goal_s->sampleGoal(rstate);
170  else
171  sampler_->sampleUniform(rstate);
172 
173  /* find closest state in the tree */
174  Motion *nmotion = nn_->nearest(rmotion);
175  base::State *dstate = rstate;
176 
177  /* find state to add */
178  double d = si_->distance(nmotion->state_, rstate);
179  if (d == 0) // this takes care of the case that the goal is a single point and we re-sample it multiple times
180  continue;
181  if (d > maxDistance_)
182  {
183  si_->getStateSpace()->interpolate(nmotion->state_, rstate, maxDistance_ / d, xstate);
184  dstate = xstate;
185  }
186 
187  if (checkMotion(nmotion->state_, dstate))
188  {
189  statesGenerated++;
190  /* create a motion */
191  auto *motion = new Motion(si_);
192  si_->copyState(motion->state_, dstate);
193 
194  /* update fields */
195  double distN = distanceFunction(nmotion, motion);
196 
197  motion->id_ = nn_->size();
198  idToMotionMap_.push_back(motion);
199  lowerBoundGraph_.addVertex(motion->id_);
200  motion->parentApx_ = nmotion;
201 
202  std::list<std::size_t> dummy;
203  lowerBoundGraph_.addEdge(nmotion->id_, motion->id_, distN, false, dummy);
204 
205  motion->costLb_ = nmotion->costLb_ + distN;
206  motion->costApx_ = nmotion->costApx_ + distN;
207  nmotion->childrenApx_.push_back(motion);
208 
209  std::vector<Motion *> nnVec;
210  unsigned int k = std::ceil(k_rrg * log((double)(nn_->size() + 1)));
211  nn_->nearestK(motion, k, nnVec);
212  nn_->add(motion); // if we add the motion before the nearestK call, we will get ourselves...
213 
214  IsLessThan isLessThan(this, motion);
215  std::sort(nnVec.begin(), nnVec.end(), isLessThan);
216 
217  //-------------------------------------------------//
218  // Rewiring Part (i) - find best parent of motion //
219  //-------------------------------------------------//
220  if (motion->parentApx_ != nnVec.front())
221  {
222  for (auto potentialParent : nnVec)
223  {
224  double dist = distanceFunction(potentialParent, motion);
225  considerEdge(potentialParent, motion, dist);
226  }
227  }
228 
229  //------------------------------------------------------------------//
230  // Rewiring Part (ii) //
231  // check if motion may be a better parent to one of its neighbors //
232  //------------------------------------------------------------------//
233  for (auto child : nnVec)
234  {
235  double dist = distanceFunction(motion, child);
236  considerEdge(motion, child, dist);
237  }
238 
239  double dist = 0.0;
240  bool sat = goal->isSatisfied(motion->state_, &dist);
241 
242  if (sat)
243  {
244  approxdif = dist;
245  solution = motion;
246  }
247  if (dist < approxdif)
248  {
249  approxdif = dist;
250  approxSol = motion;
251  }
252 
253  if (solution != nullptr && bestCost_ != solution->costApx_)
254  {
255  OMPL_INFORM("%s: approximation cost = %g", getName().c_str(), solution->costApx_);
256  bestCost_ = solution->costApx_;
257  }
258  }
259  }
260 
261  bool solved = false;
262  bool approximate = false;
263 
264  if (solution == nullptr)
265  {
266  solution = approxSol;
267  approximate = true;
268  }
269 
270  if (solution != nullptr)
271  {
272  lastGoalMotion_ = solution;
273 
274  /* construct the solution path */
275  std::vector<Motion *> mpath;
276  while (solution != nullptr)
277  {
278  mpath.push_back(solution);
279  solution = solution->parentApx_;
280  }
281 
282  /* set the solution path */
283  auto path(std::make_shared<PathGeometric>(si_));
284  for (int i = mpath.size() - 1; i >= 0; --i)
285  path->append(mpath[i]->state_);
286  // Add the solution path.
287  base::PlannerSolution psol(path);
288  psol.setPlannerName(getName());
289  if (approximate)
290  psol.setApproximate(approxdif);
291  pdef_->addSolutionPath(psol);
292  solved = true;
293  }
294 
295  si_->freeState(xstate);
296  if (rmotion->state_ != nullptr)
297  si_->freeState(rmotion->state_);
298  delete rmotion;
299 
300  OMPL_INFORM("%s: Created %u states", getName().c_str(), statesGenerated);
301 
302  return base::PlannerStatus(solved, approximate);
303 }
304 
305 void ompl::geometric::LBTRRT::considerEdge(Motion *parent, Motion *child, double c)
306 {
307  // optimization - check if the bounded approximation invariant
308  // will be violated after the edge insertion (at least for the child node)
309  // if this is the case - perform the local planning
310  // this prevents the update of the graph due to the edge insertion and then the re-update as it is removed
311  double potential_cost = parent->costLb_ + c;
312  if (child->costApx_ > (1 + epsilon_) * potential_cost)
313  if (!checkMotion(parent, child))
314  return;
315 
316  // update lowerBoundGraph_
317  std::list<std::size_t> affected;
318 
319  lowerBoundGraph_.addEdge(parent->id_, child->id_, c, true, affected);
320 
321  // now, check if the bounded apprimation invariant has been violated for each affected vertex
322  // insert them into a priority queue ordered according to the lb cost
323  std::list<std::size_t>::iterator iter;
324  IsLessThanLB isLessThanLB(this);
325  Lb_queue queue(isLessThanLB);
326 
327  for (iter = affected.begin(); iter != affected.end(); ++iter)
328  {
329  Motion *m = getMotion(*iter);
330  m->costLb_ = lowerBoundGraph_.getShortestPathCost(*iter);
331  if (m->costApx_ > (1 + epsilon_) * m->costLb_)
332  queue.insert(m);
333  }
334 
335  while (!queue.empty())
336  {
337  Motion *motion = *(queue.begin());
338  queue.erase(queue.begin());
339 
340  if (motion->costApx_ > (1 + epsilon_) * motion->costLb_)
341  {
342  Motion *potential_parent = getMotion(lowerBoundGraph_.getShortestPathParent(motion->id_));
343  if (checkMotion(potential_parent, motion))
344  {
345  double delta = lazilyUpdateApxParent(motion, potential_parent);
346  updateChildCostsApx(motion, delta);
347  }
348  else
349  {
350  affected.clear();
351 
352  lowerBoundGraph_.removeEdge(potential_parent->id_, motion->id_, true, affected);
353 
354  for (iter = affected.begin(); iter != affected.end(); ++iter)
355  {
356  Motion *affected = getMotion(*iter);
357  auto lb_queue_iter = queue.find(affected);
358  if (lb_queue_iter != queue.end())
359  {
360  queue.erase(lb_queue_iter);
361  affected->costLb_ = lowerBoundGraph_.getShortestPathCost(affected->id_);
362  if (affected->costApx_ > (1 + epsilon_) * affected->costLb_)
363  queue.insert(affected);
364  }
365  else
366  {
367  affected->costLb_ = lowerBoundGraph_.getShortestPathCost(affected->id_);
368  }
369  }
370 
371  motion->costLb_ = lowerBoundGraph_.getShortestPathCost(motion->id_);
372  if (motion->costApx_ > (1 + epsilon_) * motion->costLb_)
373  queue.insert(motion);
374 
375  // optimization - we can remove the opposite edge
376  lowerBoundGraph_.removeEdge(motion->id_, potential_parent->id_, false, affected);
377  }
378  }
379  }
380 
381  }
382 
384 {
385  Planner::getPlannerData(data);
386 
387  std::vector<Motion *> motions;
388  if (nn_)
389  nn_->list(motions);
390 
391  if (lastGoalMotion_ != nullptr)
393 
394  for (auto &motion : motions)
395  {
396  if (motion->parentApx_ == nullptr)
397  data.addStartVertex(base::PlannerDataVertex(motion->state_));
398  else
399  data.addEdge(base::PlannerDataVertex(motion->parentApx_->state_), base::PlannerDataVertex(motion->state_));
400  }
401 }
402 
404 {
405  for (auto child : m->childrenApx_)
406  {
407  child->costApx_ += delta;
408  updateChildCostsApx(child, delta);
409  }
410 }
411 
413 {
414  double dist = distanceFunction(parent, child);
415  removeFromParentApx(child);
416  double deltaApx = parent->costApx_ + dist - child->costApx_;
417  child->parentApx_ = parent;
418  parent->childrenApx_.push_back(child);
419  child->costApx_ = parent->costApx_ + dist;
420 
421  return deltaApx;
422 }
423 
425 {
426  std::vector<Motion *> &vec = m->parentApx_->childrenApx_;
427  for (auto it = vec.begin(); it != vec.end(); ++it)
428  if (*it == m)
429  {
430  vec.erase(it);
431  break;
432  }
433 }
void updateChildCostsApx(Motion *m, double delta)
update the child cost of the approximation tree
Definition: LBTRRT.cpp:403
bool approximateSolutions
Flag indicating whether the planner is able to compute approximate solutions.
Definition: Planner.h:203
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:399
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
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:110
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:97
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:247
base::State * state_
The state contained by the motion.
Definition: LBTRRT.h:176
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:286
ProblemDefinitionPtr pdef_
The user set problem definition.
Definition: Planner.h:409
bool directed
Flag indicating whether the planner is able to account for the fact that the validity of a motion fro...
Definition: Planner.h:213
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
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:292
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition: LBTRRT.h:295
#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:273
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
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: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
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:412
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
PlannerSpecs specs_
The specifications of the planner (its capabilities)
Definition: Planner.h:418
const State * nextStart()
Return the next valid start state or nullptr if no more valid start states are available.
Definition: Planner.cpp:227
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
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:194
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: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
std::vector< Motion * > childrenApx_
The children in the approximation tree.
Definition: LBTRRT.h:190
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:300
base::StateSamplerPtr sampler_
State sampler.
Definition: LBTRRT.h:270
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68