BFMT.cpp
1 
2 #include <boost/math/constants/constants.hpp>
3 #include <boost/math/distributions/binomial.hpp>
4 #include <ompl/datastructures/BinaryHeap.h>
5 #include <ompl/tools/config/SelfConfig.h>
6 
7 #include <ompl/datastructures/NearestNeighborsGNAT.h>
8 #include <ompl/base/objectives/PathLengthOptimizationObjective.h>
9 #include <ompl/geometric/planners/fmt/BFMT.h>
10 
11 #include <fstream>
12 #include <ompl/base/spaces/RealVectorStateSpace.h>
13 
14 namespace ompl
15 {
16  namespace geometric
17  {
18  BFMT::BFMT(const base::SpaceInformationPtr &si)
19  : base::Planner(si, "BFMT")
20  , freeSpaceVolume_(si_->getStateSpace()->getMeasure()) // An upper bound on the free space volume is the
21  // total space volume; the free fraction is estimated
22  // in sampleFree
23  {
25  specs_.directed = false;
26 
27  ompl::base::Planner::declareParam<unsigned int>("num_samples", this, &BFMT::setNumSamples,
28  &BFMT::getNumSamples, "10:10:1000000");
29  ompl::base::Planner::declareParam<double>("radius_multiplier", this, &BFMT::setRadiusMultiplier,
30  &BFMT::getRadiusMultiplier, "0.1:0.05:50.");
31  ompl::base::Planner::declareParam<bool>("nearest_k", this, &BFMT::setNearestK, &BFMT::getNearestK, "0,1");
32  ompl::base::Planner::declareParam<bool>("balanced", this, &BFMT::setExploration, &BFMT::getExploration,
33  "0,1");
34  ompl::base::Planner::declareParam<bool>("optimality", this, &BFMT::setTermination, &BFMT::getTermination,
35  "0,1");
36  ompl::base::Planner::declareParam<bool>("heuristics", this, &BFMT::setHeuristics, &BFMT::getHeuristics,
37  "0,1");
38  ompl::base::Planner::declareParam<bool>("cache_cc", this, &BFMT::setCacheCC, &BFMT::getCacheCC, "0,1");
39  ompl::base::Planner::declareParam<bool>("extended_fmt", this, &BFMT::setExtendedFMT, &BFMT::getExtendedFMT,
40  "0,1");
41  }
42 
43  ompl::geometric::BFMT::~BFMT()
44  {
45  freeMemory();
46  }
47 
48  void BFMT::setup()
49  {
50  if (pdef_)
51  {
52  /* Setup the optimization objective. If no optimization objective was
53  specified, then default to optimizing path length as computed by the
54  distance() function in the state space */
55  if (pdef_->hasOptimizationObjective())
56  opt_ = pdef_->getOptimizationObjective();
57  else
58  {
59  OMPL_INFORM("%s: No optimization objective specified. Defaulting to optimizing path length.",
60  getName().c_str());
61  opt_ = std::make_shared<base::PathLengthOptimizationObjective>(si_);
62  // Store the new objective in the problem def'n
63  pdef_->setOptimizationObjective(opt_);
64  }
65  Open_[0].getComparisonOperator().opt_ = opt_.get();
66  Open_[0].getComparisonOperator().heuristics_ = heuristics_;
67  Open_[1].getComparisonOperator().opt_ = opt_.get();
68  Open_[1].getComparisonOperator().heuristics_ = heuristics_;
69 
70  if (!nn_)
71  nn_.reset(tools::SelfConfig::getDefaultNearestNeighbors<BiDirMotion *>(this));
72  nn_->setDistanceFunction([this](const BiDirMotion *a, const BiDirMotion *b)
73  {
74  return distanceFunction(a, b);
75  });
76 
77  if (nearestK_ && !nn_->reportsSortedResults())
78  {
79  OMPL_WARN("%s: NearestNeighbors datastructure does not return sorted solutions. Nearest K strategy "
80  "disabled.",
81  getName().c_str());
82  nearestK_ = false;
83  }
84  }
85  else
86  {
87  OMPL_INFORM("%s: problem definition is not set, deferring setup completion...", getName().c_str());
88  setup_ = false;
89  }
90  }
91 
93  {
94  if (nn_)
95  {
96  BiDirMotionPtrs motions;
97  nn_->list(motions);
98  for (auto &motion : motions)
99  {
100  si_->freeState(motion->getState());
101  delete motion;
102  }
103  }
104  }
105 
106  void BFMT::clear()
107  {
108  Planner::clear();
109  sampler_.reset();
110  freeMemory();
111  if (nn_)
112  nn_->clear();
113  Open_[FWD].clear();
114  Open_[REV].clear();
115  Open_elements[FWD].clear();
116  Open_elements[REV].clear();
117  neighborhoods_.clear();
118  collisionChecks_ = 0;
119  }
120 
122  {
124  BiDirMotionPtrs motions;
125  nn_->list(motions);
126 
127  int fwd_tree_tag = 1;
128  int rev_tree_tag = 2;
129 
130  for (auto motion : motions)
131  {
132  bool inFwdTree = (motion->currentSet_[FWD] != BiDirMotion::SET_UNVISITED);
133 
134  // For samples added to the fwd tree, add incoming edges (from fwd tree parent)
135  if (inFwdTree)
136  {
137  if (motion->parent_[FWD] != nullptr)
138  {
139  data.addEdge(base::PlannerDataVertex(motion->parent_[FWD]->getState(), fwd_tree_tag),
140  base::PlannerDataVertex(motion->getState(), fwd_tree_tag));
141  }
142  }
143  }
144 
145  // The edges in the goal tree are reversed so that they are in the same direction as start tree
146  for (auto motion : motions)
147  {
148  bool inRevTree = (motion->currentSet_[REV] != BiDirMotion::SET_UNVISITED);
149 
150  // For samples added to a tree, add incoming edges (from fwd tree parent)
151  if (inRevTree)
152  {
153  if (motion->parent_[REV] != nullptr)
154  {
155  data.addEdge(base::PlannerDataVertex(motion->getState(), rev_tree_tag),
156  base::PlannerDataVertex(motion->parent_[REV]->getState(), rev_tree_tag));
157  }
158  }
159  }
160  }
161 
163  {
164  // Check if neighborhood has already been saved
165  if (neighborhoods_.find(m) == neighborhoods_.end())
166  {
167  BiDirMotionPtrs neighborhood;
168  if (nearestK_)
169  nn_->nearestK(m, NNk_, neighborhood);
170  else
171  nn_->nearestR(m, NNr_, neighborhood);
172 
173  if (!neighborhood.empty())
174  {
175  // Save the neighborhood but skip the first element (m)
176  neighborhoods_[m] = std::vector<BiDirMotion *>(neighborhood.size() - 1, nullptr);
177  std::copy(neighborhood.begin() + 1, neighborhood.end(), neighborhoods_[m].begin());
178  }
179  else
180  {
181  // Save an empty neighborhood
182  neighborhoods_[m] = std::vector<BiDirMotion *>(0);
183  }
184  }
185  }
186 
187  void BFMT::sampleFree(const std::shared_ptr<NearestNeighbors<BiDirMotion *>> &nn,
189  {
190  unsigned int nodeCount = 0;
191  unsigned int sampleAttempts = 0;
192  auto *motion = new BiDirMotion(si_, &tree_);
193 
194  // Sample numSamples_ number of nodes from the free configuration space
195  while (nodeCount < numSamples_ && !ptc)
196  {
197  sampler_->sampleUniform(motion->getState());
198  sampleAttempts++;
199  if (si_->isValid(motion->getState()))
200  { // collision checking
201  ++nodeCount;
202  nn->add(motion);
203  motion = new BiDirMotion(si_, &tree_);
204  }
205  }
206  si_->freeState(motion->getState());
207  delete motion;
208 
209  // 95% confidence limit for an upper bound for the true free space volume
211  boost::math::binomial_distribution<>::find_upper_bound_on_p(sampleAttempts, nodeCount, 0.05) *
212  si_->getStateSpace()->getMeasure();
213  }
214 
215  double BFMT::calculateUnitBallVolume(const unsigned int dimension) const
216  {
217  if (dimension == 0)
218  return 1.0;
219  if (dimension == 1)
220  return 2.0;
221  return 2.0 * boost::math::constants::pi<double>() / dimension * calculateUnitBallVolume(dimension - 2);
222  }
223 
224  double BFMT::calculateRadius(const unsigned int dimension, const unsigned int n) const
225  {
226  double a = 1.0 / (double)dimension;
227  double unitBallVolume = calculateUnitBallVolume(dimension);
228 
229  return radiusMultiplier_ * 2.0 * std::pow(a, a) * std::pow(freeSpaceVolume_ / unitBallVolume, a) *
230  std::pow(log((double)n) / (double)n, a);
231  }
232 
234  {
235  checkValidity();
236  if (!sampler_)
237  {
238  sampler_ = si_->allocStateSampler();
239  }
240  goal_s = dynamic_cast<base::GoalSampleableRegion *>(pdef_->getGoal().get());
241  }
242 
244  {
246  initializeProblem(goal_s);
247  if (goal_s == nullptr)
248  {
249  OMPL_ERROR("%s: Unknown type of goal", getName().c_str());
251  }
252 
253  useFwdTree();
254 
255  // Add start states to Unvisitedfwd and Openfwd
256  bool valid_initMotion = false;
257  BiDirMotion *initMotion;
258  while (const base::State *st = pis_.nextStart())
259  {
260  initMotion = new BiDirMotion(si_, &tree_);
261  si_->copyState(initMotion->getState(), st);
262 
263  initMotion->currentSet_[REV] = BiDirMotion::SET_UNVISITED;
264  nn_->add(initMotion); // S <-- {x_init}
265  if (si_->isValid(initMotion->getState()))
266  {
267  // Take the first valid initial state as the forward tree root
268  Open_elements[FWD][initMotion] = Open_[FWD].insert(initMotion);
269  initMotion->currentSet_[FWD] = BiDirMotion::SET_OPEN;
270  initMotion->cost_[FWD] = opt_->initialCost(initMotion->getState());
271  valid_initMotion = true;
272  heurGoalState_[1] = initMotion->getState();
273  }
274  }
275 
276  if ((initMotion == nullptr) || !valid_initMotion)
277  {
278  OMPL_ERROR("Start state undefined or invalid.");
280  }
281 
282  // Sample N free states in configuration state_
283  sampleFree(nn_, ptc); // S <-- SAMPLEFREE(N)
284  OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(),
285  nn_->size());
286 
287  // Calculate the nearest neighbor search radius
288  if (nearestK_)
289  {
290  NNk_ = std::ceil(std::pow(2.0 * radiusMultiplier_, (double)si_->getStateDimension()) *
291  (boost::math::constants::e<double>() / (double)si_->getStateDimension()) *
292  log((double)nn_->size()));
293  OMPL_DEBUG("Using nearest-neighbors k of %d", NNk_);
294  }
295  else
296  {
297  NNr_ = calculateRadius(si_->getStateDimension(), nn_->size());
298  OMPL_DEBUG("Using radius of %f", NNr_);
299  }
300 
301  // Add goal states to Unvisitedrev and Openrev
302  bool valid_goalMotion = false;
303  BiDirMotion *goalMotion;
304  while (const base::State *st = pis_.nextGoal())
305  {
306  goalMotion = new BiDirMotion(si_, &tree_);
307  si_->copyState(goalMotion->getState(), st);
308 
309  goalMotion->currentSet_[FWD] = BiDirMotion::SET_UNVISITED;
310  nn_->add(goalMotion); // S <-- {x_goal}
311  if (si_->isValid(goalMotion->getState()))
312  {
313  // Take the first valid goal state as the reverse tree root
314  Open_elements[REV][goalMotion] = Open_[REV].insert(goalMotion);
315  goalMotion->currentSet_[REV] = BiDirMotion::SET_OPEN;
316  goalMotion->cost_[REV] = opt_->terminalCost(goalMotion->getState());
317  valid_goalMotion = true;
318  heurGoalState_[0] = goalMotion->getState();
319  }
320  }
321 
322  if ((goalMotion == nullptr) || !valid_goalMotion)
323  {
324  OMPL_ERROR("Goal state undefined or invalid.");
326  }
327 
328  useRevTree();
329 
330  // Plan a path
331  BiDirMotion *connection_point = nullptr;
332  bool earlyFailure = true;
333 
334  if (initMotion != nullptr && goalMotion != nullptr)
335  {
336  earlyFailure = plan(initMotion, goalMotion, connection_point, ptc);
337  }
338  else
339  {
340  OMPL_ERROR("Initial/goal state(s) are undefined!");
341  }
342 
343  if (earlyFailure)
344  {
345  return base::PlannerStatus(false, false);
346  }
347 
348  // Save the best path (through z)
349  if (!ptc)
350  {
351  base::Cost fwd_cost, rev_cost, connection_cost;
352 
353  // Construct the solution path
354  useFwdTree();
355  BiDirMotionPtrs path_fwd;
356  tracePath(connection_point, path_fwd);
357  fwd_cost = connection_point->getCost();
358 
359  useRevTree();
360  BiDirMotionPtrs path_rev;
361  tracePath(connection_point, path_rev);
362  rev_cost = connection_point->getCost();
363 
364  // ASSUMES FROM THIS POINT THAT z = path_fwd[0] = path_rev[0]
365  // Remove the first element, z, in the traced reverse path
366  // (the same as the first element in the traced forward path)
367  if (path_rev.size() > 1)
368  {
369  connection_cost = base::Cost(rev_cost.value() - path_rev[1]->getCost().value());
370  path_rev.erase(path_rev.begin());
371  }
372  else if (path_fwd.size() > 1)
373  {
374  connection_cost = base::Cost(fwd_cost.value() - path_fwd[1]->getCost().value());
375  path_fwd.erase(path_fwd.begin());
376  }
377  else
378  {
379  OMPL_ERROR("Solution path traced incorrectly or otherwise constructed improperly \
380  through forward/reverse trees (both paths are one node in length, each).");
381  }
382 
383  // Adjust costs/parents in reverse tree nodes as cost/direction from forward tree root
384  useFwdTree();
385  path_rev[0]->setCost(base::Cost(path_fwd[0]->getCost().value() + connection_cost.value()));
386  path_rev[0]->setParent(path_fwd[0]);
387  for (unsigned int i = 1; i < path_rev.size(); ++i)
388  {
389  path_rev[i]->setCost(
390  base::Cost(fwd_cost.value() + (rev_cost.value() - path_rev[i]->getCost().value())));
391  path_rev[i]->setParent(path_rev[i - 1]);
392  }
393 
394  BiDirMotionPtrs mpath;
395  std::reverse(path_rev.begin(), path_rev.end());
396  mpath.reserve(path_fwd.size() + path_rev.size()); // preallocate memory
397  mpath.insert(mpath.end(), path_rev.begin(), path_rev.end());
398  mpath.insert(mpath.end(), path_fwd.begin(), path_fwd.end());
399 
400  // Set the solution path
401  auto path(std::make_shared<PathGeometric>(si_));
402  for (int i = mpath.size() - 1; i >= 0; --i)
403  {
404  path->append(mpath[i]->getState());
405  }
406 
407  static const bool approximate = false;
408  static const double cost_difference_from_goal = 0.0;
409  pdef_->addSolutionPath(path, approximate, cost_difference_from_goal, getName());
410 
411  OMPL_DEBUG("Total path cost: %f\n", fwd_cost.value() + rev_cost.value());
412  return base::PlannerStatus(true, false);
413  }
414 
415  // Planner terminated without accomplishing goal
416  return {false, false};
417  }
418 
419  void BFMT::expandTreeFromNode(BiDirMotion *&z, BiDirMotion *&connection_point)
420  {
421  // Define Opennew and set it to NULL
422  BiDirMotionPtrs Open_new;
423 
424  // Define Znear as all unexplored nodes in the neighborhood around z
425  BiDirMotionPtrs zNear;
426  const BiDirMotionPtrs &zNeighborhood = neighborhoods_[z];
427 
428  for (auto i : zNeighborhood)
429  {
430  if (i->getCurrentSet() == BiDirMotion::SET_UNVISITED)
431  {
432  zNear.push_back(i);
433  }
434  }
435 
436  // For each node x in Znear
437  for (auto x : zNear)
438  {
439  if (!precomputeNN_)
440  saveNeighborhood(x); // nearest neighbors
441 
442  // Define Xnear as all frontier nodes in the neighborhood around the unexplored node x
443  BiDirMotionPtrs xNear;
444  const BiDirMotionPtrs &xNeighborhood = neighborhoods_[x];
445  for (auto j : xNeighborhood)
446  {
447  if (j->getCurrentSet() == BiDirMotion::SET_OPEN)
448  {
449  xNear.push_back(j);
450  }
451  }
452  // Find the node in Xnear with minimum cost-to-come in the current tree
453  BiDirMotion *xMin = nullptr;
454  double cMin = std::numeric_limits<double>::infinity();
455  for (auto &j : xNear)
456  {
457  // check if node costs are smaller than minimum
458  double cNew = j->getCost().value() + distanceFunction(j, x);
459 
460  if (cNew < cMin)
461  {
462  xMin = j;
463  cMin = cNew;
464  }
465  }
466 
467  // xMin was found
468  if (xMin != nullptr)
469  {
470  bool collision_free = false;
471  if (cacheCC_)
472  {
473  if (!xMin->alreadyCC(x))
474  {
475  collision_free = si_->checkMotion(xMin->getState(), x->getState());
477  // Due to FMT3* design, it is only necessary to save unsuccesful
478  // connection attemps because of collision
479  if (!collision_free)
480  xMin->addCC(x);
481  }
482  }
483  else
484  {
486  collision_free = si_->checkMotion(xMin->getState(), x->getState());
487  }
488 
489  if (collision_free)
490  { // motion between yMin and x is obstacle free
491  // add edge from xMin to x
492  x->setParent(xMin);
493  x->setCost(base::Cost(cMin));
494  xMin->getChildren().push_back(x);
495 
496  if (heuristics_)
497  x->setHeuristicCost(opt_->motionCostHeuristic(x->getState(), heurGoalState_[tree_]));
498 
499  // check if new node x is in the other tree; if so, save result
500  if (x->getOtherSet() != BiDirMotion::SET_UNVISITED)
501  {
502  if (connection_point == nullptr)
503  {
504  connection_point = x;
505  if (termination_ == FEASIBILITY)
506  {
507  break;
508  }
509  }
510  else
511  {
512  if ((connection_point->cost_[FWD].value() + connection_point->cost_[REV].value()) >
513  (x->cost_[FWD].value() + x->cost_[REV].value()))
514  {
515  connection_point = x;
516  }
517  }
518  }
519 
520  Open_new.push_back(x); // add x to Open_new
521  x->setCurrentSet(BiDirMotion::SET_CLOSED); // remove x from Unvisited
522  }
523  }
524  } // End "for x in Znear"
525 
526  // Remove motion z from binary heap and map
527  BiDirMotionBinHeap::Element *zElement = Open_elements[tree_][z];
528  Open_[tree_].remove(zElement);
529  Open_elements[tree_].erase(z);
530  z->setCurrentSet(BiDirMotion::SET_CLOSED);
531 
532  // add nodes in Open_new to Open
533  for (auto &i : Open_new)
534  {
535  if(Open_elements[tree_][i] == nullptr)
536  {
537  Open_elements[tree_][i] = Open_[tree_].insert(i);
538  i->setCurrentSet(BiDirMotion::SET_OPEN);
539  }
540  }
541  }
542 
543  bool BFMT::plan(BiDirMotion *x_init, BiDirMotion *x_goal, BiDirMotion *&connection_point,
545  {
546  // If pre-computation, find neighborhoods for all N sample nodes plus initial
547  // and goal state(s). Otherwise compute the neighborhoods of the initial and
548  // goal states separately and compute the others as needed.
549  BiDirMotionPtrs sampleNodes;
550  nn_->list(sampleNodes);
553  if (precomputeNN_)
554  {
555  for (auto &sampleNode : sampleNodes)
556  {
557  saveNeighborhood(sampleNode); // nearest neighbors
558  }
559  }
560  else
561  {
562  saveNeighborhood(x_init); // nearest neighbors
563  saveNeighborhood(x_goal); // nearest neighbors
564  }
565 
566  // Copy nodes in the sample set to Unvisitedfwd. Overwrite the label of the initial
567  // node with set Open for the forward tree, since it starts in set Openfwd.
568  useFwdTree();
569  for (auto &sampleNode : sampleNodes)
570  {
571  sampleNode->setCurrentSet(BiDirMotion::SET_UNVISITED);
572  }
573  x_init->setCurrentSet(BiDirMotion::SET_OPEN);
574 
575  // Copy nodes in the sample set to Unvisitedrev. Overwrite the label of the goal
576  // node with set Open for the reverse tree, since it starts in set Openrev.
577  useRevTree();
578  for (auto &sampleNode : sampleNodes)
579  {
580  sampleNode->setCurrentSet(BiDirMotion::SET_UNVISITED);
581  }
582  x_goal->setCurrentSet(BiDirMotion::SET_OPEN);
583 
584  // Expand the trees until reaching the termination condition
585  bool earlyFailure = false;
586  bool success = false;
587 
588  useFwdTree();
589  BiDirMotion *z = x_init;
590 
591  while (!success)
592  {
593  expandTreeFromNode(z, connection_point);
594 
595  // Check if the algorithm should terminate. Possibly redefines connection_point.
596  if (termination(z, connection_point, ptc))
597  success = true;
598  else
599  {
600  if (Open_[tree_].empty()) // If this heap is empty...
601  {
602  if (!extendedFMT_) // ... eFMT not enabled...
603  {
604  if (Open_[(tree_ + 1) % 2].empty()) // ... and this one, failure.
605  {
606  OMPL_INFORM("Both Open are empty before path was found --> no feasible path exists");
607  earlyFailure = true;
608  return earlyFailure;
609  }
610  }
611  else // However, if eFMT is enabled, run it.
612  insertNewSampleInOpen(ptc);
613  }
614 
615  // This function will be always reached with at least one state in one heap.
616  // However, if ptc terminates, we should skip this.
617  if (!ptc)
618  chooseTreeAndExpansionNode(z);
619  else
620  return true;
621  }
622  }
623  earlyFailure = false;
624  return earlyFailure;
625  }
626 
628  {
629  // Sample and connect samples to tree only if there is
630  // a possibility to connect to unvisited nodes.
631  std::vector<BiDirMotion *> nbh;
632  std::vector<base::Cost> costs;
633  std::vector<base::Cost> incCosts;
634  std::vector<std::size_t> sortedCostIndices;
635 
636  // our functor for sorting nearest neighbors
637  CostIndexCompare compareFn(costs, *opt_);
638 
639  auto *m = new BiDirMotion(si_, &tree_);
640  while (!ptc && Open_[tree_].empty()) //&& oneSample)
641  {
642  // Get new sample and check whether it is valid.
643  sampler_->sampleUniform(m->getState());
644  if (!si_->isValid(m->getState()))
645  continue;
646 
647  // Get neighbours of the new sample.
648  std::vector<BiDirMotion *> yNear;
649  if (nearestK_)
650  nn_->nearestK(m, NNk_, nbh);
651  else
652  nn_->nearestR(m, NNr_, nbh);
653 
654  yNear.reserve(nbh.size());
655  for (auto &j : nbh)
656  {
657  if (j->getCurrentSet() == BiDirMotion::SET_CLOSED)
658  {
659  if (nearestK_)
660  {
661  // Only include neighbors that are mutually k-nearest
662  // Relies on NN datastructure returning k-nearest in sorted order
663  const base::Cost connCost = opt_->motionCost(j->getState(), m->getState());
664  const base::Cost worstCost =
665  opt_->motionCost(neighborhoods_[j].back()->getState(), j->getState());
666 
667  if (opt_->isCostBetterThan(worstCost, connCost))
668  continue;
669  yNear.push_back(j);
670  }
671  else
672  yNear.push_back(j);
673  }
674  }
675 
676  // Sample again if the new sample does not connect to the tree.
677  if (yNear.empty())
678  continue;
679 
680  // cache for distance computations
681  //
682  // Our cost caches only increase in size, so they're only
683  // resized if they can't fit the current neighborhood
684  if (costs.size() < yNear.size())
685  {
686  costs.resize(yNear.size());
687  incCosts.resize(yNear.size());
688  sortedCostIndices.resize(yNear.size());
689  }
690 
691  // Finding the nearest neighbor to connect to
692  // By default, neighborhood states are sorted by cost, and collision checking
693  // is performed in increasing order of cost
694  //
695  // calculate all costs and distances
696  for (std::size_t i = 0; i < yNear.size(); ++i)
697  {
698  incCosts[i] = opt_->motionCost(yNear[i]->getState(), m->getState());
699  costs[i] = opt_->combineCosts(yNear[i]->getCost(), incCosts[i]);
700  }
701 
702  // sort the nodes
703  //
704  // we're using index-value pairs so that we can get at
705  // original, unsorted indices
706  for (std::size_t i = 0; i < yNear.size(); ++i)
707  sortedCostIndices[i] = i;
708  std::sort(sortedCostIndices.begin(), sortedCostIndices.begin() + yNear.size(), compareFn);
709 
710  // collision check until a valid motion is found
711  for (std::vector<std::size_t>::const_iterator i = sortedCostIndices.begin();
712  i != sortedCostIndices.begin() + yNear.size(); ++i)
713  {
715  if (si_->checkMotion(yNear[*i]->getState(), m->getState()))
716  {
717  const base::Cost incCost = opt_->motionCost(yNear[*i]->getState(), m->getState());
718  m->setParent(yNear[*i]);
719  yNear[*i]->getChildren().push_back(m);
720  m->setCost(opt_->combineCosts(yNear[*i]->getCost(), incCost));
721  m->setHeuristicCost(opt_->motionCostHeuristic(m->getState(), heurGoalState_[tree_]));
722  m->setCurrentSet(BiDirMotion::SET_OPEN);
723  Open_elements[tree_][m] = Open_[tree_].insert(m);
724 
725  nn_->add(m);
726  saveNeighborhood(m);
727  updateNeighborhood(m, nbh);
728 
729  break;
730  }
731  }
732  } // While Open_[tree_] empty
733  }
734 
735  bool BFMT::termination(BiDirMotion *&z, BiDirMotion *&connection_point,
737  {
738  bool terminate = false;
739  switch (termination_)
740  {
741  case FEASIBILITY:
742  // Test if a connection point was found during tree expansion
743  return (connection_point != nullptr || ptc);
744  break;
745 
746  case OPTIMALITY:
747  // Test if z is in SET_CLOSED (interior) of other tree
748  if (ptc)
749  terminate = true;
750  else if (z->getOtherSet() == BiDirMotion::SET_CLOSED)
751  terminate = true;
752 
753  break;
754  };
755  return terminate;
756  }
757 
758  // Choose exploration tree and node z to expand
760  {
761  switch (exploration_)
762  {
763  case SWAP_EVERY_TIME:
764  if (Open_[(tree_ + 1) % 2].empty())
765  z = Open_[tree_].top()->data; // Continue expanding the current tree (not empty by exit
766  // condition in plan())
767  else
768  {
769  z = Open_[(tree_ + 1) % 2].top()->data; // Take top of opposite tree heap as new z
770  swapTrees(); // Swap to the opposite tree
771  }
772  break;
773 
774  case CHOOSE_SMALLEST_Z:
775  BiDirMotion *z1, *z2;
776  if (Open_[(tree_ + 1) % 2].empty())
777  z = Open_[tree_].top()->data; // Continue expanding the current tree (not empty by exit
778  // condition in plan())
779  else if (Open_[tree_].empty())
780  {
781  z = Open_[(tree_ + 1) % 2].top()->data; // Take top of opposite tree heap as new z
782  swapTrees(); // Swap to the opposite tree
783  }
784  else
785  {
786  z1 = Open_[tree_].top()->data;
787  z2 = Open_[(tree_ + 1) % 2].top()->data;
788 
789  if (z1->getCost().value() < z2->getOtherCost().value())
790  z = z1;
791  else
792  {
793  z = z2;
794  swapTrees();
795  }
796  }
797  break;
798  };
799  }
800 
801  // Trace a path of nodes along a tree towards the root (forward or reverse)
802  void BFMT::tracePath(BiDirMotion *z, BiDirMotionPtrs &path)
803  {
804  BiDirMotion *solution = z;
805 
806  while (solution != nullptr)
807  {
808  path.push_back(solution);
809  solution = solution->getParent();
810  }
811  }
812 
814  {
815  tree_ = (TreeType)((((int)tree_) + 1) % 2);
816  }
817 
818  void BFMT::updateNeighborhood(BiDirMotion *m, const std::vector<BiDirMotion *> nbh)
819  {
820  // Neighborhoods are only updated if the new motion is within bounds (k nearest or within r).
821  for (auto i : nbh)
822  {
823  // If CLOSED, that neighborhood won't be used again.
824  // Else, if neighhboorhod already exists, we have to insert the node in
825  // the corresponding place of the neighborhood of the neighbor of m.
826  if (i->getCurrentSet() == BiDirMotion::SET_CLOSED)
827  continue;
828 
829  auto it = neighborhoods_.find(i);
830  if (it != neighborhoods_.end())
831  {
832  if (it->second.empty())
833  continue;
834 
835  const base::Cost connCost = opt_->motionCost(i->getState(), m->getState());
836  const base::Cost worstCost = opt_->motionCost(it->second.back()->getState(), i->getState());
837 
838  if (opt_->isCostBetterThan(worstCost, connCost))
839  continue;
840 
841  // insert the neighbor in the vector in the correct order
842  std::vector<BiDirMotion *> &nbhToUpdate = it->second;
843  for (std::size_t j = 0; j < nbhToUpdate.size(); ++j)
844  {
845  // If connection to the new state is better than the current neighbor tested, insert.
846  const base::Cost cost = opt_->motionCost(i->getState(), nbhToUpdate[j]->getState());
847  if (opt_->isCostBetterThan(connCost, cost))
848  {
849  nbhToUpdate.insert(nbhToUpdate.begin() + j, m);
850  break;
851  }
852  }
853  }
854  }
855  }
856  } // End "geometric" namespace
857 } // End "ompl" namespace
base::OptimizationObjectivePtr opt_
The cost objective function.
Definition: FMT.h:576
MotionBinHeap Open_
A binary heap for storing explored motions in cost-to-come sorted order. The motions in Open have bee...
Definition: FMT.h:526
unsigned int collisionChecks_
Number of collision checks performed by the algorithm.
Definition: FMT.h:536
unsigned int NNk_
K used in the nearestK strategy.
Definition: FMT.h:551
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbor datastructure containing the set of all motions.
Definition: FMT.h:570
void freeMemory()
Free the memory allocated by this planner.
Definition: FMT.cpp:120
void saveNeighborhood(BiDirMotion *m)
Save the neighbors within a neighborhood of a given state. The strategy used (nearestK or nearestR de...
Definition: BFMT.cpp:162
double calculateUnitBallVolume(unsigned int dimension) const
Compute the volume of the unit ball in a given dimension.
Definition: FMT.cpp:194
@ UNRECOGNIZED_GOAL_TYPE
The goal is of a type that a planner does not recognize.
bool getExtendedFMT() const
Returns true if the extended FMT* is activated.
Definition: BFMT.h:315
void saveNeighborhood(Motion *m)
Save the neighbors within a neighborhood of a given state. The strategy used (nearestK or nearestR de...
Definition: FMT.cpp:169
base::Cost cost_[2]
The cost of this motion
Definition: BFMT.h:429
LessThan & getComparisonOperator()
Return a reference to the comparison operator.
Definition: BinaryHeap.h:298
bool heuristics_
Flag to activate the cost to go heuristics.
Definition: FMT.h:545
Element * top() const
Return the top element. nullptr for an empty heap.
Definition: BinaryHeap.h:184
BiDirMotionPtrs getChildren() const
Get the children of the motion.
Definition: BFMT.h:474
unsigned int numSamples_
The number of samples to use when planning.
Definition: FMT.h:533
double getRadiusMultiplier() const
Get the multiplier used for the nearest neighbors search radius.
Definition: BFMT.h:260
Definition of an abstract state.
Definition: State.h:113
bool getNearestK() const
Get the state of the nearestK strategy.
Definition: BFMT.h:237
std::map< Motion *, std::vector< Motion * > > neighborhoods_
A map linking a motion to all of the motions within a distance r of that motion.
Definition: FMT.h:530
ProblemDefinitionPtr pdef_
The user set problem definition.
Definition: Planner.h:477
void setExtendedFMT(bool e)
Activates the extended FMT*: adding new samples if planner does not finish successfully.
Definition: BFMT.h:309
double value() const
The value of the cost.
Definition: Cost.h:152
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
bool getHeuristics() const
Returns true if the heap is ordered taking into account cost to go heuristics.
Definition: BFMT.h:303
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition: Cost.h:111
void addCC(BiDirMotion *m)
Caches a failed collision check to m.
Definition: BFMT.h:529
void clear()
Clear the heap.
Definition: BinaryHeap.h:176
bool extendedFMT_
Add new samples if the tree was not able to find a solution.
Definition: FMT.h:585
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68
void insertNewSampleInOpen(const base::PlannerTerminationCondition &ptc)
Extended FMT strategy: inserts a new motion in open if the heap is empty.
Definition: BFMT.cpp:627
double radiusMultiplier_
This planner uses a nearest neighbor search radius proportional to the lower bound for optimality der...
Definition: FMT.h:567
unsigned int getNumSamples() const
Get the number of states that the planner will sample.
Definition: BFMT.h:225
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Definition: PlannerData.h:238
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:106
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
const State * nextStart()
Return the next valid start state or nullptr if no more valid start states are available.
Definition: Planner.cpp:228
void setRadiusMultiplier(const double radiusMultiplier)
The planner searches for neighbors of a node within a cost r, where r is the value described for BFMT...
Definition: BFMT.h:251
bool getCacheCC() const
Get the state of the collision check caching.
Definition: BFMT.h:290
PlannerSpecs specs_
The specifications of the planner (its capabilities)
Definition: Planner.h:486
@ INVALID_GOAL
Invalid goal state.
bool directed
Flag indicating whether the planner is able to account for the fact that the validity of a motion fro...
Definition: Planner.h:269
bool cacheCC_
Flag to activate the collision check caching.
Definition: FMT.h:542
void sampleFree(const ompl::base::PlannerTerminationCondition &ptc)
Sample a state from the free configuration space and save it into the nearest neighbors data structur...
Definition: FMT.cpp:212
double distanceFunction(const Motion *a, const Motion *b) const
Compute the distance between two motions as the cost between their contained states....
Definition: FMT.h:462
bool expandTreeFromNode(Motion **z)
Complete one iteration of the main loop of the FMT* algorithm: Find K nearest nodes in set Unvisited ...
Definition: FMT.cpp:504
A class to store the exit status of Planner::solve()
TreeType
Tree identifier.
Definition: BFMT.h:182
void setNearestK(bool nearestK)
If nearestK is true, FMT will be run using the Knearest strategy.
Definition: BFMT.h:231
const State * nextGoal(const PlannerTerminationCondition &ptc)
Return the next valid goal state or nullptr if no more valid goal states are available....
Definition: Planner.cpp:265
void setHeuristics(bool h)
Activates the cost to go heuristics when ordering the heap.
Definition: BFMT.h:296
base::Cost getCost() const
Set the state associated with the motion.
Definition: BFMT.h:438
Abstract representation of a container that can perform nearest neighbors queries.
bool nearestK_
Flag to activate the K nearest neighbors strategy.
Definition: FMT.h:539
void setTermination(bool optimality)
Sets the termination strategy: optimality true finishes when the best possible path is found....
Definition: BFMT.h:340
bool getExploration() const
Returns the exploration strategy.
Definition: BFMT.h:332
base::StateSamplerPtr sampler_
State sampler.
Definition: FMT.h:573
bool setup_
Flag indicating whether setup() has been called.
Definition: Planner.h:497
double calculateUnitBallVolume(unsigned int dimension) const
Compute the volume of the unit ball in a given dimension.
Definition: BFMT.cpp:215
void updateNeighborhood(BiDirMotion *m, std::vector< BiDirMotion * > nbh)
For a motion m, updates the stored neighborhoods of all its neighbors by by inserting m (maintaining ...
Definition: BFMT.cpp:818
bool getTermination() const
Returns the termination strategy.
Definition: BFMT.h:350
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: BFMT.cpp:121
double freeSpaceVolume_
The volume of the free configuration space, computed as an upper bound with 95% confidence.
Definition: FMT.h:555
double calculateRadius(unsigned int dimension, unsigned int n) const
Calculate the radius to use for nearest neighbor searches, using the bound given in [L....
Definition: FMT.cpp:203
void setCurrentSet(SetType set)
Set the current set of the motion.
Definition: BFMT.h:480
void initializeProblem(base::GoalSampleableRegion *&goal_s)
Carries out some planner checks.
Definition: BFMT.cpp:233
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition: Console.h:66
BiDirMotion * getParent() const
Get the parent of the motion.
Definition: BFMT.h:462
void swapTrees()
Change the active tree.
Definition: BFMT.cpp:813
Element * insert(const _T &data)
Add a new element.
Definition: BinaryHeap.h:204
void expandTreeFromNode(BiDirMotion *&z, BiDirMotion *&connection_point)
Complete one iteration of the main loop of the BFMT* algorithm: Find K nearest nodes in set Unvisited...
Definition: BFMT.cpp:419
double calculateRadius(unsigned int dimension, unsigned int n) const
Calculate the radius to use for nearest neighbor searches, using the bound given in [L....
Definition: BFMT.cpp:224
void remove(Element *element)
Remove a specific element.
Definition: BinaryHeap.h:196
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: BFMT.cpp:243
SetType currentSet_[2]
Current set in which the motion is included.
Definition: BFMT.h:423
virtual void getPlannerData(PlannerData &data) const
Get information about the current run of the motion planner. Repeated calls to this function will upd...
Definition: Planner.cpp:129
double NNr_
Radius employed in the nearestR strategy.
Definition: FMT.h:548
void sampleFree(const std::shared_ptr< NearestNeighbors< BiDirMotion * >> &nn, const base::PlannerTerminationCondition &ptc)
Sample a state from the free configuration space and save it into the nearest neighbors data structur...
Definition: BFMT.cpp:187
bool alreadyCC(BiDirMotion *m)
Returns true if the connection to m has been already tested and failed because of a collision.
Definition: BFMT.h:523
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: BFMT.cpp:106
PlannerInputStates pis_
Utility class to extract valid input states
Definition: Planner.h:480
bool termination(BiDirMotion *&z, BiDirMotion *&connection_point, const base::PlannerTerminationCondition &ptc)
Checks if the termination condition is met.
Definition: BFMT.cpp:735
SpaceInformationPtr si_
The space information for which planning is done.
Definition: Planner.h:474
bool plan(BiDirMotion *x_init, BiDirMotion *x_goal, BiDirMotion *&connection_point, const base::PlannerTerminationCondition &ptc)
Executes the actual planning algorithm, swapping and expanding the trees.
Definition: BFMT.cpp:543
void updateNeighborhood(Motion *m, std::vector< Motion * > nbh)
For a motion m, updates the stored neighborhoods of all its neighbors by by inserting m (maintaining ...
Definition: FMT.cpp:643
base::State * getState() const
Get the state associated with the motion.
Definition: BFMT.h:516
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition: Console.h:64
void chooseTreeAndExpansionNode(BiDirMotion *&z)
Chooses and expand a tree according to the exploration strategy.
Definition: BFMT.cpp:759
bool approximateSolutions
Flag indicating whether the planner is able to compute approximate solutions.
Definition: Planner.h:259
void freeMemory()
Free the memory allocated by this planner.
Definition: BFMT.cpp:92
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: BFMT.cpp: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...
void setNumSamples(const unsigned int numSamples)
Set the number of states that the planner should sample. The planner will sample this number of state...
Definition: BFMT.h:219
Abstract definition of a goal region that can be sampled.
void setCacheCC(bool ccc)
Sets the collision check caching to save calls to the collision checker with slightly memory usage as...
Definition: BFMT.h:284
void tracePath(BiDirMotion *z, BiDirMotionPtrs &path)
Trace the path along a tree towards the root (forward or reverse)
Definition: BFMT.cpp:802
SetType getOtherSet() const
Get set of this motion in the inactive tree.
Definition: BFMT.h:492
base::Cost getOtherCost() const
Get cost of this motion in the inactive tree.
Definition: BFMT.h:444
const std::string & getName() const
Get the name of the planner.
Definition: Planner.cpp:56
@ INVALID_START
Invalid start state or no start state specified.
#define OMPL_DEBUG(fmt,...)
Log a formatted debugging string.
Definition: Console.h:70
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition: PlannerData.h:122
void setExploration(bool balanced)
Sets exploration strategy: balanced true expands one tree every iteration. False will select the tree...
Definition: BFMT.h:322
Main namespace. Contains everything in this library.
Representation of a bidirectional motion.
Definition: BFMT.h:369