Loading...
Searching...
No Matches
RRTstar.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2011, Rice University
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Rice 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: Alejandro Perez, Sertac Karaman, Ryan Luna, Luis G. Torres, Ioan Sucan, Javier V Gomez, Jonathan Gammell */
36
37#include "ompl/geometric/planners/rrt/RRTstar.h"
38#include <algorithm>
39#include <boost/math/constants/constants.hpp>
40#include <limits>
41#include <vector>
42#include "ompl/base/Goal.h"
43#include "ompl/base/goals/GoalSampleableRegion.h"
44#include "ompl/base/goals/GoalState.h"
45#include "ompl/base/objectives/PathLengthOptimizationObjective.h"
46#include "ompl/base/samplers/InformedStateSampler.h"
47#include "ompl/base/samplers/informed/RejectionInfSampler.h"
48#include "ompl/base/samplers/informed/OrderedInfSampler.h"
49#include "ompl/tools/config/SelfConfig.h"
50#include "ompl/util/GeometricEquations.h"
51
52ompl::geometric::RRTstar::RRTstar(const base::SpaceInformationPtr &si) : base::Planner(si, "RRTstar")
53{
54 specs_.approximateSolutions = true;
55 specs_.optimizingPaths = true;
56 specs_.canReportIntermediateSolutions = true;
57
58 Planner::declareParam<double>("range", this, &RRTstar::setRange, &RRTstar::getRange, "0.:1.:10000.");
59 Planner::declareParam<double>("goal_bias", this, &RRTstar::setGoalBias, &RRTstar::getGoalBias, "0.:.05:1.");
60 Planner::declareParam<double>("rewire_factor", this, &RRTstar::setRewireFactor, &RRTstar::getRewireFactor,
61 "1.0:0.01:2.0");
62 Planner::declareParam<bool>("use_k_nearest", this, &RRTstar::setKNearest, &RRTstar::getKNearest, "0,1");
63 Planner::declareParam<bool>("delay_collision_checking", this, &RRTstar::setDelayCC, &RRTstar::getDelayCC, "0,1");
64 Planner::declareParam<bool>("tree_pruning", this, &RRTstar::setTreePruning, &RRTstar::getTreePruning, "0,1");
65 Planner::declareParam<double>("prune_threshold", this, &RRTstar::setPruneThreshold, &RRTstar::getPruneThreshold,
66 "0.:.01:1.");
67 Planner::declareParam<bool>("pruned_measure", this, &RRTstar::setPrunedMeasure, &RRTstar::getPrunedMeasure, "0,1");
68 Planner::declareParam<bool>("informed_sampling", this, &RRTstar::setInformedSampling, &RRTstar::getInformedSampling,
69 "0,1");
70 Planner::declareParam<bool>("sample_rejection", this, &RRTstar::setSampleRejection, &RRTstar::getSampleRejection,
71 "0,1");
72 Planner::declareParam<bool>("new_state_rejection", this, &RRTstar::setNewStateRejection,
73 &RRTstar::getNewStateRejection, "0,1");
74 Planner::declareParam<bool>("use_admissible_heuristic", this, &RRTstar::setAdmissibleCostToCome,
75 &RRTstar::getAdmissibleCostToCome, "0,1");
76 Planner::declareParam<bool>("ordered_sampling", this, &RRTstar::setOrderedSampling, &RRTstar::getOrderedSampling,
77 "0,1");
78 Planner::declareParam<unsigned int>("ordering_batch_size", this, &RRTstar::setBatchSize, &RRTstar::getBatchSize,
79 "1:100:1000000");
80 Planner::declareParam<bool>("focus_search", this, &RRTstar::setFocusSearch, &RRTstar::getFocusSearch, "0,1");
81 Planner::declareParam<unsigned int>("number_sampling_attempts", this, &RRTstar::setNumSamplingAttempts,
82 &RRTstar::getNumSamplingAttempts, "10:10:100000");
83
84 addPlannerProgressProperty("iterations INTEGER", [this] { return numIterationsProperty(); });
85 addPlannerProgressProperty("best cost REAL", [this] { return bestCostProperty(); });
86}
87
88ompl::geometric::RRTstar::~RRTstar()
89{
90 freeMemory();
91}
92
94{
95 Planner::setup();
98 if (!si_->getStateSpace()->hasSymmetricDistance() || !si_->getStateSpace()->hasSymmetricInterpolate())
99 {
100 OMPL_WARN("%s requires a state space with symmetric distance and symmetric interpolation.", getName().c_str());
101 }
102
103 if (!nn_)
105 nn_->setDistanceFunction([this](const Motion *a, const Motion *b) { return distanceFunction(a, b); });
106
107 // Setup optimization objective
108 //
109 // If no optimization objective was specified, then default to
110 // optimizing path length as computed by the distance() function
111 // in the state space.
112 if (pdef_)
113 {
114 if (pdef_->hasOptimizationObjective())
115 opt_ = pdef_->getOptimizationObjective();
116 else
117 {
118 OMPL_INFORM("%s: No optimization objective specified. Defaulting to optimizing path length for the allowed "
119 "planning time.",
120 getName().c_str());
121 opt_ = std::make_shared<base::PathLengthOptimizationObjective>(si_);
122
123 // Store the new objective in the problem def'n
124 pdef_->setOptimizationObjective(opt_);
125 }
126
127 // Set the bestCost_ and prunedCost_ as infinite
128 bestCost_ = opt_->infiniteCost();
129 prunedCost_ = opt_->infiniteCost();
130 }
131 else
132 {
133 OMPL_INFORM("%s: problem definition is not set, deferring setup completion...", getName().c_str());
134 setup_ = false;
135 }
136
137 // Get the measure of the entire space:
138 prunedMeasure_ = si_->getSpaceMeasure();
139
140 // Calculate some constants:
142}
143
145{
146 setup_ = false;
147 Planner::clear();
148 sampler_.reset();
149 infSampler_.reset();
150 freeMemory();
151 if (nn_)
152 nn_->clear();
153
154 bestGoalMotion_ = nullptr;
155 goalMotions_.clear();
156 startMotions_.clear();
157
158 iterations_ = 0;
159 bestCost_ = base::Cost(std::numeric_limits<double>::quiet_NaN());
160 prunedCost_ = base::Cost(std::numeric_limits<double>::quiet_NaN());
161 prunedMeasure_ = 0.0;
162}
163
165{
167 base::Goal *goal = pdef_->getGoal().get();
168 auto *goal_s = dynamic_cast<base::GoalSampleableRegion *>(goal);
169
170 bool symCost = opt_->isSymmetric();
171
172 // Check if there are more starts
173 if (pis_.haveMoreStartStates() == true)
174 {
175 // There are, add them
176 while (const base::State *st = pis_.nextStart())
177 {
178 auto *motion = new Motion(si_);
179 si_->copyState(motion->state, st);
180 motion->cost = opt_->identityCost();
181 nn_->add(motion);
182 startMotions_.push_back(motion);
183 }
184
185 // And assure that, if we're using an informed sampler, it's reset
186 infSampler_.reset();
187 }
188 // No else
189
190 if (nn_->size() == 0)
191 {
192 OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
194 }
195
196 // Allocate a sampler if necessary
197 if (!sampler_ && !infSampler_)
198 {
199 allocSampler();
200 }
201
202 OMPL_INFORM("%s: Started planning with %u states. Seeking a solution better than %.5f.", getName().c_str(),
203 nn_->size(), opt_->getCostThreshold().value());
204
206 !si_->getStateSpace()->isMetricSpace())
207 OMPL_WARN("%s: The state space (%s) is not metric and as a result the optimization objective may not satisfy "
208 "the triangle inequality. "
209 "You may need to disable pruning or rejection.",
210 getName().c_str(), si_->getStateSpace()->getName().c_str());
211
212 const base::ReportIntermediateSolutionFn intermediateSolutionCallback = pdef_->getIntermediateSolutionCallback();
213
214 Motion *approxGoalMotion = nullptr;
215 double approxDist = std::numeric_limits<double>::infinity();
216
217 auto *rmotion = new Motion(si_);
218 base::State *rstate = rmotion->state;
219 base::State *xstate = si_->allocState();
220
221 std::vector<Motion *> nbh;
222
223 std::vector<base::Cost> costs;
224 std::vector<base::Cost> incCosts;
225 std::vector<std::size_t> sortedCostIndices;
226
227 std::vector<int> valid;
228 unsigned int rewireTest = 0;
229 unsigned int statesGenerated = 0;
230
231 if (bestGoalMotion_)
232 OMPL_INFORM("%s: Starting planning with existing solution of cost %.5f", getName().c_str(), bestCost_.value());
233
234 if (useKNearest_)
235 OMPL_INFORM("%s: Initial k-nearest value of %u", getName().c_str(),
236 (unsigned int)std::ceil(k_rrt_ * log((double)(nn_->size() + 1u))));
237 else
239 "%s: Initial rewiring radius of %.2f", getName().c_str(),
240 std::min(maxDistance_, r_rrt_ * std::pow(log((double)(nn_->size() + 1u)) / ((double)(nn_->size() + 1u)),
241 1 / (double)(si_->getStateDimension()))));
242
243 // our functor for sorting nearest neighbors
244 CostIndexCompare compareFn(costs, *opt_);
245
246 while (ptc == false)
247 {
248 iterations_++;
249
250 // sample random state (with goal biasing)
251 // Goal samples are only sampled until maxSampleCount() goals are in the tree, to prohibit duplicate goal
252 // states.
253 if (goal_s && goalMotions_.size() < goal_s->maxSampleCount() && rng_.uniform01() < goalBias_ &&
254 goal_s->canSample())
255 goal_s->sampleGoal(rstate);
256 else
257 {
258 // Attempt to generate a sample, if we fail (e.g., too many rejection attempts), skip the remainder of this
259 // loop and return to try again
260 if (!sampleUniform(rstate))
261 continue;
262 }
263
264 // find closest state in the tree
265 Motion *nmotion = nn_->nearest(rmotion);
266
267 if (intermediateSolutionCallback && si_->equalStates(nmotion->state, rstate))
268 continue;
269
270 base::State *dstate = rstate;
271
272 // find state to add to the tree
273 double d = si_->distance(nmotion->state, rstate);
274 if (d > maxDistance_)
275 {
276 si_->getStateSpace()->interpolate(nmotion->state, rstate, maxDistance_ / d, xstate);
277 dstate = xstate;
278 }
279
280 // Check if the motion between the nearest state and the state to add is valid
281 if (si_->checkMotion(nmotion->state, dstate))
282 {
283 // create a motion
284 auto *motion = new Motion(si_);
285 si_->copyState(motion->state, dstate);
286 motion->parent = nmotion;
287 motion->incCost = opt_->motionCost(nmotion->state, motion->state);
288 motion->cost = opt_->combineCosts(nmotion->cost, motion->incCost);
289
290 // Find nearby neighbors of the new motion
291 getNeighbors(motion, nbh);
292
293 rewireTest += nbh.size();
294 ++statesGenerated;
295
296 // cache for distance computations
297 //
298 // Our cost caches only increase in size, so they're only
299 // resized if they can't fit the current neighborhood
300 if (costs.size() < nbh.size())
301 {
302 costs.resize(nbh.size());
303 incCosts.resize(nbh.size());
304 sortedCostIndices.resize(nbh.size());
305 }
306
307 // cache for motion validity (only useful in a symmetric space)
308 //
309 // Our validity caches only increase in size, so they're
310 // only resized if they can't fit the current neighborhood
311 if (valid.size() < nbh.size())
312 valid.resize(nbh.size());
313 std::fill(valid.begin(), valid.begin() + nbh.size(), 0);
314
315 // Finding the nearest neighbor to connect to
316 // By default, neighborhood states are sorted by cost, and collision checking
317 // is performed in increasing order of cost
318 if (delayCC_)
319 {
320 // calculate all costs and distances
321 for (std::size_t i = 0; i < nbh.size(); ++i)
322 {
323 incCosts[i] = opt_->motionCost(nbh[i]->state, motion->state);
324 costs[i] = opt_->combineCosts(nbh[i]->cost, incCosts[i]);
325 }
326
327 // sort the nodes
328 //
329 // we're using index-value pairs so that we can get at
330 // original, unsorted indices
331 for (std::size_t i = 0; i < nbh.size(); ++i)
332 sortedCostIndices[i] = i;
333 std::sort(sortedCostIndices.begin(), sortedCostIndices.begin() + nbh.size(), compareFn);
334
335 // collision check until a valid motion is found
336 //
337 // ASYMMETRIC CASE: it's possible that none of these
338 // neighbors are valid. This is fine, because motion
339 // already has a connection to the tree through
340 // nmotion (with populated cost fields!).
341 for (std::vector<std::size_t>::const_iterator i = sortedCostIndices.begin();
342 i != sortedCostIndices.begin() + nbh.size(); ++i)
343 {
344 if (nbh[*i] == nmotion ||
345 ((!useKNearest_ || si_->distance(nbh[*i]->state, motion->state) < maxDistance_) &&
346 si_->checkMotion(nbh[*i]->state, motion->state)))
347 {
348 motion->incCost = incCosts[*i];
349 motion->cost = costs[*i];
350 motion->parent = nbh[*i];
351 valid[*i] = 1;
352 break;
353 }
354 else
355 valid[*i] = -1;
356 }
357 }
358 else // if not delayCC
359 {
360 motion->incCost = opt_->motionCost(nmotion->state, motion->state);
361 motion->cost = opt_->combineCosts(nmotion->cost, motion->incCost);
362 // find which one we connect the new state to
363 for (std::size_t i = 0; i < nbh.size(); ++i)
364 {
365 if (nbh[i] != nmotion)
366 {
367 incCosts[i] = opt_->motionCost(nbh[i]->state, motion->state);
368 costs[i] = opt_->combineCosts(nbh[i]->cost, incCosts[i]);
369 if (opt_->isCostBetterThan(costs[i], motion->cost))
370 {
371 if ((!useKNearest_ || si_->distance(nbh[i]->state, motion->state) < maxDistance_) &&
372 si_->checkMotion(nbh[i]->state, motion->state))
373 {
374 motion->incCost = incCosts[i];
375 motion->cost = costs[i];
376 motion->parent = nbh[i];
377 valid[i] = 1;
378 }
379 else
380 valid[i] = -1;
381 }
382 }
383 else
384 {
385 incCosts[i] = motion->incCost;
386 costs[i] = motion->cost;
387 valid[i] = 1;
388 }
389 }
390 }
391
393 {
394 if (opt_->isCostBetterThan(solutionHeuristic(motion), bestCost_))
395 {
396 nn_->add(motion);
397 motion->parent->children.push_back(motion);
398 }
399 else // If the new motion does not improve the best cost it is ignored.
400 {
401 si_->freeState(motion->state);
402 delete motion;
403 continue;
404 }
405 }
406 else
407 {
408 // add motion to the tree
409 nn_->add(motion);
410 motion->parent->children.push_back(motion);
411 }
412
413 bool checkForSolution = false;
414 for (std::size_t i = 0; i < nbh.size(); ++i)
415 {
416 if (nbh[i] != motion->parent)
417 {
418 base::Cost nbhIncCost;
419 if (symCost)
420 nbhIncCost = incCosts[i];
421 else
422 nbhIncCost = opt_->motionCost(motion->state, nbh[i]->state);
423 base::Cost nbhNewCost = opt_->combineCosts(motion->cost, nbhIncCost);
424 if (opt_->isCostBetterThan(nbhNewCost, nbh[i]->cost))
425 {
426 bool motionValid;
427 if (valid[i] == 0)
428 {
429 motionValid =
430 (!useKNearest_ || si_->distance(nbh[i]->state, motion->state) < maxDistance_) &&
431 si_->checkMotion(motion->state, nbh[i]->state);
432 }
433 else
434 {
435 motionValid = (valid[i] == 1);
436 }
437
438 if (motionValid)
439 {
440 // Remove this node from its parent list
441 removeFromParent(nbh[i]);
442
443 // Add this node to the new parent
444 nbh[i]->parent = motion;
445 nbh[i]->incCost = nbhIncCost;
446 nbh[i]->cost = nbhNewCost;
447 nbh[i]->parent->children.push_back(nbh[i]);
448
449 // Update the costs of the node's children
450 updateChildCosts(nbh[i]);
451
452 checkForSolution = true;
453 }
454 }
455 }
456 }
457
458 // Add the new motion to the goalMotion_ list, if it satisfies the goal
459 double distanceFromGoal;
460 if (goal->isSatisfied(motion->state, &distanceFromGoal))
461 {
462 motion->inGoal = true;
463 goalMotions_.push_back(motion);
464 checkForSolution = true;
465 }
466
467 // Checking for solution or iterative improvement
468 if (checkForSolution)
469 {
470 bool updatedSolution = false;
471 if (!bestGoalMotion_ && !goalMotions_.empty())
472 {
473 // We have found our first solution, store it as the best. We only add one
474 // vertex at a time, so there can only be one goal vertex at this moment.
477 updatedSolution = true;
478
479 OMPL_INFORM("%s: Found an initial solution with a cost of %.2f in %u iterations (%u "
480 "vertices in the graph)",
481 getName().c_str(), bestCost_.value(), iterations_, nn_->size());
482 }
483 else
484 {
485 // We already have a solution, iterate through the list of goal vertices
486 // and see if there's any improvement.
487 for (auto &goalMotion : goalMotions_)
488 {
489 // Is this goal motion better than the (current) best?
490 if (opt_->isCostBetterThan(goalMotion->cost, bestCost_))
491 {
492 bestGoalMotion_ = goalMotion;
494 updatedSolution = true;
495
496 // Check if it satisfies the optimization objective, if it does, break the for loop
497 if (opt_->isSatisfied(bestCost_))
498 {
499 break;
500 }
501 }
502 }
503 }
504
505 if (updatedSolution)
506 {
507 if (useTreePruning_)
508 {
510 }
511
512 if (intermediateSolutionCallback)
513 {
514 std::vector<const base::State *> spath;
515 Motion *intermediate_solution =
516 bestGoalMotion_->parent; // Do not include goal state to simplify code.
517
518 // Push back until we find the start, but not the start itself
519 while (intermediate_solution->parent != nullptr)
520 {
521 spath.push_back(intermediate_solution->state);
522 intermediate_solution = intermediate_solution->parent;
523 }
524
525 intermediateSolutionCallback(this, spath, bestCost_);
526 }
527 }
528 }
529
530 // Checking for approximate solution (closest state found to the goal)
531 if (goalMotions_.size() == 0 && distanceFromGoal < approxDist)
532 {
533 approxGoalMotion = motion;
534 approxDist = distanceFromGoal;
535 }
536 }
537
538 // terminate if a sufficient solution is found
539 if (bestGoalMotion_ && opt_->isSatisfied(bestCost_))
540 break;
541 }
542
543 // Add our solution (if it exists)
544 Motion *newSolution = nullptr;
545 if (bestGoalMotion_)
546 {
547 // We have an exact solution
548 newSolution = bestGoalMotion_;
549 }
550 else if (approxGoalMotion)
551 {
552 // We don't have a solution, but we do have an approximate solution
553 newSolution = approxGoalMotion;
554 }
555 // No else, we have nothing
556
557 // Add what we found
558 if (newSolution)
559 {
560 ptc.terminate();
561 // construct the solution path
562 std::vector<Motion *> mpath;
563 Motion *iterMotion = newSolution;
564 while (iterMotion != nullptr)
565 {
566 mpath.push_back(iterMotion);
567 iterMotion = iterMotion->parent;
568 }
569
570 // set the solution path
571 auto path(std::make_shared<PathGeometric>(si_));
572 for (int i = mpath.size() - 1; i >= 0; --i)
573 path->append(mpath[i]->state);
574
575 // Add the solution path.
576 base::PlannerSolution psol(path);
577 psol.setPlannerName(getName());
578
579 // If we don't have a goal motion, the solution is approximate
580 if (!bestGoalMotion_)
581 psol.setApproximate(approxDist);
582
583 // Does the solution satisfy the optimization objective?
584 psol.setOptimized(opt_, newSolution->cost, opt_->isSatisfied(bestCost_));
585 pdef_->addSolutionPath(psol);
586 }
587 // No else, we have nothing
588
589 si_->freeState(xstate);
590 if (rmotion->state)
591 si_->freeState(rmotion->state);
592 delete rmotion;
593
594 OMPL_INFORM("%s: Created %u new states. Checked %u rewire options. %u goal states in tree. Final solution cost "
595 "%.3f",
596 getName().c_str(), statesGenerated, rewireTest, goalMotions_.size(), bestCost_.value());
597
598 // We've added a solution if newSolution == true, and it is an approximate solution if bestGoalMotion_ == false
599 return {newSolution != nullptr, bestGoalMotion_ == nullptr};
600}
601
602void ompl::geometric::RRTstar::getNeighbors(Motion *motion, std::vector<Motion *> &nbh) const
603{
604 auto cardDbl = static_cast<double>(nn_->size() + 1u);
605 if (useKNearest_)
606 {
607 //- k-nearest RRT*
608 unsigned int k = std::ceil(k_rrt_ * log(cardDbl));
609 nn_->nearestK(motion, k, nbh);
610 }
611 else
612 {
613 double r = std::min(
614 maxDistance_, r_rrt_ * std::pow(log(cardDbl) / cardDbl, 1 / static_cast<double>(si_->getStateDimension())));
615 nn_->nearestR(motion, r, nbh);
616 }
617}
618
620{
621 for (auto it = m->parent->children.begin(); it != m->parent->children.end(); ++it)
622 {
623 if (*it == m)
624 {
625 m->parent->children.erase(it);
626 break;
627 }
628 }
629}
630
632{
633 for (std::size_t i = 0; i < m->children.size(); ++i)
634 {
635 m->children[i]->cost = opt_->combineCosts(m->cost, m->children[i]->incCost);
637 }
638}
639
641{
642 if (nn_)
643 {
644 std::vector<Motion *> motions;
645 nn_->list(motions);
646 for (auto &motion : motions)
647 {
648 if (motion->state)
649 si_->freeState(motion->state);
650 delete motion;
651 }
652 }
653}
654
656{
657 Planner::getPlannerData(data);
658
659 std::vector<Motion *> motions;
660 if (nn_)
661 nn_->list(motions);
662
663 if (bestGoalMotion_)
665
666 for (auto &motion : motions)
667 {
668 if (motion->parent == nullptr)
669 data.addStartVertex(base::PlannerDataVertex(motion->state));
670 else
671 data.addEdge(base::PlannerDataVertex(motion->parent->state), base::PlannerDataVertex(motion->state));
672 }
673}
674
676{
677 // Variable
678 // The percent improvement (expressed as a [0,1] fraction) in cost
679 double fracBetter;
680 // The number pruned
681 int numPruned = 0;
682
683 if (opt_->isFinite(prunedCost_))
684 {
685 fracBetter = std::abs((pruneTreeCost.value() - prunedCost_.value()) / prunedCost_.value());
686 }
687 else
688 {
689 fracBetter = 1.0;
690 }
691
692 if (fracBetter > pruneThreshold_)
693 {
694 // We are only pruning motions if they, AND all descendents, have a estimated cost greater than pruneTreeCost
695 // The easiest way to do this is to find leaves that should be pruned and ascend up their ancestry until a
696 // motion is found that is kept.
697 // To avoid making an intermediate copy of the NN structure, we process the tree by descending down from the
698 // start(s).
699 // In the first pass, all Motions with a cost below pruneTreeCost, or Motion's with children with costs below
700 // pruneTreeCost are added to the replacement NN structure,
701 // while all other Motions are stored as either a 'leaf' or 'chain' Motion. After all the leaves are
702 // disconnected and deleted, we check
703 // if any of the the chain Motions are now leaves, and repeat that process until done.
704 // This avoids (1) copying the NN structure into an intermediate variable and (2) the use of the expensive
705 // NN::remove() method.
706
707 // Variable
708 // The queue of Motions to process:
709 std::queue<Motion *, std::deque<Motion *>> motionQueue;
710 // The list of leaves to prune
711 std::queue<Motion *, std::deque<Motion *>> leavesToPrune;
712 // The list of chain vertices to recheck after pruning
713 std::list<Motion *> chainsToRecheck;
714
715 // Clear the NN structure:
716 nn_->clear();
717
718 // Put all the starts into the NN structure and their children into the queue:
719 // We do this so that start states are never pruned.
720 for (auto &startMotion : startMotions_)
721 {
722 // Add to the NN
723 nn_->add(startMotion);
724
725 // Add their children to the queue:
726 addChildrenToList(&motionQueue, startMotion);
727 }
728
729 while (motionQueue.empty() == false)
730 {
731 // Test, can the current motion ever provide a better solution?
732 if (keepCondition(motionQueue.front(), pruneTreeCost))
733 {
734 // Yes it can, so it definitely won't be pruned
735 // Add it back into the NN structure
736 nn_->add(motionQueue.front());
737
738 // Add it's children to the queue
739 addChildrenToList(&motionQueue, motionQueue.front());
740 }
741 else
742 {
743 // No it can't, but does it have children?
744 if (motionQueue.front()->children.empty() == false)
745 {
746 // Yes it does.
747 // We can minimize the number of intermediate chain motions if we check their children
748 // If any of them won't be pruned, then this motion won't either. This intuitively seems
749 // like a nice balance between following the descendents forever.
750
751 // Variable
752 // Whether the children are definitely to be kept.
753 bool keepAChild = false;
754
755 // Find if any child is definitely not being pruned.
756 for (unsigned int i = 0u; keepAChild == false && i < motionQueue.front()->children.size(); ++i)
757 {
758 // Test if the child can ever provide a better solution
759 keepAChild = keepCondition(motionQueue.front()->children.at(i), pruneTreeCost);
760 }
761
762 // Are we *definitely* keeping any of the children?
763 if (keepAChild)
764 {
765 // Yes, we are, so we are not pruning this motion
766 // Add it back into the NN structure.
767 nn_->add(motionQueue.front());
768 }
769 else
770 {
771 // No, we aren't. This doesn't mean we won't though
772 // Move this Motion to the temporary list
773 chainsToRecheck.push_back(motionQueue.front());
774 }
775
776 // Either way. add it's children to the queue
777 addChildrenToList(&motionQueue, motionQueue.front());
778 }
779 else
780 {
781 // No, so we will be pruning this motion:
782 leavesToPrune.push(motionQueue.front());
783 }
784 }
785
786 // Pop the iterator, std::list::erase returns the next iterator
787 motionQueue.pop();
788 }
789
790 // We now have a list of Motions to definitely remove, and a list of Motions to recheck
791 // Iteratively check the two lists until there is nothing to to remove
792 while (leavesToPrune.empty() == false)
793 {
794 // First empty the current leaves-to-prune
795 while (leavesToPrune.empty() == false)
796 {
797 // If this leaf is a goal, remove it from the goal set
798 if (leavesToPrune.front()->inGoal == true)
799 {
800 // Warn if pruning the _best_ goal
801 if (leavesToPrune.front() == bestGoalMotion_)
802 {
803 OMPL_ERROR("%s: Pruning the best goal.", getName().c_str());
804 }
805 // Remove it
806 goalMotions_.erase(std::remove(goalMotions_.begin(), goalMotions_.end(), leavesToPrune.front()),
807 goalMotions_.end());
808 }
809
810 // Remove the leaf from its parent
811 removeFromParent(leavesToPrune.front());
812
813 // Erase the actual motion
814 // First free the state
815 si_->freeState(leavesToPrune.front()->state);
816
817 // then delete the pointer
818 delete leavesToPrune.front();
819
820 // And finally remove it from the list, erase returns the next iterator
821 leavesToPrune.pop();
822
823 // Update our counter
824 ++numPruned;
825 }
826
827 // Now, we need to go through the list of chain vertices and see if any are now leaves
828 auto mIter = chainsToRecheck.begin();
829 while (mIter != chainsToRecheck.end())
830 {
831 // Is the Motion a leaf?
832 if ((*mIter)->children.empty() == true)
833 {
834 // It is, add to the removal queue
835 leavesToPrune.push(*mIter);
836
837 // Remove from this queue, getting the next
838 mIter = chainsToRecheck.erase(mIter);
839 }
840 else
841 {
842 // Is isn't, skip to the next
843 ++mIter;
844 }
845 }
846 }
847
848 // Now finally add back any vertices left in chainsToReheck.
849 // These are chain vertices that have descendents that we want to keep
850 for (const auto &r : chainsToRecheck)
851 // Add the motion back to the NN struct:
852 nn_->add(r);
853
854 // All done pruning.
855 // Update the cost at which we've pruned:
856 prunedCost_ = pruneTreeCost;
857
858 // And if we're using the pruned measure, the measure to which we've pruned
860 {
861 prunedMeasure_ = infSampler_->getInformedMeasure(prunedCost_);
862
863 if (useKNearest_ == false)
864 {
866 }
867 }
868 // No else, prunedMeasure_ is the si_ measure by default.
869 }
870
871 return numPruned;
872}
873
874void ompl::geometric::RRTstar::addChildrenToList(std::queue<Motion *, std::deque<Motion *>> *motionList, Motion *motion)
875{
876 for (auto &child : motion->children)
877 {
878 motionList->push(child);
879 }
880}
881
882bool ompl::geometric::RRTstar::keepCondition(const Motion *motion, const base::Cost &threshold) const
883{
884 // We keep if the cost-to-come-heuristic of motion is <= threshold, by checking
885 // if !(threshold < heuristic), as if b is not better than a, then a is better than, or equal to, b
886 if (bestGoalMotion_ && motion == bestGoalMotion_)
887 {
888 // If the threshold is the theoretical minimum, the bestGoalMotion_ will sometimes fail the test due to floating
889 // point precision. Avoid that.
890 return true;
891 }
892
893 return !opt_->isCostBetterThan(threshold, solutionHeuristic(motion));
894}
895
897{
898 base::Cost costToCome;
900 {
901 // Start with infinite cost
902 costToCome = opt_->infiniteCost();
903
904 // Find the min from each start
905 for (auto &startMotion : startMotions_)
906 {
907 costToCome = opt_->betterCost(costToCome, opt_->motionCost(startMotion->state,
908 motion->state)); // lower-bounding cost from the
909 // start to the state
910 }
911 }
912 else
913 {
914 costToCome = motion->cost; // current cost from the state to the goal
915 }
916
917 const base::Cost costToGo =
918 opt_->costToGo(motion->state, pdef_->getGoal().get()); // lower-bounding cost from the state to the goal
919 return opt_->combineCosts(costToCome, costToGo); // add the two costs
920}
921
923{
924 if (static_cast<bool>(opt_) == true)
925 {
926 if (opt_->hasCostToGoHeuristic() == false)
927 {
928 OMPL_INFORM("%s: No cost-to-go heuristic set. Informed techniques will not work well.", getName().c_str());
929 }
930 }
931
932 // If we just disabled tree pruning, but we wee using prunedMeasure, we need to disable that as it required myself
933 if (prune == false && getPrunedMeasure() == true)
934 {
935 setPrunedMeasure(false);
936 }
937
938 // Store
939 useTreePruning_ = prune;
940}
941
943{
944 if (static_cast<bool>(opt_) == true)
945 {
946 if (opt_->hasCostToGoHeuristic() == false)
947 {
948 OMPL_INFORM("%s: No cost-to-go heuristic set. Informed techniques will not work well.", getName().c_str());
949 }
950 }
951
952 // This option only works with informed sampling
953 if (informedMeasure == true && (useInformedSampling_ == false || useTreePruning_ == false))
954 {
955 OMPL_ERROR("%s: InformedMeasure requires InformedSampling and TreePruning.", getName().c_str());
956 }
957
958 // Check if we're changed and update parameters if we have:
959 if (informedMeasure != usePrunedMeasure_)
960 {
961 // Store the setting
962 usePrunedMeasure_ = informedMeasure;
963
964 // Update the prunedMeasure_ appropriately, if it has been configured.
965 if (setup_ == true)
966 {
968 {
969 prunedMeasure_ = infSampler_->getInformedMeasure(prunedCost_);
970 }
971 else
972 {
973 prunedMeasure_ = si_->getSpaceMeasure();
974 }
975 }
976
977 // And either way, update the rewiring radius if necessary
978 if (useKNearest_ == false)
979 {
981 }
982 }
983}
984
986{
987 if (static_cast<bool>(opt_) == true)
988 {
989 if (opt_->hasCostToGoHeuristic() == false)
990 {
991 OMPL_INFORM("%s: No cost-to-go heuristic set. Informed techniques will not work well.", getName().c_str());
992 }
993 }
994
995 // This option is mutually exclusive with setSampleRejection, assert that:
996 if (informedSampling == true && useRejectionSampling_ == true)
997 {
998 OMPL_ERROR("%s: InformedSampling and SampleRejection are mutually exclusive options.", getName().c_str());
999 }
1000
1001 // If we just disabled tree pruning, but we are using prunedMeasure, we need to disable that as it required myself
1002 if (informedSampling == false && getPrunedMeasure() == true)
1003 {
1004 setPrunedMeasure(false);
1005 }
1006
1007 // Check if we're changing the setting of informed sampling. If we are, we will need to create a new sampler, which
1008 // we only want to do if one is already allocated.
1009 if (informedSampling != useInformedSampling_)
1010 {
1011 // If we're disabled informedSampling, and prunedMeasure is enabled, we need to disable that
1012 if (informedSampling == false && usePrunedMeasure_ == true)
1013 {
1014 setPrunedMeasure(false);
1015 }
1016
1017 // Store the value
1018 useInformedSampling_ = informedSampling;
1019
1020 // If we currently have a sampler, we need to make a new one
1021 if (sampler_ || infSampler_)
1022 {
1023 // Reset the samplers
1024 sampler_.reset();
1025 infSampler_.reset();
1026
1027 // Create the sampler
1028 allocSampler();
1029 }
1030 }
1031}
1032
1034{
1035 if (static_cast<bool>(opt_) == true)
1036 {
1037 if (opt_->hasCostToGoHeuristic() == false)
1038 {
1039 OMPL_INFORM("%s: No cost-to-go heuristic set. Informed techniques will not work well.", getName().c_str());
1040 }
1041 }
1042
1043 // This option is mutually exclusive with setInformedSampling, assert that:
1044 if (reject == true && useInformedSampling_ == true)
1045 {
1046 OMPL_ERROR("%s: InformedSampling and SampleRejection are mutually exclusive options.", getName().c_str());
1047 }
1048
1049 // Check if we're changing the setting of rejection sampling. If we are, we will need to create a new sampler, which
1050 // we only want to do if one is already allocated.
1051 if (reject != useRejectionSampling_)
1052 {
1053 // Store the setting
1054 useRejectionSampling_ = reject;
1055
1056 // If we currently have a sampler, we need to make a new one
1057 if (sampler_ || infSampler_)
1058 {
1059 // Reset the samplers
1060 sampler_.reset();
1061 infSampler_.reset();
1062
1063 // Create the sampler
1064 allocSampler();
1065 }
1066 }
1067}
1068
1070{
1071 // Make sure we're using some type of informed sampling
1072 if (useInformedSampling_ == false && useRejectionSampling_ == false)
1073 {
1074 OMPL_ERROR("%s: OrderedSampling requires either informed sampling or rejection sampling.", getName().c_str());
1075 }
1076
1077 // Check if we're changing the setting. If we are, we will need to create a new sampler, which we only want to do if
1078 // one is already allocated.
1079 if (orderSamples != useOrderedSampling_)
1080 {
1081 // Store the setting
1082 useOrderedSampling_ = orderSamples;
1083
1084 // If we currently have a sampler, we need to make a new one
1085 if (sampler_ || infSampler_)
1086 {
1087 // Reset the samplers
1088 sampler_.reset();
1089 infSampler_.reset();
1090
1091 // Create the sampler
1092 allocSampler();
1093 }
1094 }
1095}
1096
1098{
1099 // Allocate the appropriate type of sampler.
1101 {
1102 // We are using informed sampling, this can end-up reverting to rejection sampling in some cases
1103 OMPL_INFORM("%s: Using informed sampling.", getName().c_str());
1104 infSampler_ = opt_->allocInformedStateSampler(pdef_, numSampleAttempts_);
1105 }
1106 else if (useRejectionSampling_)
1107 {
1108 // We are explicitly using rejection sampling.
1109 OMPL_INFORM("%s: Using rejection sampling.", getName().c_str());
1110 infSampler_ = std::make_shared<base::RejectionInfSampler>(pdef_, numSampleAttempts_);
1111 }
1112 else
1113 {
1114 // We are using a regular sampler
1115 sampler_ = si_->allocStateSampler();
1116 }
1117
1118 // Wrap into a sorted sampler
1119 if (useOrderedSampling_ == true)
1120 {
1121 infSampler_ = std::make_shared<base::OrderedInfSampler>(infSampler_, batchSize_);
1122 }
1123 // No else
1124}
1125
1127{
1128 // Use the appropriate sampler
1130 {
1131 // Attempt the focused sampler and return the result.
1132 // If bestCost is changing a lot by small amounts, this could
1133 // be prunedCost_ to reduce the number of times the informed sampling
1134 // transforms are recalculated.
1135 return infSampler_->sampleUniform(statePtr, bestCost_);
1136 }
1137 else
1138 {
1139 // Simply return a state from the regular sampler
1140 sampler_->sampleUniform(statePtr);
1141
1142 // Always true
1143 return true;
1144 }
1145}
1146
1148{
1149 const auto dimDbl = static_cast<double>(si_->getStateDimension());
1150
1151 // k_rrt > 2^(d + 1) * e * (1 + 1 / d). K-nearest RRT*
1152 k_rrt_ = rewireFactor_ * (std::pow(2, dimDbl + 1) * boost::math::constants::e<double>() * (1.0 + 1.0 / dimDbl));
1153
1154 // r_rrt > (2*(1+1/d))^(1/d)*(measure/ballvolume)^(1/d)
1155 // If we're not using the informed measure, prunedMeasure_ will be set to si_->getSpaceMeasure();
1157 std::pow(2 * (1.0 + 1.0 / dimDbl) * (prunedMeasure_ / unitNBallMeasure(si_->getStateDimension())),
1158 1.0 / dimDbl);
1159}
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.
Abstract definition of goals.
Definition Goal.h:63
virtual bool isSatisfied(const State *st) const =0
Return true if the state satisfies the goal constraints.
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...
void terminate() const
Notify that the condition for termination should become true, regardless of what eval() returns....
PlannerInputStates pis_
Utility class to extract valid input states.
Definition Planner.h:407
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 RRTstar.h:334
base::Cost cost
The cost up to this motion.
Definition RRTstar.h:354
base::Cost incCost
The incremental cost of this motion's parent to this motion (this is stored to save distance computat...
Definition RRTstar.h:358
std::vector< Motion * > children
The set of motions descending from the current motion.
Definition RRTstar.h:361
Motion * parent
The parent motion in the exploration tree.
Definition RRTstar.h:348
base::State * state
The state contained by the motion.
Definition RRTstar.h:345
bool useRejectionSampling_
The status of the sample rejection parameter.
Definition RRTstar.h:482
bool useAdmissibleCostToCome_
The admissibility of the new-state rejection heuristic.
Definition RRTstar.h:488
base::InformedSamplerPtr infSampler_
An informed sampler.
Definition RRTstar.h:429
void freeMemory()
Free the memory allocated by this planner.
Definition RRTstar.cpp:640
base::StateSamplerPtr sampler_
State sampler.
Definition RRTstar.h:426
void calculateRewiringLowerBounds()
Calculate the k_RRG* and r_RRG* terms.
Definition RRTstar.cpp:1147
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition RRTstar.cpp:144
unsigned int numSampleAttempts_
The number of attempts to make at informed sampling.
Definition RRTstar.h:491
base::Cost bestCost_
Best cost found so far by algorithm.
Definition RRTstar.h:503
bool keepCondition(const Motion *motion, const base::Cost &threshold) const
Check whether the given motion passes the specified cost threshold, meaning it will be kept during pr...
Definition RRTstar.cpp:882
double k_rrt_
A constant for k-nearest rewiring calculations.
Definition RRTstar.h:452
double pruneThreshold_
The tree is pruned when the change in solution cost is greater than this fraction.
Definition RRTstar.h:473
double rewireFactor_
The rewiring factor, s, so that r_rrt = s \times r_rrt* > r_rrt* (or k_rrt = s \times k_rrt* > k_rrt*...
Definition RRTstar.h:449
std::vector< Motion * > startMotions_
Stores the start states as Motions.
Definition RRTstar.h:500
double r_rrt_
A constant for r-disc rewiring calculations.
Definition RRTstar.h:455
void updateChildCosts(Motion *m)
Updates the cost of the children of this node if the cost up to this node has changed.
Definition RRTstar.cpp:631
unsigned int batchSize_
The size of the batches.
Definition RRTstar.h:497
bool useTreePruning_
The status of the tree pruning option.
Definition RRTstar.h:470
bool useNewStateRejection_
The status of the new-state rejection parameter.
Definition RRTstar.h:485
base::Cost prunedCost_
The cost at which the graph was last pruned.
Definition RRTstar.h:506
void removeFromParent(Motion *m)
Removes the given motion from the parent's child list.
Definition RRTstar.cpp:619
bool delayCC_
Option to delay and reduce collision checking within iterations.
Definition RRTstar.h:458
void setSampleRejection(bool reject)
Controls whether heuristic rejection is used on samples (e.g., x_rand).
Definition RRTstar.cpp:1033
void setInformedSampling(bool informedSampling)
Use direct sampling of the heuristic for the generation of random samples (e.g., x_rand)....
Definition RRTstar.cpp:985
void getNeighbors(Motion *motion, std::vector< Motion * > &nbh) const
Gets the neighbours of a given motion, using either k-nearest of radius as appropriate.
Definition RRTstar.cpp:602
bool useInformedSampling_
Option to use informed sampling.
Definition RRTstar.h:479
double prunedMeasure_
The measure of the problem when we pruned it (if this isn't in use, it will be set to si_->getSpaceMe...
Definition RRTstar.h:510
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 RRTstar.cpp:164
bool sampleUniform(base::State *statePtr)
Generate a sample.
Definition RRTstar.cpp:1126
bool useOrderedSampling_
Option to create batches of samples and order them.
Definition RRTstar.h:494
std::vector< Motion * > goalMotions_
A list of states in the tree that satisfy the goal condition.
Definition RRTstar.h:467
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition RRTstar.h:432
void setPrunedMeasure(bool informedMeasure)
Use the measure of the pruned subproblem instead of the measure of the entire problem domain (if such...
Definition RRTstar.cpp:942
void allocSampler()
Create the samplers.
Definition RRTstar.cpp:1097
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 RRTstar.cpp:655
void addChildrenToList(std::queue< Motion *, std::deque< Motion * > > *motionList, Motion *motion)
Add the children of a vertex to the given list.
Definition RRTstar.cpp:874
bool getPrunedMeasure() const
Get the state of using the pruned measure.
Definition RRTstar.h:205
RNG rng_
The random number generator.
Definition RRTstar.h:442
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition RRTstar.cpp:93
bool usePrunedMeasure_
Option to use the informed measure.
Definition RRTstar.h:476
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition RRTstar.h:439
Motion * bestGoalMotion_
The best goal motion.
Definition RRTstar.h:464
void setOrderedSampling(bool orderSamples)
Controls whether samples are returned in ordered by the heuristic. This is accomplished by generating...
Definition RRTstar.cpp:1069
base::OptimizationObjectivePtr opt_
Objective we're optimizing.
Definition RRTstar.h:461
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)...
Definition RRTstar.h:436
void setTreePruning(bool prune)
Controls whether the tree is pruned during the search. This pruning removes a vertex if and only if i...
Definition RRTstar.cpp:922
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states).
Definition RRTstar.h:389
base::Cost solutionHeuristic(const Motion *motion) const
Computes the solution cost heuristically as the cost to come from start to the motion plus the cost t...
Definition RRTstar.cpp:896
bool useKNearest_
Option to use k-nearest search for rewiring.
Definition RRTstar.h:445
unsigned int iterations_
Number of iterations the algorithm performed.
Definition RRTstar.h:513
int pruneTree(const base::Cost &pruneTreeCost)
Prunes all those states which estimated total cost is higher than pruneTreeCost. Returns the number o...
Definition RRTstar.cpp:675
This class contains methods that automatically configure various parameters for motion planning....
Definition SelfConfig.h:59
static NearestNeighbors< _T > * getDefaultNearestNeighbors(const base::Planner *planner)
Select a default nearest neighbor datastructure for the given space.
Definition SelfConfig.h:105
void configurePlannerRange(double &range)
Compute what a good length for motion segments is.
#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_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...
std::function< void(const Planner *, const std::vector< const base::State * > &, const Cost)> ReportIntermediateSolutionFn
When a planner has an intermediate solution (e.g., optimizing planners), a function with this signatu...
double unitNBallMeasure(unsigned int N)
The Lebesgue measure (i.e., "volume") of an n-dimensional ball with a unit radius.
Representation of a solution to a planning problem.
void setApproximate(double difference)
Specify that the solution is approximate and set the difference to the goal.
void setPlannerName(const std::string &name)
Set the name of the planner used to compute this solution.
void setOptimized(const OptimizationObjectivePtr &opt, Cost cost, bool meetsObjective)
Set the optimization objective used to optimize this solution, the cost of the solution and whether i...
A class to store the exit status of Planner::solve().
@ INVALID_START
Invalid start state or no start state specified.