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