Loading...
Searching...
No Matches
FMT.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2013, Autonomous Systems Laboratory, Stanford 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 Stanford 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/* Authors: Ashley Clark (Stanford) and Wolfgang Pointner (AIT) */
36/* Co-developers: Brice Rebsamen (Stanford), Tim Wheeler (Stanford)
37 Edward Schmerling (Stanford), and Javier V. Gómez (UC3M - Stanford)*/
38/* Algorithm design: Lucas Janson (Stanford) and Marco Pavone (Stanford) */
39/* Acknowledgements for insightful comments: Oren Salzman (Tel Aviv University),
40 * Joseph Starek (Stanford) */
41
42#include <limits>
43#include <iostream>
44
45#include <boost/math/constants/constants.hpp>
46#include <boost/math/distributions/binomial.hpp>
47
48#include <ompl/datastructures/BinaryHeap.h>
49#include <ompl/tools/config/SelfConfig.h>
50#include <ompl/base/objectives/PathLengthOptimizationObjective.h>
51#include <ompl/geometric/planners/fmt/FMT.h>
52
53ompl::geometric::FMT::FMT(const base::SpaceInformationPtr &si) : base::Planner(si, "FMT")
54{
55 // An upper bound on the free space volume is the total space volume; the free fraction is estimated in sampleFree
56 freeSpaceVolume_ = si_->getStateSpace()->getMeasure();
57 lastGoalMotion_ = nullptr;
58
59 specs_.approximateSolutions = false;
60 specs_.directed = false;
61
62 ompl::base::Planner::declareParam<unsigned int>("num_samples", this, &FMT::setNumSamples, &FMT::getNumSamples,
63 "10:10:1000000");
64 ompl::base::Planner::declareParam<double>("radius_multiplier", this, &FMT::setRadiusMultiplier,
65 &FMT::getRadiusMultiplier, "0.1:0.05:50.");
66 ompl::base::Planner::declareParam<bool>("use_k_nearest", this, &FMT::setNearestK, &FMT::getNearestK, "0,1");
67 ompl::base::Planner::declareParam<bool>("cache_cc", this, &FMT::setCacheCC, &FMT::getCacheCC, "0,1");
68 ompl::base::Planner::declareParam<bool>("heuristics", this, &FMT::setHeuristics, &FMT::getHeuristics, "0,1");
69 ompl::base::Planner::declareParam<bool>("extended_fmt", this, &FMT::setExtendedFMT, &FMT::getExtendedFMT, "0,1");
70}
71
72ompl::geometric::FMT::~FMT()
73{
74 freeMemory();
75}
76
78{
79 if (pdef_)
80 {
81 /* Setup the optimization objective. If no optimization objective was
82 specified, then default to optimizing path length as computed by the
83 distance() function in the state space */
84 if (pdef_->hasOptimizationObjective())
85 opt_ = pdef_->getOptimizationObjective();
86 else
87 {
88 OMPL_INFORM("%s: No optimization objective specified. Defaulting to optimizing path length.",
89 getName().c_str());
90 opt_ = std::make_shared<base::PathLengthOptimizationObjective>(si_);
91 // Store the new objective in the problem def'n
92 pdef_->setOptimizationObjective(opt_);
93 }
94 Open_.getComparisonOperator().opt_ = opt_.get();
95 Open_.getComparisonOperator().heuristics_ = heuristics_;
96
97 if (!nn_)
99 nn_->setDistanceFunction([this](const Motion *a, const Motion *b) { return distanceFunction(a, b); });
100
101 if (nearestK_ && !nn_->reportsSortedResults())
102 {
103 OMPL_WARN("%s: NearestNeighbors datastructure does not return sorted solutions. Nearest K strategy "
104 "disabled.",
105 getName().c_str());
106 nearestK_ = false;
107 }
108 }
109 else
110 {
111 OMPL_INFORM("%s: problem definition is not set, deferring setup completion...", getName().c_str());
112 setup_ = false;
113 }
114}
115
117{
118 if (nn_)
119 {
120 std::vector<Motion *> motions;
121 motions.reserve(nn_->size());
122 nn_->list(motions);
123 for (auto &motion : motions)
124 {
125 si_->freeState(motion->getState());
126 delete motion;
127 }
128 }
129}
130
132{
133 Planner::clear();
134 lastGoalMotion_ = nullptr;
135 sampler_.reset();
136 freeMemory();
137 if (nn_)
138 nn_->clear();
139 Open_.clear();
140 neighborhoods_.clear();
141
143}
144
146{
147 Planner::getPlannerData(data);
148 std::vector<Motion *> motions;
149 nn_->list(motions);
150
151 if (lastGoalMotion_ != nullptr)
153
154 unsigned int size = motions.size();
155 for (unsigned int i = 0; i < size; ++i)
156 {
157 if (motions[i]->getParent() == nullptr)
158 data.addStartVertex(base::PlannerDataVertex(motions[i]->getState()));
159 else
160 data.addEdge(base::PlannerDataVertex(motions[i]->getParent()->getState()),
161 base::PlannerDataVertex(motions[i]->getState()));
162 }
163}
164
166{
167 // Check to see if neighborhood has not been saved yet
168 if (neighborhoods_.find(m) == neighborhoods_.end())
169 {
170 std::vector<Motion *> nbh;
171 if (nearestK_)
172 nn_->nearestK(m, NNk_, nbh);
173 else
174 nn_->nearestR(m, NNr_, nbh);
175 if (!nbh.empty())
176 {
177 // Save the neighborhood but skip the first element, since it will be motion m
178 neighborhoods_[m] = std::vector<Motion *>(nbh.size() - 1, nullptr);
179 std::copy(nbh.begin() + 1, nbh.end(), neighborhoods_[m].begin());
180 }
181 else
182 {
183 // Save an empty neighborhood
184 neighborhoods_[m] = std::vector<Motion *>(0);
185 }
186 } // If neighborhood hadn't been saved yet
187}
188
189// Calculate the unit ball volume for a given dimension
190double ompl::geometric::FMT::calculateUnitBallVolume(const unsigned int dimension) const
191{
192 if (dimension == 0)
193 return 1.0;
194 if (dimension == 1)
195 return 2.0;
196 return 2.0 * boost::math::constants::pi<double>() / dimension * calculateUnitBallVolume(dimension - 2);
197}
198
199double ompl::geometric::FMT::calculateRadius(const unsigned int dimension, const unsigned int n) const
200{
201 double a = 1.0 / (double)dimension;
202 double unitBallVolume = calculateUnitBallVolume(dimension);
203
204 return radiusMultiplier_ * 2.0 * std::pow(a, a) * std::pow(freeSpaceVolume_ / unitBallVolume, a) *
205 std::pow(log((double)n) / (double)n, a);
206}
207
209{
210 unsigned int nodeCount = 0;
211 unsigned int sampleAttempts = 0;
212 auto *motion = new Motion(si_);
213
214 // Sample numSamples_ number of nodes from the free configuration space
215 while (nodeCount < numSamples_ && !ptc)
216 {
217 sampler_->sampleUniform(motion->getState());
218 sampleAttempts++;
219
220 bool collision_free = si_->isValid(motion->getState());
221
222 if (collision_free)
223 {
224 nodeCount++;
225 nn_->add(motion);
226 motion = new Motion(si_);
227 } // If collision free
228 } // While nodeCount < numSamples
229 si_->freeState(motion->getState());
230 delete motion;
231
232 // 95% confidence limit for an upper bound for the true free space volume
233 freeSpaceVolume_ = boost::math::binomial_distribution<>::find_upper_bound_on_p(sampleAttempts, nodeCount, 0.05) *
234 si_->getStateSpace()->getMeasure();
235}
236
238{
239 // Ensure that there is at least one node near each goal
240 while (const base::State *goalState = pis_.nextGoal())
241 {
242 auto *gMotion = new Motion(si_);
243 si_->copyState(gMotion->getState(), goalState);
244
245 std::vector<Motion *> nearGoal;
246 nn_->nearestR(gMotion, goal->getThreshold(), nearGoal);
247
248 // If there is no node in the goal region, insert one
249 if (nearGoal.empty())
250 {
251 OMPL_DEBUG("No state inside goal region");
252 if (si_->getStateValidityChecker()->isValid(gMotion->getState()))
253 {
254 nn_->add(gMotion);
255 goalState_ = gMotion->getState();
256 }
257 else
258 {
259 si_->freeState(gMotion->getState());
260 delete gMotion;
261 }
262 }
263 else // There is already a sample in the goal region
264 {
265 goalState_ = nearGoal[0]->getState();
266 si_->freeState(gMotion->getState());
267 delete gMotion;
268 }
269 } // For each goal
270}
271
273{
274 if (lastGoalMotion_ != nullptr)
275 {
276 OMPL_INFORM("solve() called before clear(); returning previous solution");
278 OMPL_DEBUG("Final path cost: %f", lastGoalMotion_->getCost().value());
279 return base::PlannerStatus(true, false);
280 }
281 if (!Open_.empty())
282 {
283 OMPL_INFORM("solve() called before clear(); no previous solution so starting afresh");
284 clear();
285 }
286
288 auto *goal = dynamic_cast<base::GoalSampleableRegion *>(pdef_->getGoal().get());
289 Motion *initMotion = nullptr;
290
291 if (goal == nullptr)
292 {
293 OMPL_ERROR("%s: Unknown type of goal", getName().c_str());
295 }
296
297 if (!goal->couldSample())
298 {
299 OMPL_ERROR("%s: Insufficient states in sampleable goal region", getName().c_str());
301 }
302
303 // Add start states to V (nn_) and Open
304 while (const base::State *st = pis_.nextStart())
305 {
306 initMotion = new Motion(si_);
307 si_->copyState(initMotion->getState(), st);
308 Open_.insert(initMotion);
309 initMotion->setSetType(Motion::SET_OPEN);
310 initMotion->setCost(opt_->initialCost(initMotion->getState()));
311 nn_->add(initMotion); // V <-- {x_init}
312 }
313
314 if (initMotion == nullptr)
315 {
316 OMPL_ERROR("Start state undefined");
318 }
319
320 // Sample N free states in the configuration space
321 if (!sampler_)
322 sampler_ = si_->allocStateSampler();
323 sampleFree(ptc);
325 OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), nn_->size());
326
327 // Calculate the nearest neighbor search radius
329 if (nearestK_)
330 {
331 NNk_ = std::ceil(std::pow(2.0 * radiusMultiplier_, (double)si_->getStateDimension()) *
332 (boost::math::constants::e<double>() / (double)si_->getStateDimension()) *
333 log((double)nn_->size()));
334 OMPL_DEBUG("Using nearest-neighbors k of %d", NNk_);
335 }
336 else
337 {
338 NNr_ = calculateRadius(si_->getStateDimension(), nn_->size());
339 OMPL_DEBUG("Using radius of %f", NNr_);
340 }
341
342 // Execute the planner, and return early if the planner returns a failure
343 bool plannerSuccess = false;
344 bool successfulExpansion = false;
345 Motion *z = initMotion; // z <-- xinit
347
348 while (!ptc)
349 {
350 if ((plannerSuccess = goal->isSatisfied(z->getState())))
351 break;
352
353 successfulExpansion = expandTreeFromNode(&z);
354
355 if (!extendedFMT_ && !successfulExpansion)
356 break;
357 if (extendedFMT_ && !successfulExpansion)
358 {
359 // Apply RRT*-like connections: sample and connect samples to tree
360 std::vector<Motion *> nbh;
361 std::vector<base::Cost> costs;
362 std::vector<base::Cost> incCosts;
363 std::vector<std::size_t> sortedCostIndices;
364
365 // our functor for sorting nearest neighbors
366 CostIndexCompare compareFn(costs, *opt_);
367
368 auto *m = new Motion(si_);
369 while (!ptc && Open_.empty())
370 {
371 sampler_->sampleUniform(m->getState());
372
373 if (!si_->isValid(m->getState()))
374 continue;
375
376 if (nearestK_)
377 nn_->nearestK(m, NNk_, nbh);
378 else
379 nn_->nearestR(m, NNr_, nbh);
380
381 // Get neighbours in the tree.
382 std::vector<Motion *> yNear;
383 yNear.reserve(nbh.size());
384 for (auto &j : nbh)
385 {
386 if (j->getSetType() == Motion::SET_CLOSED)
387 {
388 if (nearestK_)
389 {
390 // Only include neighbors that are mutually k-nearest
391 // Relies on NN datastructure returning k-nearest in sorted order
392 const base::Cost connCost = opt_->motionCost(j->getState(), m->getState());
393 const base::Cost worstCost =
394 opt_->motionCost(neighborhoods_[j].back()->getState(), j->getState());
395
396 if (opt_->isCostBetterThan(worstCost, connCost))
397 continue;
398 yNear.push_back(j);
399 }
400 else
401 yNear.push_back(j);
402 }
403 }
404
405 // Sample again if the new sample does not connect to the tree.
406 if (yNear.empty())
407 continue;
408
409 // cache for distance computations
410 //
411 // Our cost caches only increase in size, so they're only
412 // resized if they can't fit the current neighborhood
413 if (costs.size() < yNear.size())
414 {
415 costs.resize(yNear.size());
416 incCosts.resize(yNear.size());
417 sortedCostIndices.resize(yNear.size());
418 }
419
420 // Finding the nearest neighbor to connect to
421 // By default, neighborhood states are sorted by cost, and collision checking
422 // is performed in increasing order of cost
423 //
424 // calculate all costs and distances
425 for (std::size_t i = 0; i < yNear.size(); ++i)
426 {
427 incCosts[i] = opt_->motionCost(yNear[i]->getState(), m->getState());
428 costs[i] = opt_->combineCosts(yNear[i]->getCost(), incCosts[i]);
429 }
430
431 // sort the nodes
432 //
433 // we're using index-value pairs so that we can get at
434 // original, unsorted indices
435 for (std::size_t i = 0; i < yNear.size(); ++i)
436 sortedCostIndices[i] = i;
437 std::sort(sortedCostIndices.begin(), sortedCostIndices.begin() + yNear.size(), compareFn);
438
439 // collision check until a valid motion is found
440 for (std::vector<std::size_t>::const_iterator i = sortedCostIndices.begin();
441 i != sortedCostIndices.begin() + yNear.size(); ++i)
442 {
443 if (si_->checkMotion(yNear[*i]->getState(), m->getState()))
444 {
445 m->setParent(yNear[*i]);
446 yNear[*i]->getChildren().push_back(m);
447 const base::Cost incCost = opt_->motionCost(yNear[*i]->getState(), m->getState());
448 m->setCost(opt_->combineCosts(yNear[*i]->getCost(), incCost));
449 m->setHeuristicCost(opt_->motionCostHeuristic(m->getState(), goalState_));
450 m->setSetType(Motion::SET_OPEN);
451
452 nn_->add(m);
454 updateNeighborhood(m, nbh);
455
456 Open_.insert(m);
457 z = m;
458 break;
459 }
460 }
461 } // while (!ptc && Open_.empty())
462 } // else if (extendedFMT_ && !successfulExpansion)
463 } // While not at goal
464
465 if (plannerSuccess)
466 {
467 // Return the path to z, since by definition of planner success, z is in the goal region
468 lastGoalMotion_ = z;
470
471 OMPL_DEBUG("Final path cost: %f", lastGoalMotion_->getCost().value());
472
473 return base::PlannerStatus(true, false);
474 } // if plannerSuccess
475
476 // Planner terminated without accomplishing goal
477 return {false, false};
478}
479
481{
482 std::vector<Motion *> mpath;
483 Motion *solution = goalMotion;
484
485 // Construct the solution path
486 while (solution != nullptr)
487 {
488 mpath.push_back(solution);
489 solution = solution->getParent();
490 }
491
492 // Set the solution path
493 auto path(std::make_shared<PathGeometric>(si_));
494 int mPathSize = mpath.size();
495 for (int i = mPathSize - 1; i >= 0; --i)
496 path->append(mpath[i]->getState());
497 pdef_->addSolutionPath(path, false, -1.0, getName());
498}
499
501{
502 // Find all nodes that are near z, and also in set Unvisited
503
504 std::vector<Motion *> xNear;
505 const std::vector<Motion *> &zNeighborhood = neighborhoods_[*z];
506 const unsigned int zNeighborhoodSize = zNeighborhood.size();
507 xNear.reserve(zNeighborhoodSize);
508
509 for (unsigned int i = 0; i < zNeighborhoodSize; ++i)
510 {
511 Motion *x = zNeighborhood[i];
512 if (x->getSetType() == Motion::SET_UNVISITED)
513 {
515 if (nearestK_)
516 {
517 // Only include neighbors that are mutually k-nearest
518 // Relies on NN datastructure returning k-nearest in sorted order
519 const base::Cost connCost = opt_->motionCost((*z)->getState(), x->getState());
520 const base::Cost worstCost = opt_->motionCost(neighborhoods_[x].back()->getState(), x->getState());
521
522 if (opt_->isCostBetterThan(worstCost, connCost))
523 continue;
524 xNear.push_back(x);
525 }
526 else
527 xNear.push_back(x);
528 }
529 }
530
531 // For each node near z and in set Unvisited, attempt to connect it to set Open
532 std::vector<Motion *> yNear;
533 std::vector<Motion *> Open_new;
534 const unsigned int xNearSize = xNear.size();
535 for (unsigned int i = 0; i < xNearSize; ++i)
536 {
537 Motion *x = xNear[i];
538
539 // Find all nodes that are near x and in set Open
540 const std::vector<Motion *> &xNeighborhood = neighborhoods_[x];
541
542 const unsigned int xNeighborhoodSize = xNeighborhood.size();
543 yNear.reserve(xNeighborhoodSize);
544 for (unsigned int j = 0; j < xNeighborhoodSize; ++j)
545 {
546 if (xNeighborhood[j]->getSetType() == Motion::SET_OPEN)
547 yNear.push_back(xNeighborhood[j]);
548 }
549
550 // Find the lowest cost-to-come connection from Open to x
551 base::Cost cMin(opt_->infiniteCost());
552 Motion *yMin = getBestParent(x, yNear, cMin);
553 yNear.clear();
554
555 // If an optimal connection from Open to x was found
556 if (yMin != nullptr)
557 {
558 bool collision_free = false;
559 if (cacheCC_)
560 {
561 if (!yMin->alreadyCC(x))
562 {
563 collision_free = si_->checkMotion(yMin->getState(), x->getState());
565 // Due to FMT* design, it is only necessary to save unsuccesful
566 // connection attemps because of collision
567 if (!collision_free)
568 yMin->addCC(x);
569 }
570 }
571 else
572 {
574 collision_free = si_->checkMotion(yMin->getState(), x->getState());
575 }
576
577 if (collision_free)
578 {
579 // Add edge from yMin to x
580 x->setParent(yMin);
581 x->setCost(cMin);
582 x->setHeuristicCost(opt_->motionCostHeuristic(x->getState(), goalState_));
583 yMin->getChildren().push_back(x);
584
585 // Add x to Open
586 Open_new.push_back(x);
587 // Remove x from Unvisited
588 x->setSetType(Motion::SET_CLOSED);
589 }
590 } // An optimal connection from Open to x was found
591 } // For each node near z and in set Unvisited, try to connect it to set Open
592
593 // Update Open
594 Open_.pop();
595 (*z)->setSetType(Motion::SET_CLOSED);
596
597 // Add the nodes in Open_new to Open
598 unsigned int openNewSize = Open_new.size();
599 for (unsigned int i = 0; i < openNewSize; ++i)
600 {
601 Open_.insert(Open_new[i]);
602 Open_new[i]->setSetType(Motion::SET_OPEN);
603 }
604 Open_new.clear();
605
606 if (Open_.empty())
607 {
608 if (!extendedFMT_)
609 OMPL_INFORM("Open is empty before path was found --> no feasible path exists");
610 return false;
611 }
612
613 // Take the top of Open as the new z
614 *z = Open_.top()->data;
615
616 return true;
617}
618
620 base::Cost &cMin)
621{
622 Motion *min = nullptr;
623 const unsigned int neighborsSize = neighbors.size();
624 for (unsigned int j = 0; j < neighborsSize; ++j)
625 {
626 const base::State *s = neighbors[j]->getState();
627 const base::Cost dist = opt_->motionCost(s, m->getState());
628 const base::Cost cNew = opt_->combineCosts(neighbors[j]->getCost(), dist);
629
630 if (opt_->isCostBetterThan(cNew, cMin))
631 {
632 min = neighbors[j];
633 cMin = cNew;
634 }
635 }
636 return min;
637}
638
639void ompl::geometric::FMT::updateNeighborhood(Motion *m, const std::vector<Motion *> nbh)
640{
641 for (auto i : nbh)
642 {
643 // If CLOSED, the neighborhood already exists. If neighborhood already exists, we have
644 // to insert the node in the corresponding place of the neighborhood of the neighbor of m.
645 if (i->getSetType() == Motion::SET_CLOSED || neighborhoods_.find(i) != neighborhoods_.end())
646 {
647 const base::Cost connCost = opt_->motionCost(i->getState(), m->getState());
648 const base::Cost worstCost = opt_->motionCost(neighborhoods_[i].back()->getState(), i->getState());
649
650 if (opt_->isCostBetterThan(worstCost, connCost))
651 continue;
652
653 // Insert the neighbor in the vector in the correct order
654 std::vector<Motion *> &nbhToUpdate = neighborhoods_[i];
655 for (std::size_t j = 0; j < nbhToUpdate.size(); ++j)
656 {
657 // If connection to the new state is better than the current neighbor tested, insert.
658 const base::Cost cost = opt_->motionCost(i->getState(), nbhToUpdate[j]->getState());
659 if (opt_->isCostBetterThan(connCost, cost))
660 {
661 nbhToUpdate.insert(nbhToUpdate.begin() + j, m);
662 break;
663 }
664 }
665 }
666 else
667 {
668 std::vector<Motion *> nbh2;
669 if (nearestK_)
670 nn_->nearestK(m, NNk_, nbh2);
671 else
672 nn_->nearestR(m, NNr_, nbh2);
673
674 if (!nbh2.empty())
675 {
676 // Save the neighborhood but skip the first element, since it will be motion m
677 neighborhoods_[i] = std::vector<Motion *>(nbh2.size() - 1, nullptr);
678 std::copy(nbh2.begin() + 1, nbh2.end(), neighborhoods_[i].begin());
679 }
680 else
681 {
682 // Save an empty neighborhood
683 neighborhoods_[i] = std::vector<Motion *>(0);
684 }
685 }
686 }
687}
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition Cost.h:48
double getThreshold() const
Get the distance to the goal that is allowed for a state to be considered in the goal region.
Definition GoalRegion.h:82
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,...
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...
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...
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
Definition of an abstract state.
Definition State.h:50
Representation of a motion.
Definition FMT.h:215
void setSetType(const SetType currentSet)
Specify the set that this motion belongs to.
Definition FMT.h:277
base::State * getState() const
Get the state associated with the motion.
Definition FMT.h:247
void addCC(Motion *m)
Caches a failed collision check to m.
Definition FMT.h:296
void setCost(const base::Cost cost)
Set the cost-to-come for the current motion.
Definition FMT.h:265
std::vector< Motion * > & getChildren()
Get the children of the motion.
Definition FMT.h:314
bool alreadyCC(Motion *m)
Returns true if the connection to m has been already tested and failed because of a collision.
Definition FMT.h:290
Motion * getParent() const
Get the parent motion of the current motion.
Definition FMT.h:259
unsigned int NNk_
K used in the nearestK strategy.
Definition FMT.h:454
bool nearestK_
Flag to activate the K nearest neighbors strategy.
Definition FMT.h:442
void saveNeighborhood(Motion *m)
Save the neighbors within a neighborhood of a given state. The strategy used (nearestK or nearestR de...
Definition FMT.cpp:165
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:199
bool cacheCC_
Flag to activate the collision check caching.
Definition FMT.h:445
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbor datastructure containing the set of all motions.
Definition FMT.h:473
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 FMT.cpp:272
bool heuristics_
Flag to activate the cost to go heuristics.
Definition FMT.h:448
double radiusMultiplier_
This planner uses a nearest neighbor search radius proportional to the lower bound for optimality der...
Definition FMT.h:470
void traceSolutionPathThroughTree(Motion *goalMotion)
Trace the path from a goal state back to the start state and save the result as a solution in the Pro...
Definition FMT.cpp:480
unsigned int numSamples_
The number of samples to use when planning.
Definition FMT.h:436
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:639
Motion * getBestParent(Motion *m, std::vector< Motion * > &neighbors, base::Cost &cMin)
Returns the best parent and the connection cost in the neighborhood of a motion m.
Definition FMT.cpp:619
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:208
base::OptimizationObjectivePtr opt_
The cost objective function.
Definition FMT.h:479
base::State * goalState_
Goal state caching to accelerate cost to go heuristic computation.
Definition FMT.h:485
double NNr_
Radius employed in the nearestR strategy.
Definition FMT.h:451
void freeMemory()
Free the memory allocated by this planner.
Definition FMT.cpp:116
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition FMT.cpp:131
double freeSpaceVolume_
The volume of the free configuration space, computed as an upper bound with 95% confidence.
Definition FMT.h:458
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:433
base::StateSamplerPtr sampler_
State sampler.
Definition FMT.h:476
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition FMT.h:482
unsigned int collisionChecks_
Number of collision checks performed by the algorithm.
Definition FMT.h:439
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:365
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:500
MotionBinHeap Open_
A binary heap for storing explored motions in cost-to-come sorted order. The motions in Open have bee...
Definition FMT.h:429
bool extendedFMT_
Add new samples if the tree was not able to find a solution.
Definition FMT.h:488
double calculateUnitBallVolume(unsigned int dimension) const
Compute the volume of the unit ball in a given dimension.
Definition FMT.cpp:190
void getPlannerData(base::PlannerData &data) const override
Get information about the current run of the motion planner. Repeated calls to this function will upd...
Definition FMT.cpp:145
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition FMT.cpp:77
void assureGoalIsSampled(const ompl::base::GoalSampleableRegion *goal)
For each goal region, check to see if any of the sampled states fall within that region....
Definition FMT.cpp:237
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 sampling based planning routines shared by both planning under geometric cons...
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.