Loading...
Searching...
No Matches
SPARSdb.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2013, Rutgers the State University of New Jersey, New Brunswick
5 * Copyright (c) 2014, University of Colorado, Boulder
6 * All Rights Reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of Rutgers University nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *********************************************************************/
35
36/* Author: Andrew Dobson, Dave Coleman */
37
38#include <ompl/base/goals/GoalSampleableRegion.h>
39#include <ompl/geometric/planners/prm/ConnectionStrategy.h>
40#include <ompl/tools/config/SelfConfig.h>
41#include <ompl/tools/thunder/SPARSdb.h>
42#include <ompl/util/Console.h>
43#include <boost/foreach.hpp>
44#include <boost/graph/astar_search.hpp>
45#include <boost/graph/incremental_components.hpp>
46#include <boost/property_map/vector_property_map.hpp>
47#include <random>
48
49// Allow hooks for visualizing planner
50// #define OMPL_THUNDER_DEBUG
51
52#define foreach BOOST_FOREACH
53#define foreach_reverse BOOST_REVERSE_FOREACH
54
55// edgeWeightMap methods ////////////////////////////////////////////////////////////////////////////
56
57BOOST_CONCEPT_ASSERT(
58 (boost::ReadablePropertyMapConcept<ompl::geometric::SPARSdb::edgeWeightMap, ompl::geometric::SPARSdb::Edge>));
59
61 : g_(graph), collisionStates_(collisionStates)
62{
63}
64
66{
67 // Get the status of collision checking for this edge
68 if (collisionStates_[e] == IN_COLLISION)
69 return std::numeric_limits<double>::infinity();
70
71 return boost::get(boost::edge_weight, g_, e);
72}
73
74namespace boost
75{
77 {
78 return m.get(e);
79 }
80} // namespace boost
81
82// CustomVisitor methods ////////////////////////////////////////////////////////////////////////////
83
84BOOST_CONCEPT_ASSERT(
85 (boost::AStarVisitorConcept<ompl::geometric::SPARSdb::CustomVisitor, ompl::geometric::SPARSdb::Graph>));
86
90
92{
93 if (u == goal)
94 throw foundGoalException();
95}
96
97// SPARSdb methods ////////////////////////////////////////////////////////////////////////////////////////
98
99ompl::geometric::SPARSdb::SPARSdb(const base::SpaceInformationPtr &si)
100 : base::Planner(si, "SPARSdb")
101 // Numeric variables
102 , nearSamplePoints_((2 * si_->getStateDimension()))
103 // Property accessors of edges
104 , edgeWeightProperty_(boost::get(boost::edge_weight, g_))
106 // Property accessors of vertices
107 , stateProperty_(boost::get(vertex_state_t(), g_))
108 , colorProperty_(boost::get(vertex_color_t(), g_))
110 // Disjoint set accessors
111 , disjointSets_(boost::get(boost::vertex_rank, g_), boost::get(boost::vertex_predecessor, g_))
112{
113 specs_.recognizedGoal = base::GOAL_SAMPLEABLE_REGION;
114 specs_.approximateSolutions = false;
115 specs_.optimizingPaths = true;
116
117 psimp_ = std::make_shared<PathSimplifier>(si_);
118
119 Planner::declareParam<double>("stretch_factor", this, &SPARSdb::setStretchFactor, &SPARSdb::getStretchFactor,
120 "1.1:0.1:3.0");
121 Planner::declareParam<double>("sparse_delta_fraction", this, &SPARSdb::setSparseDeltaFraction,
122 &SPARSdb::getSparseDeltaFraction, "0.0:0.01:1.0");
123 Planner::declareParam<double>("dense_delta_fraction", this, &SPARSdb::setDenseDeltaFraction,
124 &SPARSdb::getDenseDeltaFraction, "0.0:0.0001:0.1");
125 Planner::declareParam<unsigned int>("max_failures", this, &SPARSdb::setMaxFailures, &SPARSdb::getMaxFailures,
126 "100:10:3000");
127}
128
133
135{
136 Planner::setup();
137 if (!nn_)
139 nn_->setDistanceFunction([this](const Vertex a, const Vertex b) { return distanceFunction(a, b); });
140 double maxExt = si_->getMaximumExtent();
143
144 if (!sampler_)
145 sampler_ = si_->allocValidStateSampler();
146}
147
148void ompl::geometric::SPARSdb::setProblemDefinition(const base::ProblemDefinitionPtr &pdef)
149{
150 Planner::setProblemDefinition(pdef);
151 clearQuery();
152}
153
155{
156 startM_.clear();
157 goalM_.clear();
158 pis_.restart();
159}
160
162{
163 Planner::clear();
164 clearQuery();
166 iterations_ = 0;
167 freeMemory();
168 if (nn_)
169 nn_->clear();
170}
171
173{
174 Planner::clear();
175 sampler_.reset();
176
177 foreach (Vertex v, boost::vertices(g_))
178 {
179 foreach (InterfaceData &d, interfaceDataProperty_[v].interfaceHash | boost::adaptors::map_values)
180 d.clear(si_);
181 if (stateProperty_[v] != nullptr)
182 si_->freeState(stateProperty_[v]);
183 stateProperty_[v] = nullptr;
184 }
185 g_.clear();
186
187 if (nn_)
188 nn_->clear();
189}
190
191bool ompl::geometric::SPARSdb::getSimilarPaths(int /*nearestK*/, const base::State *start, const base::State *goal,
192 CandidateSolution &candidateSolution,
194{
195 // TODO: nearestK unused
196
197 // Get neighbors near start and goal. Note: potentially they are not *visible* - will test for this later
198
199 // Start
200 OMPL_INFORM("Looking for a node near the problem start");
202 {
203 OMPL_INFORM("No graph neighbors found for start within radius %f", sparseDelta_);
204 return false;
205 }
206 if (verbose_)
207 OMPL_INFORM("Found %d nodes near start", startVertexCandidateNeighbors_.size());
208
209 // Goal
210 OMPL_INFORM("Looking for a node near the problem goal");
211 if (!findGraphNeighbors(goal, goalVertexCandidateNeighbors_))
212 {
213 OMPL_INFORM("No graph neighbors found for goal within radius %f", sparseDelta_);
214 return false;
215 }
216 if (verbose_)
217 OMPL_INFORM("Found %d nodes near goal", goalVertexCandidateNeighbors_.size());
218
219 // Get paths between start and goal
220 bool result =
221 getPaths(startVertexCandidateNeighbors_, goalVertexCandidateNeighbors_, start, goal, candidateSolution, ptc);
222
223 // Error check
224 if (!result)
225 {
226 OMPL_INFORM("getSimilarPaths(): SPARSdb returned FALSE for getPaths");
227 return false;
228 }
229 if (!candidateSolution.path_)
230 {
231 OMPL_ERROR("getSimilarPaths(): SPARSdb returned solution is nullptr");
232 return false;
233 }
234
235 // Debug output
236 if (false)
237 {
238 ompl::geometric::PathGeometric geometricSolution =
239 static_cast<ompl::geometric::PathGeometric &>(*candidateSolution.path_);
240
241 for (std::size_t i = 0; i < geometricSolution.getStateCount(); ++i)
242 {
243 OMPL_INFORM(" getSimilarPaths(): Adding state %f to plannerData", i);
244 si_->printState(geometricSolution.getState(i), std::cout);
245 }
246 }
247
248 return result;
249}
250
251bool ompl::geometric::SPARSdb::getPaths(const std::vector<Vertex> &candidateStarts,
252 const std::vector<Vertex> &candidateGoals, const base::State *actualStart,
253 const base::State *actualGoal, CandidateSolution &candidateSolution,
255{
256 // Try every combination of nearby start and goal pairs
257 foreach (Vertex start, candidateStarts)
258 {
259 // Check if this start is visible from the actual start
260 if (!si_->checkMotion(actualStart, stateProperty_[start]))
261 {
262 if (verbose_)
263 OMPL_WARN("FOUND CANDIDATE START THAT IS NOT VISIBLE ");
264 continue; // this is actually not visible
265 }
266
267 foreach (Vertex goal, candidateGoals)
268 {
269 if (verbose_)
270 OMPL_INFORM(" foreach_goal: Checking motion from %d to %d", actualGoal, stateProperty_[goal]);
271
272 // Check if our planner is out of time
273 if (ptc == true)
274 {
275 OMPL_DEBUG("getPaths function interrupted because termination condition is true.");
276 return false;
277 }
278
279 // Check if this goal is visible from the actual goal
280 if (!si_->checkMotion(actualGoal, stateProperty_[goal]))
281 {
282 if (verbose_)
283 OMPL_INFORM("FOUND CANDIDATE GOAL THAT IS NOT VISIBLE! ");
284 continue; // this is actually not visible
285 }
286
287 // Repeatidly search through graph for connection then check for collisions then repeat
288 if (lazyCollisionSearch(start, goal, actualStart, actualGoal, candidateSolution, ptc))
289 {
290 // Found a path
291 return true;
292 }
293 else
294 {
295 // Did not find a path
296 OMPL_INFORM("Did not find a path, looking for other start/goal combinations ");
297 }
298
299 } // foreach
300 } // foreach
301
302 return false;
303}
304
306 const base::State *actualStart, const base::State *actualGoal,
307 CandidateSolution &candidateSolution,
309{
310 base::Goal *g = pdef_->getGoal().get(); // for checking isStartGoalPairValid
311
312 // Vector to store candidate paths in before they are converted to PathPtrs
313 std::vector<Vertex> vertexPath;
314
315 // decide if start and goal are connected
316 // TODO this does not compute dynamic graphcs
317 // i.e. it will say its the same components even when an edge has been disabled
318 bool same_component =
319 true; // sameComponent(start, goal); // TODO is this important? I disabled it during dev and never used it
320
321 // Check if the chosen start and goal can be used together to satisfy problem
322 if (!same_component)
323 {
324 if (verbose_)
325 OMPL_INFORM(" Goal and start are not part of same component, skipping ");
326 return false;
327 }
328
329 // TODO: remove this because start and goal are not either start nor goals
331 {
332 if (verbose_)
333 OMPL_INFORM(" Start and goal pair are not valid combinations, skipping ");
334 return false;
335 }
336
337 // Make sure that the start and goal aren't so close together that they find the same vertex
338 if (start == goal)
339 {
340 if (verbose_)
341 OMPL_INFORM(" Start equals goal, skipping ");
342 return false;
343 }
344
345 // Keep looking for paths between chosen start and goal until one is found that is valid,
346 // or no further paths can be found between them because of disabled edges
347 // this is necessary for lazy collision checking i.e. rerun after marking invalid edges we found
348 bool havePartialSolution = false;
349 while (true)
350 {
351 if (verbose_)
352 OMPL_INFORM(" while true: look for valid paths between start and goal");
353
354 // Check if our planner is out of time
355 if (ptc == true)
356 {
357 OMPL_DEBUG("lazyCollisionSearch: function interrupted because termination condition is true.");
358 return false;
359 }
360
361 // Attempt to find a solution from start to goal
362 if (!constructSolution(start, goal, vertexPath))
363 {
364 // We will stop looking through this start-goal combination, but perhaps this partial solution is good
365 if (verbose_)
366 OMPL_INFORM(" unable to construct solution between start and goal using astar");
367
368 // no solution path found. check if a previous partially correct solution was found
369 if (havePartialSolution && false) // TODO: re-implement partial solution logic
370 {
371 if (verbose_)
372 OMPL_INFORM("has partial solution ");
373 // Save this candidateSolution for later
374 convertVertexPathToStatePath(vertexPath, actualStart, actualGoal, candidateSolution);
375 return false;
376 }
377
378 if (verbose_)
379 OMPL_INFORM(" no partial solution found on this astar search, keep looking through start-goal "
380 "combos");
381
382 // no path found what so ever
383 // return false;
384 return false;
385 }
386 havePartialSolution = true; // we have found at least one path at this point. may be invalid
387
388 if (verbose_)
389 {
390 OMPL_INFORM(" has at least a partial solution, maybe exact solution");
391 OMPL_INFORM(" Solution has %d vertices", vertexPath.size());
392 }
393
394 // Check if all the points in the potential solution are valid
395 if (lazyCollisionCheck(vertexPath, ptc))
396 {
397 if (verbose_)
398 {
399 OMPL_INFORM("---------- lazy collision check returned valid ");
400 }
401
402 // the path is valid, we are done!
403 convertVertexPathToStatePath(vertexPath, actualStart, actualGoal, candidateSolution);
404 return true;
405 }
406 // else, loop with updated graph that has the invalid edges/states disabled
407 } // while
408
409 // we never found a valid path
410 return false;
411}
412
414 std::vector<Vertex> &vertexPath) const
415{
416 auto *vertexPredecessors = new Vertex[boost::num_vertices(g_)];
417 bool foundGoal = false;
418
419 auto *vertexDistances = new double[boost::num_vertices(g_)];
420
421 try
422 {
423 boost::astar_search(
424 g_, // graph
425 start, // start state
426 [this, goal](const Vertex v) { return distanceFunction(v, goal); }, // the heuristic
427 // ability to disable edges (set cost to inifinity):
428 boost::weight_map(edgeWeightMap(g_, edgeCollisionStateProperty_))
429 .predecessor_map(vertexPredecessors)
430 .distance_map(&vertexDistances[0])
431 .visitor(CustomVisitor(goal)));
432 }
434 {
435 // the custom exception from CustomVisitor
436 if (verbose_ && false)
437 {
438 OMPL_INFORM("constructSolution: Astar found goal vertex ------------------------");
439 OMPL_INFORM("distance to goal: %f", vertexDistances[goal]);
440 }
441
442 if (vertexDistances[goal] > 1.7e+308) // terrible hack for detecting infinity
443 // double diff = d[goal] - std::numeric_limits<double>::infinity();
444 // if ((diff < std::numeric_limits<double>::epsilon()) && (-diff < std::numeric_limits<double>::epsilon()))
445 // check if the distance to goal is inifinity. if so, it is unreachable
446 // if (d[goal] >= std::numeric_limits<double>::infinity())
447 {
448 if (verbose_)
449 OMPL_INFORM("Distance to goal is infinity");
450 foundGoal = false;
451 }
452 else
453 {
454 // Only clear the vertexPath after we know we have a new solution, otherwise it might have a good
455 // previous one
456 vertexPath.clear(); // remove any old solutions
457
458 // Trace back a shortest path in reverse and only save the states
459 Vertex v;
460 for (v = goal; v != vertexPredecessors[v]; v = vertexPredecessors[v])
461 {
462 vertexPath.push_back(v);
463 }
464 if (v != goal) // TODO explain this because i don't understand
465 {
466 vertexPath.push_back(v);
467 }
468
469 foundGoal = true;
470 }
471 }
472
473 delete[] vertexPredecessors;
474 delete[] vertexDistances;
475
476 // No solution found from start to goal
477 return foundGoal;
478}
479
480bool ompl::geometric::SPARSdb::lazyCollisionCheck(std::vector<Vertex> &vertexPath,
482{
483 OMPL_DEBUG("Starting lazy collision checking");
484
485 bool hasInvalidEdges = false;
486
487 // Initialize
488 Vertex fromVertex = vertexPath[0];
489 Vertex toVertex;
490
491 // Loop through every pair of states and make sure path is valid.
492 for (std::size_t toID = 1; toID < vertexPath.size(); ++toID)
493 {
494 // Increment location on path
495 toVertex = vertexPath[toID];
496
497 // Check if our planner is out of time
498 if (ptc == true)
499 {
500 OMPL_DEBUG("Lazy collision check function interrupted because termination condition is true.");
501 return false;
502 }
503
504 Edge thisEdge = boost::edge(fromVertex, toVertex, g_).first;
505
506 // Has this edge already been checked before?
507 if (edgeCollisionStateProperty_[thisEdge] == NOT_CHECKED)
508 {
509 // Check path between states
510 if (!si_->checkMotion(stateProperty_[fromVertex], stateProperty_[toVertex]))
511 {
512 // Path between (from, to) states not valid, disable the edge
513 OMPL_INFORM(" DISABLING EDGE from vertex %f to vertex %f", fromVertex, toVertex);
514
515 // Disable edge
516 edgeCollisionStateProperty_[thisEdge] = IN_COLLISION;
517 }
518 else
519 {
520 // Mark edge as free so we no longer need to check for collision
521 edgeCollisionStateProperty_[thisEdge] = FREE;
522 }
523 }
524
525 // Check final result
526 if (edgeCollisionStateProperty_[thisEdge] == IN_COLLISION)
527 {
528 // Remember that this path is no longer valid, but keep checking remainder of path edges
529 hasInvalidEdges = true;
530 }
531
532 // switch vertex focus
533 fromVertex = toVertex;
534 }
535
536 OMPL_INFORM("Done lazy collision checking");
537
538 // TODO: somewhere in the code we need to reset all edges collision status back to NOT_CHECKED for future queries
539
540 // Only return true if nothing was found invalid
541 return !hasInvalidEdges;
542}
543
545{
546 return boost::same_component(m1, m2, disjointSets_);
547}
548
553
554void ompl::geometric::SPARSdb::printDebug(std::ostream &out) const
555{
556 out << "SPARSdb Debug Output: " << std::endl;
557 out << " Settings: " << std::endl;
558 out << " Max Failures: " << getMaxFailures() << std::endl;
559 out << " Dense Delta Fraction: " << getDenseDeltaFraction() << std::endl;
560 out << " Sparse Delta Fraction: " << getSparseDeltaFraction() << std::endl;
561 out << " Sparse Delta: " << sparseDelta_ << std::endl;
562 out << " Stretch Factor: " << getStretchFactor() << std::endl;
563 out << " Maximum Extent: " << si_->getMaximumExtent() << std::endl;
564 out << " Status: " << std::endl;
565 out << " Vertices Count: " << getNumVertices() << std::endl;
566 out << " Edges Count: " << getNumEdges() << std::endl;
567 out << " Iterations: " << getIterations() << std::endl;
568 out << " Consecutive Failures: " << consecutiveFailures_ << std::endl;
569 out << " Number of guards: " << nn_->size() << std::endl << std::endl;
570}
571
572bool ompl::geometric::SPARSdb::getGuardSpacingFactor(const double pathLength, int &numGuards, double &spacingFactor)
573{
574 static const double factorHigh = 1.9;
575 static const double factorLow = 1.1;
576 double minPathLength = sparseDelta_ * factorLow;
577
578 // Check if the path length is too short
579 if (pathLength < minPathLength)
580 {
581 OMPL_INFORM("Path length is too short to get a correct sparcing factor: length: %f, min: %f ", pathLength,
582 minPathLength);
583 spacingFactor = factorLow;
584 return true; // still attempt
585 }
586
587 // Get initial guess using med value
588 double numGuardsFraction = pathLength / (sparseDelta_ * factorLow);
589 if (verbose_)
590 {
591 OMPL_INFORM("getGuardSpacingFactor: ");
592 OMPL_INFORM(" pathLength: %f", pathLength);
593 OMPL_INFORM(" sparseDelta: %f", sparseDelta_);
594 OMPL_INFORM(" min pathLength: %f", minPathLength);
595 OMPL_INFORM(" numGuardsFraction: %f", numGuardsFraction);
596 }
597
598 // Round down to nearest integer
599 numGuards = numGuardsFraction;
600
601 static std::size_t MAX_ATTEMPTS = 4;
602 for (std::size_t i = 0; i < MAX_ATTEMPTS; ++i)
603 {
604 if (verbose_)
605 OMPL_INFORM(" numGuards: %d", numGuards);
606
607 // Find the factor to achieve this number of guards
608 spacingFactor = pathLength / (sparseDelta_ * numGuards);
609 if (verbose_)
610 OMPL_INFORM(" new spacingFactor: %f", spacingFactor);
611
612 // Check if this factor is too low
613 if (spacingFactor < factorLow)
614 {
615 if (verbose_)
616 OMPL_INFORM(" spacing factor is too low ");
617 numGuards++;
618 continue;
619 }
620 else if (spacingFactor > factorHigh)
621 {
622 if (verbose_)
623 OMPL_INFORM(" spacing factor is too high ");
624 numGuards--;
625 continue;
626 }
627 else
628 return true; // a good value
629 }
630
631 OMPL_ERROR("Unable to find correct spacing factor - perhaps this is a bug");
632 spacingFactor = factorLow;
633 return true; // still attempt
634}
635
636bool ompl::geometric::SPARSdb::addPathToRoadmap(const base::PlannerTerminationCondition &ptc,
637 ompl::geometric::PathGeometric &solutionPath)
638{
639 // Check that the query vertex is initialized (used for internal nearest neighbor searches)
640 checkQueryStateInitialization();
641
642 // Error check
643 if (solutionPath.getStateCount() < 2)
644 {
645 OMPL_ERROR("Less than 2 states were passed to addPathToRoadmap in the solution path");
646 return false;
647 }
648
649 // Find spacing factor - 2.0 would be a perfect amount, but we leave room for rounding/interpolation errors and
650 // curves in path
651 int numGuards; // unused variable that indicates how many guards we will add
652 double spacingFactor;
653 if (!getGuardSpacingFactor(solutionPath.length(), numGuards, spacingFactor))
654 return false;
655
656 OMPL_DEBUG("Expected number of necessary coverage guards is calculated to be %i from the original path state count "
657 "%i",
658 numGuards, solutionPath.getStateCount());
659
660 unsigned int n = 0;
661 const int n1 = solutionPath.getStateCount() - 1;
662 for (int i = 0; i < n1; ++i)
663 n += si_->getStateSpace()->validSegmentCount(solutionPath.getState(i), solutionPath.getState(i + 1));
664
665 solutionPath.interpolate(n);
666
667 // Debug
668 if (verbose_)
669 {
670 OMPL_INFORM("-------------------------------------------------------");
671 OMPL_INFORM("Attempting to add %d states to roadmap", solutionPath.getStateCount());
672 OMPL_INFORM("-------------------------------------------------------");
673 }
674
675 // Try to add the start first, but don't force it
676 addStateToRoadmap(ptc, solutionPath.getState(0));
677
678#ifdef OMPL_THUNDER_DEBUG
679 visualizeStateCallback(solutionPath.getState(solutionPath.getStateCount() - 1), 3, sparseDelta_);
680#endif
681
682 // Add solution states to SPARSdb one by one ---------------------------
683
684 // Track which nodes we've already tried to add
685 std::vector<std::size_t> addedStateIDs;
686 // Track which nodes we will attempt to use as connectivity states
687 std::vector<std::size_t> connectivityStateIDs;
688 // std::vector<base::State*> connectivityStates;
689
690 double distanceFromLastState = 0;
691
692 std::size_t lastStateID = 0; // track the id in the solutionPath of the last state
693
694 for (std::size_t i = 1; i < solutionPath.getStateCount();
695 ++i) // skip 0 and last because those are start/goal and are already added
696 {
697 distanceFromLastState = si_->distance(solutionPath.getState(i), solutionPath.getState(lastStateID));
698
699 if (verbose_ && false)
700 {
701 OMPL_INFORM("Index %d at distance %f from last state ", i, distanceFromLastState);
702 }
703
704 if (distanceFromLastState >= sparseDelta_ * spacingFactor)
705 {
706 if (verbose_)
707 {
708 OMPL_INFORM("Adding state %d of %d", i, solutionPath.getStateCount());
709 }
710
711// Show the candidate state in Rviz for path insertion of GUARDS
712#ifdef OMPL_THUNDER_DEBUG
713 visualizeStateCallback(solutionPath.getState(i), 1, sparseDelta_);
714#endif
715
716 // Add a single state to the roadmap
717 if (!addStateToRoadmap(ptc, solutionPath.getState(i)))
718 {
719 if (verbose_)
720 {
721 OMPL_INFORM("Last state added to roadmap failed ");
722 }
723 }
724
725 // Now figure out midpoint state between lastState and i
726 std::size_t midStateID = (i - lastStateID) / 2 + lastStateID;
727 connectivityStateIDs.push_back(midStateID);
728
729 double distA = si_->distance(solutionPath.getState(lastStateID), solutionPath.getState(midStateID));
730 double distB = si_->distance(solutionPath.getState(i), solutionPath.getState(midStateID));
731 double diff = distA - distB;
732 if ((diff < std::numeric_limits<double>::epsilon()) && (-diff < std::numeric_limits<double>::epsilon()))
733 if (verbose_)
734 OMPL_WARN("DISTANCES ARE DIFFERENT ");
735
736 // Save this state as the new last state
737 lastStateID = i;
738 // Remember which nodes we've already added / attempted to add
739 addedStateIDs.push_back(midStateID);
740 addedStateIDs.push_back(i);
741 }
742 // Close up if it doesn't do it automatically
743 else if (i == solutionPath.getStateCount() - 1)
744 {
745 if (verbose_)
746 OMPL_INFORM("Last state - do special midpoint");
747
748 // Now figure out midpoint state between lastState and i
749 std::size_t midStateID = (i - lastStateID) / 2 + lastStateID;
750 connectivityStateIDs.push_back(midStateID);
751 addedStateIDs.push_back(midStateID);
752 if (verbose_)
753 OMPL_INFORM("Mid state is %d", midStateID);
754 }
755 }
756
757 // Attempt to add the goal directly
758 addStateToRoadmap(ptc, solutionPath.getState(solutionPath.getStateCount() - 1));
759
760 if (verbose_)
761 {
762 OMPL_INFORM("-------------------------------------------------------");
763 OMPL_INFORM("-------------------------------------------------------");
764 OMPL_INFORM("Adding connectivity states ----------------------------");
765 OMPL_INFORM("-------------------------------------------------------");
766 OMPL_INFORM("-------------------------------------------------------");
767 }
768
769 for (std::size_t i = 0; i < connectivityStateIDs.size(); ++i)
770 {
771 base::State *connectivityState = solutionPath.getState(connectivityStateIDs[i]);
772
773 if (verbose_)
774 {
775 OMPL_INFORM("Adding connectvity state ", i);
776 }
777
778#ifdef OMPL_THUNDER_DEBUG
779 // Show the candidate state in Rviz for path insertion of BRIDGES (CONNECTIVITY)
780 visualizeStateCallback(connectivityState, 2, sparseDelta_);
781 sleep(0.5);
782#endif
783
784 // Add a single state to the roadmap
785 addStateToRoadmap(ptc, connectivityState);
786 }
787
788 // Add remaining states at random
789 if (verbose_)
790 {
791 OMPL_INFORM("-------------------------------------------------------");
792 OMPL_INFORM("-------------------------------------------------------");
793 OMPL_INFORM("Adding remaining states randomly ----------------------");
794 OMPL_INFORM("-------------------------------------------------------");
795 OMPL_INFORM("-------------------------------------------------------");
796 }
797
798 // Create a vector of shuffled indexes
799 std::vector<std::size_t> shuffledIDs;
800 std::size_t usedIDTracker = 0;
801 for (std::size_t i = 1; i < solutionPath.getStateCount(); ++i) // skip 0 because start already added
802 {
803 // Check if we've already used this id
804 if (usedIDTracker < addedStateIDs.size() && i == addedStateIDs[usedIDTracker])
805 {
806 // skip this id
807 usedIDTracker++;
808 continue;
809 }
810
811 shuffledIDs.push_back(i); // 1 2 3...
812 }
813
814 std::shuffle(shuffledIDs.begin(), shuffledIDs.end(), std::mt19937(std::random_device()()));
815
816 // Add each state randomly
817 for (unsigned long shuffledID : shuffledIDs)
818 {
819#ifdef OMPL_THUNDER_DEBUG
820 visualizeStateCallback(solutionPath.getState(shuffledIDs[i]), 1, sparseDelta_);
821#endif
822
823 // Add a single state to the roadmap
824 addStateToRoadmap(ptc, solutionPath.getState(shuffledID));
825 }
826
827 bool benchmarkLogging = true;
828 if (benchmarkLogging)
829 {
830 OMPL_DEBUG("ompl::geometric::SPARSdb: Benchmark logging enabled (slower)");
831
832 // Return the result of inserting into database, if applicable
833 return checkStartGoalConnection(solutionPath);
834 }
835
836 return true;
837}
838
839bool ompl::geometric::SPARSdb::checkStartGoalConnection(ompl::geometric::PathGeometric &solutionPath)
840{
841 // Make sure path has states
842 if (solutionPath.getStateCount() < 2)
843 {
844 OMPL_ERROR("Not enough states (< 2) in the solutionPath");
845 return false;
846 }
847
848 bool error = false;
849 CandidateSolution candidateSolution;
850 do
851 {
852 base::State *actualStart = solutionPath.getState(0);
853 base::State *actualGoal = solutionPath.getState(solutionPath.getStateCount() - 1);
854
855 /* The whole neighborhood set which has been most recently computed */
856 std::vector<Vertex> graphNeighborhood;
857 /* The visible neighborhood set which has been most recently computed */
858 std::vector<Vertex> visibleNeighborhood;
859
860 // Get start vertex
861 findGraphNeighbors(actualStart, graphNeighborhood, visibleNeighborhood);
862 if (!visibleNeighborhood.size())
863 {
864 OMPL_ERROR("No vertexes found near start");
865 error = true;
866 break;
867 }
868 Vertex closeStart = visibleNeighborhood[0];
869
870 // Get goal vertex
871 findGraphNeighbors(actualGoal, graphNeighborhood, visibleNeighborhood);
872 if (!visibleNeighborhood.size())
873 {
874 OMPL_ERROR("No vertexes found near goal");
875 error = true;
876 break;
877 }
878 Vertex closeGoal = visibleNeighborhood[0];
879
880 // Check if connected
881 if (false)
882 if (!sameComponent(closeStart, closeGoal))
883 {
884 OMPL_ERROR("Start and goal are not connected!");
885 error = true;
886 break;
887 }
888
889 // Get new path from start to goal
890 std::vector<Vertex> vertexPath;
891 if (!constructSolution(closeStart, closeGoal, vertexPath))
892 {
893 OMPL_ERROR("Unable to find path from start to goal - perhaps because of new obstacles");
894 error = true;
895 break;
896 }
897
898 // Convert to PathGeometric
899 bool disableCollisionWarning = true; // this is just for benchmarking purposes
900 if (!convertVertexPathToStatePath(vertexPath, actualStart, actualGoal, candidateSolution,
901 disableCollisionWarning))
902 {
903 OMPL_ERROR("Unable to convert to state path");
904 error = true;
905 break;
906 }
907 } while (false);
908
909 // Check distance of new path from old path
910 double originalLength = solutionPath.length();
911
912 OMPL_DEBUG("Results of attempting to make insertion in SPARSdb ");
913 OMPL_DEBUG("-------------------------------------------------------");
914 OMPL_DEBUG("Original length: %f", originalLength);
915
916 if (error)
917 {
918 OMPL_ERROR("UNABLE TO GET PATH");
919
920 // Record this for plotting
921 numPathInsertionFailures_++;
922 }
923 else
924 {
925 double newLength = candidateSolution.getGeometricPath().length();
926 double percentIncrease = 100 - originalLength / newLength * 100;
927 OMPL_DEBUG("New length: %f", newLength);
928 OMPL_DEBUG("Percent increase: %f %%", percentIncrease);
929 }
930
931 return !error; // return true if it inserted correctly
932}
933
934bool ompl::geometric::SPARSdb::addStateToRoadmap(const base::PlannerTerminationCondition &ptc, base::State *newState)
935{
936 bool stateAdded = false;
937 // Check that the query vertex is initialized (used for internal nearest neighbor searches)
938 checkQueryStateInitialization();
939
940 // Deep copy
941 base::State *qNew = si_->cloneState(newState);
942 base::State *workState = si_->allocState();
943
944 /* The whole neighborhood set which has been most recently computed */
945 std::vector<Vertex> graphNeighborhood;
946 /* The visible neighborhood set which has been most recently computed */
947 std::vector<Vertex> visibleNeighborhood;
948
949 ++iterations_;
950
951 findGraphNeighbors(qNew, graphNeighborhood, visibleNeighborhood);
952
953 if (verbose_)
954 {
955 OMPL_INFORM(" graph neighborhood: %d | visible neighborhood: %d", graphNeighborhood.size(),
956 visibleNeighborhood.size());
957
958 foreach (Vertex v, visibleNeighborhood)
959 {
960 OMPL_INFORM("Visible neighbor is vertex %f with distance %f ", v, si_->distance(qNew, stateProperty_[v]));
961 }
962 }
963
964 if (verbose_)
965 OMPL_INFORM(" - checkAddCoverage() Are other nodes around it visible?");
966 // Coverage criterion
967 if (!checkAddCoverage(qNew,
968 visibleNeighborhood)) // Always add a node if no other nodes around it are visible (GUARD)
969 {
970 if (verbose_)
971 OMPL_INFORM(" -- checkAddConnectivity() Does this node connect neighboring nodes that are not connected? ");
972 // Connectivity criterion
973 if (!checkAddConnectivity(qNew, visibleNeighborhood))
974 {
975 if (verbose_)
976 OMPL_INFORM(" --- checkAddInterface() Does this node's neighbor's need it to better connect them? ");
977 if (!checkAddInterface(qNew, graphNeighborhood, visibleNeighborhood))
978 {
979 if (verbose_)
980 OMPL_INFORM(" ---- Ensure SPARS asymptotic optimality");
981 if (visibleNeighborhood.size() > 0)
982 {
983 std::map<Vertex, base::State *> closeRepresentatives;
984 if (verbose_)
985 OMPL_INFORM(" ----- findCloseRepresentatives()");
986
987 findCloseRepresentatives(workState, qNew, visibleNeighborhood[0], closeRepresentatives, ptc);
988 if (verbose_)
989 OMPL_INFORM("------ Found %d close representatives", closeRepresentatives.size());
990
991 for (auto &closeRepresentative : closeRepresentatives)
992 {
993 if (verbose_)
994 OMPL_INFORM(" ------ Looping through close representatives");
995 updatePairPoints(visibleNeighborhood[0], qNew, closeRepresentative.first,
996 closeRepresentative.second);
997 updatePairPoints(closeRepresentative.first, closeRepresentative.second, visibleNeighborhood[0],
998 qNew);
999 }
1000 if (verbose_)
1001 OMPL_INFORM(" ------ checkAddPath()");
1002 if (checkAddPath(visibleNeighborhood[0]))
1003 {
1004 if (verbose_)
1005 {
1006 OMPL_INFORM("nearest visible neighbor added ");
1007 }
1008 }
1009
1010 for (auto &closeRepresentative : closeRepresentatives)
1011 {
1012 if (verbose_)
1013 OMPL_INFORM(" ------- Looping through close representatives to add path");
1014 checkAddPath(closeRepresentative.first);
1015 si_->freeState(closeRepresentative.second);
1016 }
1017 if (verbose_)
1018 OMPL_INFORM("------ Done with inner most loop ");
1019 }
1020 }
1021 else // added for interface
1022 {
1023 stateAdded = true;
1024 }
1025 }
1026 else // added for connectivity
1027 {
1028 stateAdded = true;
1029 }
1030 }
1031 else // added for coverage
1032 {
1033 stateAdded = true;
1034 }
1035
1036 if (!stateAdded)
1037 ++consecutiveFailures_;
1038
1039 si_->freeState(workState);
1040 si_->freeState(qNew);
1041
1042 return stateAdded;
1043}
1044
1046{
1047 if (boost::num_vertices(g_) < 1)
1048 {
1049 queryVertex_ = boost::add_vertex(g_);
1050 stateProperty_[queryVertex_] = nullptr;
1051 }
1052}
1053
1059
1060bool ompl::geometric::SPARSdb::checkAddCoverage(const base::State *qNew, std::vector<Vertex> &visibleNeighborhood)
1061{
1062 if (visibleNeighborhood.size() > 0)
1063 return false;
1064 // No free paths means we add for coverage
1065 if (verbose_)
1066 OMPL_INFORM(" --- Adding node for COVERAGE ");
1067 Vertex v = addGuard(si_->cloneState(qNew), COVERAGE);
1068 if (verbose_)
1069 OMPL_INFORM(" Added vertex %f", v);
1070
1071 return true;
1072}
1073
1074bool ompl::geometric::SPARSdb::checkAddConnectivity(const base::State *qNew, std::vector<Vertex> &visibleNeighborhood)
1075{
1076 // Identify visibile nodes around our new state that are unconnected (in different connected components)
1077 // and connect them
1078
1079 std::vector<Vertex> statesInDiffConnectedComponents; // links
1080 if (visibleNeighborhood.size() > 1) // if less than 2 there is no way to find a pair of nodes in different
1081 // connected components
1082 {
1083 // For each neighbor
1084 for (std::size_t i = 0; i < visibleNeighborhood.size(); ++i)
1085 {
1086 // For each other neighbor
1087 for (std::size_t j = i + 1; j < visibleNeighborhood.size(); ++j)
1088 {
1089 // If they are in different components
1090 if (!sameComponent(visibleNeighborhood[i], visibleNeighborhood[j]))
1091 {
1092 statesInDiffConnectedComponents.push_back(visibleNeighborhood[i]);
1093 statesInDiffConnectedComponents.push_back(visibleNeighborhood[j]);
1094 }
1095 }
1096 }
1097
1098 // Were any diconnected states found?
1099 if (statesInDiffConnectedComponents.size() > 0)
1100 {
1101 if (verbose_)
1102 OMPL_INFORM(" --- Adding node for CONNECTIVITY ");
1103 // Add the node
1104 Vertex newVertex = addGuard(si_->cloneState(qNew), CONNECTIVITY);
1105
1106 for (unsigned long statesInDiffConnectedComponent : statesInDiffConnectedComponents)
1107 {
1108 // If there's no edge between the two new states
1109 // DTC: this should actually never happen - we just created the new vertex so
1110 // why would it be connected to anything?
1111 if (!boost::edge(newVertex, statesInDiffConnectedComponent, g_).second)
1112 {
1113 // The components haven't been united by previous links
1114 if (!sameComponent(statesInDiffConnectedComponent, newVertex))
1115 connectGuards(newVertex, statesInDiffConnectedComponent);
1116 }
1117 }
1118
1119 return true;
1120 }
1121 }
1122 return false;
1123}
1124
1125bool ompl::geometric::SPARSdb::checkAddInterface(const base::State *qNew, std::vector<Vertex> &graphNeighborhood,
1126 std::vector<Vertex> &visibleNeighborhood)
1127{
1128 // If we have at least 2 neighbors
1129 if (visibleNeighborhood.size() > 1)
1130 {
1131 // If the two closest nodes are also visible
1132 if (graphNeighborhood[0] == visibleNeighborhood[0] && graphNeighborhood[1] == visibleNeighborhood[1])
1133 {
1134 // If our two closest neighbors don't share an edge
1135 if (!boost::edge(visibleNeighborhood[0], visibleNeighborhood[1], g_).second)
1136 {
1137 // If they can be directly connected
1138 if (si_->checkMotion(stateProperty_[visibleNeighborhood[0]], stateProperty_[visibleNeighborhood[1]]))
1139 {
1140 // Connect them
1141 if (verbose_)
1142 OMPL_INFORM(" --- INTERFACE: directly connected nodes ");
1143 connectGuards(visibleNeighborhood[0], visibleNeighborhood[1]);
1144 // And report that we added to the roadmap
1145 resetFailures();
1146 // Report success
1147 return true;
1148 }
1149 else
1150 {
1151 // Add the new node to the graph, to bridge the interface
1152 if (verbose_)
1153 OMPL_INFORM(" --- Adding node for INTERFACE ");
1154 Vertex v = addGuard(si_->cloneState(qNew), INTERFACE);
1155 connectGuards(v, visibleNeighborhood[0]);
1156 connectGuards(v, visibleNeighborhood[1]);
1157 if (verbose_)
1158 OMPL_INFORM(" --- INTERFACE: connected two neighbors through new interface node ");
1159 // Report success
1160 return true;
1161 }
1162 }
1163 }
1164 }
1165 return false;
1166}
1167
1169{
1170 bool spannerPropertyWasViolated = false;
1171
1172 std::vector<Vertex> rs;
1173 foreach (Vertex r, boost::adjacent_vertices(v, g_))
1174 rs.push_back(r);
1175
1176 /* Candidate x vertices as described in the method, filled by function computeX(). */
1177 std::vector<Vertex> Xs;
1178
1179 /* Candidate v" vertices as described in the method, filled by function computeVPP(). */
1180 std::vector<Vertex> VPPs;
1181
1182 for (std::size_t i = 0; i < rs.size() && !spannerPropertyWasViolated; ++i)
1183 {
1184 Vertex r = rs[i];
1185 computeVPP(v, r, VPPs);
1186 foreach (Vertex rp, VPPs)
1187 {
1188 // First, compute the longest path through the graph
1189 computeX(v, r, rp, Xs);
1190 double rm_dist = 0.0;
1191 foreach (Vertex rpp, Xs)
1192 {
1193 double tmp_dist = (si_->distance(stateProperty_[r], stateProperty_[v]) +
1194 si_->distance(stateProperty_[v], stateProperty_[rpp])) /
1195 2.0;
1196 if (tmp_dist > rm_dist)
1197 rm_dist = tmp_dist;
1198 }
1199
1200 InterfaceData &d = getData(v, r, rp);
1201
1202 // Then, if the spanner property is violated
1203 if (rm_dist > stretchFactor_ * d.d_)
1204 {
1205 spannerPropertyWasViolated = true; // Report that we added for the path
1206 if (si_->checkMotion(stateProperty_[r], stateProperty_[rp]))
1207 connectGuards(r, rp);
1208 else
1209 {
1210 auto p(std::make_shared<PathGeometric>(si_));
1211 if (r < rp)
1212 {
1213 p->append(d.sigmaA_);
1214 p->append(d.pointA_);
1215 p->append(stateProperty_[v]);
1216 p->append(d.pointB_);
1217 p->append(d.sigmaB_);
1218 }
1219 else
1220 {
1221 p->append(d.sigmaB_);
1222 p->append(d.pointB_);
1223 p->append(stateProperty_[v]);
1224 p->append(d.pointA_);
1225 p->append(d.sigmaA_);
1226 }
1227
1228 psimp_->reduceVertices(*p, 10);
1229 psimp_->partialShortcutPath(*p, 50);
1230
1231 if (p->checkAndRepair(100).second)
1232 {
1233 Vertex prior = r;
1234 Vertex vnew;
1235 std::vector<base::State *> &states = p->getStates();
1236
1237 foreach (base::State *st, states)
1238 {
1239 // no need to clone st, since we will destroy p; we just copy the pointer
1240 if (verbose_)
1241 OMPL_INFORM(" --- Adding node for QUALITY");
1242 vnew = addGuard(st, QUALITY);
1243
1244 connectGuards(prior, vnew);
1245 prior = vnew;
1246 }
1247 // clear the states, so memory is not freed twice
1248 states.clear();
1249 connectGuards(prior, rp);
1250 }
1251 }
1252 }
1253 }
1254 }
1255
1256 if (!spannerPropertyWasViolated)
1257 {
1258 if (verbose_)
1259 {
1260 OMPL_INFORM(" ------- Spanner property was NOT violated, SKIPPING");
1261 }
1262 }
1263
1264 return spannerPropertyWasViolated;
1265}
1266
1271
1272void ompl::geometric::SPARSdb::findGraphNeighbors(base::State *st, std::vector<Vertex> &graphNeighborhood,
1273 std::vector<Vertex> &visibleNeighborhood)
1274{
1275 visibleNeighborhood.clear();
1277 nn_->nearestR(queryVertex_, sparseDelta_, graphNeighborhood);
1278 if (verbose_ && false)
1279 OMPL_INFORM("Finding nearest nodes in NN tree within radius %f", sparseDelta_);
1280 stateProperty_[queryVertex_] = nullptr;
1281
1282 // Now that we got the neighbors from the NN, we must remove any we can't see
1283 for (unsigned long i : graphNeighborhood)
1284 if (si_->checkMotion(st, stateProperty_[i]))
1285 visibleNeighborhood.push_back(i);
1286}
1287
1288bool ompl::geometric::SPARSdb::findGraphNeighbors(const base::State *state, std::vector<Vertex> &graphNeighborhood)
1289{
1290 base::State *stateCopy = si_->cloneState(state);
1291
1292 // Don't check for visibility
1293 graphNeighborhood.clear();
1294 stateProperty_[queryVertex_] = stateCopy;
1295
1296 // Double the range of sparseDelta_ up to 3 times until at least 1 neighbor is found
1297 std::size_t expandNeighborhoodSearchAttempts = 3;
1298 double neighborSearchRadius;
1299 static const double EXPAND_NEIGHBORHOOD_RATE =
1300 0.25; // speed to which we look outside the original sparse delta neighborhood
1301 for (std::size_t i = 0; i < expandNeighborhoodSearchAttempts; ++i)
1302 {
1303 neighborSearchRadius = sparseDelta_ + i * EXPAND_NEIGHBORHOOD_RATE * sparseDelta_;
1304 if (verbose_)
1305 {
1306 OMPL_INFORM("-------------------------------------------------------");
1307 OMPL_INFORM("Attempt %d to find neighborhood at radius %f", i + 1, neighborSearchRadius);
1308 OMPL_INFORM("-------------------------------------------------------");
1309 }
1310
1311 nn_->nearestR(queryVertex_, neighborSearchRadius, graphNeighborhood);
1312
1313 // Check if at least one neighbor found
1314 if (graphNeighborhood.size() > 0)
1315 break;
1316 }
1317 stateProperty_[queryVertex_] = nullptr;
1318
1319 // Check if no neighbors found
1320 if (!graphNeighborhood.size())
1321 {
1322 return false;
1323 }
1324 return true;
1325}
1326
1328{
1329 std::vector<Vertex> hold;
1330 nn_->nearestR(v, sparseDelta_, hold);
1331
1332 std::vector<Vertex> neigh;
1333 for (unsigned long i : hold)
1334 if (si_->checkMotion(stateProperty_[v], stateProperty_[i]))
1335 neigh.push_back(i);
1336
1337 foreach (Vertex vp, neigh)
1338 connectGuards(v, vp);
1339}
1340
1342{
1343 std::vector<Vertex> nbh;
1345 nn_->nearestR(queryVertex_, sparseDelta_, nbh);
1346 stateProperty_[queryVertex_] = nullptr;
1347
1348 if (verbose_)
1349 OMPL_INFORM(" ------- findGraphRepresentative found %d nearest neighbors of distance %f", nbh.size(),
1350 sparseDelta_);
1351
1352 Vertex result = boost::graph_traits<Graph>::null_vertex();
1353
1354 for (std::size_t i = 0; i < nbh.size(); ++i)
1355 {
1356 if (verbose_)
1357 OMPL_INFORM(" -------- Checking motion of graph rep candidate %d", i);
1358 if (si_->checkMotion(st, stateProperty_[nbh[i]]))
1359 {
1360 if (verbose_)
1361 OMPL_INFORM(" --------- VALID ");
1362 result = nbh[i];
1363 break;
1364 }
1365 }
1366 return result;
1367}
1368
1370 const Vertex qRep,
1371 std::map<Vertex, base::State *> &closeRepresentatives,
1373{
1374 // Properly clear the vector by also deleting previously sampled unused states
1375 for (auto &closeRepresentative : closeRepresentatives)
1376 si_->freeState(closeRepresentative.second);
1377 closeRepresentatives.clear();
1378
1379 // denseDelta_ = 0.25 * sparseDelta_;
1380 nearSamplePoints_ /= 10; // HACK - this makes it look for the same number of samples as dimensions
1381
1382 if (verbose_)
1383 OMPL_INFORM(" ----- nearSamplePoints: %f, denseDelta: %f", nearSamplePoints_, denseDelta_);
1384
1385 // Then, begin searching the space around new potential state qNew
1386 for (unsigned int i = 0; i < nearSamplePoints_ && ptc == false; ++i)
1387 {
1388 do
1389 {
1390 sampler_->sampleNear(workState, qNew, denseDelta_);
1391
1392#ifdef OMPL_THUNDER_DEBUG
1393 visualizeStateCallback(workState, 3, sparseDelta_);
1394 sleep(0.1);
1395#endif
1396
1397 if (verbose_)
1398 {
1399 OMPL_INFORM(" ------ findCloseRepresentatives sampled state ");
1400
1401 if (!si_->isValid(workState))
1402 {
1403 OMPL_INFORM(" ------ isValid ");
1404 }
1405 if (si_->distance(qNew, workState) > denseDelta_)
1406 {
1407 OMPL_INFORM(" ------ Distance too far ");
1408 }
1409 if (!si_->checkMotion(qNew, workState))
1410 {
1411 OMPL_INFORM(" ------ Motion invalid ");
1412 }
1413 }
1414
1415 } while ((!si_->isValid(workState) || si_->distance(qNew, workState) > denseDelta_ ||
1416 !si_->checkMotion(qNew, workState)) &&
1417 ptc == false);
1418
1419 // if we were not successful at sampling a desirable state, we are out of time
1420 if (ptc == true)
1421 {
1422 if (verbose_)
1423 OMPL_INFORM(" ------ We are out of time ");
1424 break;
1425 }
1426
1427 if (verbose_)
1428 OMPL_INFORM(" ------ Find graph representative ");
1429
1430 // Compute who his graph neighbors are
1431 Vertex representative = findGraphRepresentative(workState);
1432
1433 // Assuming this sample is actually seen by somebody (which he should be in all likelihood)
1434 if (representative != boost::graph_traits<Graph>::null_vertex())
1435 {
1436 if (verbose_)
1437 OMPL_INFORM(" ------ Representative is not null ");
1438
1439 // If his representative is different than qNew
1440 if (qRep != representative)
1441 {
1442 if (verbose_)
1443 OMPL_INFORM(" ------ qRep != representative ");
1444
1445 // And we haven't already tracked this representative
1446 if (closeRepresentatives.find(representative) == closeRepresentatives.end())
1447 {
1448 if (verbose_)
1449 OMPL_INFORM(" ------ Track the representative");
1450 // Track the representativen
1451 closeRepresentatives[representative] = si_->cloneState(workState);
1452 }
1453 }
1454 else
1455 {
1456 if (verbose_)
1457 OMPL_INFORM(" ------ qRep == representative, no good ");
1458 }
1459 }
1460 else
1461 {
1462 if (verbose_)
1463 OMPL_INFORM(" ------ Rep is null ");
1464
1465 // This guy can't be seen by anybody, so we should take this opportunity to add him
1466 if (verbose_)
1467 OMPL_INFORM(" --- Adding node for COVERAGE");
1468 addGuard(si_->cloneState(workState), COVERAGE);
1469
1470 if (verbose_)
1471 {
1472 OMPL_INFORM(" ------ STOP EFFORS TO ADD A DENSE PATH");
1473 }
1474
1475 // We should also stop our efforts to add a dense path
1476 for (auto &closeRepresentative : closeRepresentatives)
1477 si_->freeState(closeRepresentative.second);
1478 closeRepresentatives.clear();
1479 break;
1480 }
1481 } // for loop
1482}
1483
1485{
1486 // First of all, we need to compute all candidate r'
1487 std::vector<Vertex> VPPs;
1488 computeVPP(rep, r, VPPs);
1489
1490 // Then, for each pair Pv(r,r')
1491 foreach (Vertex rp, VPPs)
1492 // Try updating the pair info
1493 distanceCheck(rep, q, r, s, rp);
1494}
1495
1496void ompl::geometric::SPARSdb::computeVPP(Vertex v, Vertex vp, std::vector<Vertex> &VPPs)
1497{
1498 VPPs.clear();
1499 foreach (Vertex cvpp, boost::adjacent_vertices(v, g_))
1500 if (cvpp != vp)
1501 if (!boost::edge(cvpp, vp, g_).second)
1502 VPPs.push_back(cvpp);
1503}
1504
1505void ompl::geometric::SPARSdb::computeX(Vertex v, Vertex vp, Vertex vpp, std::vector<Vertex> &Xs)
1506{
1507 Xs.clear();
1508
1509 foreach (Vertex cx, boost::adjacent_vertices(vpp, g_))
1510 if (boost::edge(cx, v, g_).second && !boost::edge(cx, vp, g_).second)
1511 {
1512 InterfaceData &d = getData(v, vpp, cx);
1513 if ((vpp < cx && d.pointA_) || (cx < vpp && d.pointB_))
1514 Xs.push_back(cx);
1515 }
1516 Xs.push_back(vpp);
1517}
1518
1520{
1521 if (vp < vpp)
1522 return VertexPair(vp, vpp);
1523 else if (vpp < vp)
1524 return VertexPair(vpp, vp);
1525 else
1526 throw Exception(name_, "Trying to get an index where the pairs are the same point!");
1527}
1528
1533
1535 Vertex rp)
1536{
1537 // Get the info for the current representative-neighbors pair
1538 InterfaceData &d = getData(rep, r, rp);
1539
1540 if (r < rp) // FIRST points represent r (the guy discovered through sampling)
1541 {
1542 if (d.pointA_ == nullptr) // If the point we're considering replacing (P_v(r,.)) isn't there
1543 // Then we know we're doing better, so add it
1544 d.setFirst(q, s, si_);
1545 else // Otherwise, he is there,
1546 {
1547 if (d.pointB_ == nullptr) // But if the other guy doesn't exist, we can't compare.
1548 {
1549 // Should probably keep the one that is further away from rep? Not known what to do in this case.
1550 // TODO: is this not part of the algorithm?
1551 }
1552 else // We know both of these points exist, so we can check some distances
1553 if (si_->distance(q, d.pointB_) < si_->distance(d.pointA_, d.pointB_))
1554 // Distance with the new point is good, so set it.
1555 d.setFirst(q, s, si_);
1556 }
1557 }
1558 else // SECOND points represent r (the guy discovered through sampling)
1559 {
1560 if (d.pointB_ == nullptr) // If the point we're considering replacing (P_V(.,r)) isn't there...
1561 // Then we must be doing better, so add it
1562 d.setSecond(q, s, si_);
1563 else // Otherwise, he is there
1564 {
1565 if (d.pointA_ == nullptr) // But if the other guy doesn't exist, we can't compare.
1566 {
1567 // Should we be doing something cool here?
1568 }
1569 else if (si_->distance(q, d.pointA_) < si_->distance(d.pointB_, d.pointA_))
1570 // Distance with the new point is good, so set it
1571 d.setSecond(q, s, si_);
1572 }
1573 }
1574
1575 // Lastly, save what we have discovered
1576 interfaceDataProperty_[rep].interfaceHash[index(r, rp)] = d;
1577}
1578
1580{
1582
1583 std::vector<Vertex> hold;
1584 nn_->nearestR(queryVertex_, sparseDelta_, hold);
1585
1586 stateProperty_[queryVertex_] = nullptr;
1587
1588 // For each of the vertices
1589 foreach (Vertex v, hold)
1590 {
1591 foreach (VertexPair r, interfaceDataProperty_[v].interfaceHash | boost::adaptors::map_keys)
1592 interfaceDataProperty_[v].interfaceHash[r].clear(si_);
1593 }
1594}
1595
1597{
1598 Vertex m = boost::add_vertex(g_);
1599 stateProperty_[m] = state;
1600 colorProperty_[m] = type;
1601
1602 // assert(si_->isValid(state));
1603 abandonLists(state);
1604
1605 disjointSets_.make_set(m);
1606 nn_->add(m);
1607 resetFailures();
1608
1609 if (verbose_)
1610 {
1611 OMPL_INFORM(" ---- addGuard() of type %f", type);
1612 }
1613#ifdef OMPL_THUNDER_DEBUG
1614 visualizeStateCallback(state, 4, sparseDelta_); // Candidate node has already (just) been added
1615 sleep(0.1);
1616#endif
1617
1618 return m;
1619}
1620
1622{
1623 // OMPL_INFORM("connectGuards called ---------------------------------------------------------------- ");
1624 assert(v <= getNumVertices());
1625 assert(vp <= getNumVertices());
1626
1627 if (verbose_)
1628 {
1629 OMPL_INFORM(" ------- connectGuards/addEdge: Connecting vertex %f to vertex %f", v, vp);
1630 }
1631
1632 // Create the new edge
1633 Edge e = (boost::add_edge(v, vp, g_)).first;
1634
1635 // Add associated properties to the edge
1636 edgeWeightProperty_[e] = distanceFunction(v, vp); // TODO: use this value with astar
1637 edgeCollisionStateProperty_[e] = NOT_CHECKED;
1638
1639 // Add the edge to the incrementeal connected components datastructure
1640 disjointSets_.union_set(v, vp);
1641
1642// Debug in Rviz
1643#ifdef OMPL_THUNDER_DEBUG
1644 visualizeEdgeCallback(stateProperty_[v], stateProperty_[vp]);
1645 sleep(0.8);
1646#endif
1647}
1648
1650 const base::State *actualStart,
1651 const base::State *actualGoal,
1652 CandidateSolution &candidateSolution,
1653 bool disableCollisionWarning)
1654{
1655 if (!vertexPath.size())
1656 return false;
1657
1658 auto pathGeometric(std::make_shared<ompl::geometric::PathGeometric>(si_));
1659 candidateSolution.isApproximate_ = false; // assume path is valid
1660
1661 // Add original start if it is different than the first state
1662 if (actualStart != stateProperty_[vertexPath.back()])
1663 {
1664 pathGeometric->append(actualStart);
1665
1666 // Add the edge status
1667 // the edge from actualStart to start is always valid otherwise we would not have used that start
1668 candidateSolution.edgeCollisionStatus_.push_back(FREE);
1669 }
1670
1671 // Reverse the vertexPath and convert to state path
1672 for (std::size_t i = vertexPath.size(); i > 0; --i)
1673 {
1674 pathGeometric->append(stateProperty_[vertexPath[i - 1]]);
1675
1676 // Add the edge status
1677 if (i > 1) // skip the last vertex (its reversed)
1678 {
1679 Edge thisEdge = boost::edge(vertexPath[i - 1], vertexPath[i - 2], g_).first;
1680
1681 // Check if any edges in path are not free (then it an approximate path)
1682 if (edgeCollisionStateProperty_[thisEdge] == IN_COLLISION)
1683 {
1684 candidateSolution.isApproximate_ = true;
1685 candidateSolution.edgeCollisionStatus_.push_back(IN_COLLISION);
1686 }
1687 else if (edgeCollisionStateProperty_[thisEdge] == NOT_CHECKED)
1688 {
1689 if (!disableCollisionWarning)
1690 OMPL_ERROR("A chosen path has an edge that has not been checked for collision. This should not "
1691 "happen");
1692 candidateSolution.edgeCollisionStatus_.push_back(NOT_CHECKED);
1693 }
1694 else
1695 {
1696 candidateSolution.edgeCollisionStatus_.push_back(FREE);
1697 }
1698 }
1699 }
1700
1701 // Add original goal if it is different than the last state
1702 if (actualGoal != stateProperty_[vertexPath.front()])
1703 {
1704 pathGeometric->append(actualGoal);
1705
1706 // Add the edge status
1707 // the edge from actualGoal to goal is always valid otherwise we would not have used that goal
1708 candidateSolution.edgeCollisionStatus_.push_back(FREE);
1709 }
1710
1711 candidateSolution.path_ = pathGeometric;
1712
1713 return true;
1714}
1715
1717{
1718 Planner::getPlannerData(data);
1719
1720 // Explicitly add start and goal states:
1721 for (unsigned long i : startM_)
1723
1724 for (unsigned long i : goalM_)
1726
1727 // I'm curious:
1728 if (goalM_.size() > 0)
1729 {
1730 throw Exception(name_, "SPARS2 has goal states?");
1731 }
1732 if (startM_.size() > 0)
1733 {
1734 throw Exception(name_, "SPARS2 has start states?");
1735 }
1736
1737 // If there are even edges here
1738 if (boost::num_edges(g_) > 0)
1739 {
1740 // Adding edges and all other vertices simultaneously
1741 foreach (const Edge e, boost::edges(g_))
1742 {
1743 const Vertex v1 = boost::source(e, g_);
1744 const Vertex v2 = boost::target(e, g_);
1745
1746 // TODO save weights!
1749
1750 // OMPL_INFORM("Adding edge from vertex of type %d to vertex of type %d", colorProperty_[v1],
1751 // colorProperty_[v2]);
1752 }
1753 }
1754 // else
1755 // OMPL_INFORM("%s: There are no edges in the graph!", getName().c_str());
1756
1757 // Make sure to add edge-less nodes as well
1758 foreach (const Vertex n, boost::vertices(g_))
1759 if (boost::out_degree(n, g_) == 0)
1761
1762 data.properties["iterations INTEGER"] = std::to_string(iterations_);
1763}
1764
1766{
1767 // Check that the query vertex is initialized (used for internal nearest neighbor searches)
1769
1770 // Add all vertices
1771 if (verbose_)
1772 {
1773 OMPL_INFORM("SPARS::setPlannerData: numVertices=%d", data.numVertices());
1774 }
1775 OMPL_INFORM("Loading PlannerData into SPARSdb");
1776
1777 std::vector<Vertex> idToVertex;
1778
1779 // Temp disable verbose mode for loading database
1780 bool wasVerbose = verbose_;
1781 verbose_ = false;
1782
1783 OMPL_INFORM("Loading vertices:");
1784 // Add the nodes to the graph
1785 for (std::size_t vertexID = 0; vertexID < data.numVertices(); ++vertexID)
1786 {
1787 // Get the state from loaded planner data
1788 const base::State *oldState = data.getVertex(vertexID).getState();
1789 base::State *state = si_->cloneState(oldState);
1790
1791 // Get the tag, which in this application represents the vertex type
1792 auto type = static_cast<GuardType>(data.getVertex(vertexID).getTag());
1793
1794 // ADD GUARD
1795 idToVertex.push_back(addGuard(state, type));
1796 }
1797
1798 OMPL_INFORM("Loading edges:");
1799 // Add the corresponding edges to the graph
1800 std::vector<unsigned int> edgeList;
1801 for (std::size_t fromVertex = 0; fromVertex < data.numVertices(); ++fromVertex)
1802 {
1803 edgeList.clear();
1804
1805 // Get the edges
1806 data.getEdges(fromVertex, edgeList); // returns num of edges
1807
1808 Vertex m = idToVertex[fromVertex];
1809
1810 // Process edges
1811 for (unsigned int toVertex : edgeList)
1812 {
1813 Vertex n = idToVertex[toVertex];
1814
1815 // Add the edge to the graph
1816 const base::Cost weight(0);
1817 if (verbose_ && false)
1818 {
1819 OMPL_INFORM(" Adding edge from vertex id %d to id %d into edgeList", fromVertex, toVertex);
1820 OMPL_INFORM(" Vertex %d to %d", m, n);
1821 }
1822 connectGuards(m, n);
1823 }
1824 } // for
1825
1826 // Re-enable verbose mode, if necessary
1827 verbose_ = wasVerbose;
1828}
1829
1831{
1832 foreach (const Edge e, boost::edges(g_))
1833 edgeCollisionStateProperty_[e] = NOT_CHECKED; // each edge has an unknown state
1834}
The exception type for ompl.
Definition Exception.h:47
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition Cost.h:48
Abstract definition of goals.
Definition Goal.h:63
virtual bool isStartGoalPairValid(const State *, const State *) const
Since there can be multiple starting states (and multiple goal states) it is possible certain pairs a...
Definition Goal.h:136
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition PlannerData.h:59
virtual const State * getState() const
Retrieve the state associated with this vertex.
Definition PlannerData.h:80
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...
unsigned int numVertices() const
Retrieve the number of vertices in this structure.
unsigned int getEdges(unsigned int v, std::vector< unsigned int > &edgeList) const
Returns a list of the vertex indexes directly connected to vertex with index v (outgoing edges)....
const PlannerDataVertex & getVertex(unsigned int index) const
Retrieve a reference to the vertex object with the given index. If this vertex does not exist,...
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...
unsigned int addVertex(const PlannerDataVertex &st)
Adds the given vertex to the graph data. The vertex index is returned. Duplicates are not added....
std::map< std::string, std::string > properties
Any extra properties (key-value pairs) the planner can set.
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
PlannerSpecs specs_
The specifications of the planner (its capabilities).
Definition Planner.h:413
ProblemDefinitionPtr pdef_
The user set problem definition.
Definition Planner.h:404
std::string name_
The name of this planner.
Definition Planner.h:410
SpaceInformationPtr si_
The space information for which planning is done.
Definition Planner.h:401
Definition of an abstract state.
Definition State.h:50
Definition of a geometric path.
std::size_t getStateCount() const
Get the number of states (way-points) that make up this path.
void interpolate(unsigned int count)
Insert a number of states in a path so that the path is made up of exactly count states....
double length() const override
Compute the length of a geometric path (sum of lengths of segments that make up the path).
base::State * getState(unsigned int index)
Get the state located at index along the path.
void examine_vertex(Vertex u, const Graph &g) const
Definition SPARSdb.cpp:91
edgeWeightMap(const Graph &graph, const EdgeCollisionStateMap &collisionStates)
Definition SPARSdb.cpp:60
Vertex queryVertex_
Vertex for performing nearest neighbor queries.
Definition SPARSdb.h:717
double getStretchFactor() const
Retrieve the spanner's set stretch factor.
Definition SPARSdb.h:433
bool convertVertexPathToStatePath(std::vector< Vertex > &vertexPath, const base::State *actualStart, const base::State *actualGoal, CandidateSolution &candidateSolution, bool disableCollisionWarning=false)
Convert astar results to correctly ordered path.
Definition SPARSdb.cpp:1649
bool checkAddCoverage(const base::State *qNew, std::vector< Vertex > &visibleNeighborhood)
Checks to see if the sample needs to be added to ensure coverage of the space.
Definition SPARSdb.cpp:1060
std::vector< Vertex > goalM_
Array of goal milestones.
Definition SPARSdb.h:714
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 SPARSdb.cpp:1716
unsigned int maxFailures_
The number of consecutive failures to add to the graph before termination.
Definition SPARSdb.h:730
double sparseDeltaFraction_
Maximum visibility range for nodes in the graph as a fraction of maximum extent.
Definition SPARSdb.h:723
bool getSimilarPaths(int nearestK, const base::State *start, const base::State *goal, CandidateSolution &candidateSolution, const base::PlannerTerminationCondition &ptc)
Search the roadmap for the best path close to the given start and goal states that is valid.
Definition SPARSdb.cpp:191
bool checkAddConnectivity(const base::State *qNew, std::vector< Vertex > &visibleNeighborhood)
Checks to see if the sample needs to be added to ensure connectivity.
Definition SPARSdb.cpp:1074
void setStretchFactor(double t)
Sets the stretch factor.
Definition SPARSdb.h:387
std::vector< Vertex > startVertexCandidateNeighbors_
Used by getSimilarPaths.
Definition SPARSdb.h:779
double getSparseDeltaFraction() const
Retrieve the sparse graph visibility range delta.
Definition SPARSdb.h:427
boost::graph_traits< Graph >::edge_descriptor Edge
Edge in Graph.
Definition SPARSdb.h:297
bool checkAddInterface(const base::State *qNew, std::vector< Vertex > &graphNeighborhood, std::vector< Vertex > &visibleNeighborhood)
Checks to see if the current sample reveals the existence of an interface, and if so,...
Definition SPARSdb.cpp:1125
boost::graph_traits< Graph >::vertex_descriptor Vertex
Vertex in Graph.
Definition SPARSdb.h:294
double sparseDelta_
Maximum visibility range for nodes in the graph.
Definition SPARSdb.h:773
unsigned int getNumEdges() const
Get the number of edges in the sparse roadmap.
Definition SPARSdb.h:516
unsigned int consecutiveFailures_
A counter for the number of consecutive failed iterations of the algorithm.
Definition SPARSdb.h:767
void clearQuery() override
Clear the query previously loaded from the ProblemDefinition. Subsequent calls to solve() will reuse ...
Definition SPARSdb.cpp:154
~SPARSdb() override
Destructor.
Definition SPARSdb.cpp:129
VertexPair index(Vertex vp, Vertex vpp)
Rectifies indexing order for accessing the vertex data.
Definition SPARSdb.cpp:1519
bool constructSolution(Vertex start, Vertex goal, std::vector< Vertex > &vertexPath) const
Given two milestones from the same connected component, construct a path connecting them and set it a...
Definition SPARSdb.cpp:413
bool lazyCollisionSearch(const Vertex &start, const Vertex &goal, const base::State *actualStart, const base::State *actualGoal, CandidateSolution &candidateSolution, const base::PlannerTerminationCondition &ptc)
Repeatidly search through graph for connection then check for collisions then repeat.
Definition SPARSdb.cpp:305
void findCloseRepresentatives(base::State *workState, const base::State *qNew, Vertex qRep, std::map< Vertex, base::State * > &closeRepresentatives, const base::PlannerTerminationCondition &ptc)
Finds representatives of samples near qNew_ which are not his representative.
Definition SPARSdb.cpp:1369
void resetFailures()
A reset function for resetting the failures count.
Definition SPARSdb.cpp:1267
base::ValidStateSamplerPtr sampler_
Sampler user for generating valid samples in the state space.
Definition SPARSdb.h:702
void setSparseDeltaFraction(double D)
Sets vertex visibility range as a fraction of max. extent.
Definition SPARSdb.h:393
boost::property_map< Graph, edge_collision_state_t >::type EdgeCollisionStateMap
Access map that stores the lazy collision checking status of each edge.
Definition SPARSdb.h:303
bool reachedFailureLimit() const
Returns whether we have reached the iteration failures limit, maxFailures_.
Definition SPARSdb.cpp:549
std::vector< Vertex > startM_
Array of start milestones.
Definition SPARSdb.h:711
bool checkAddPath(Vertex v)
Checks vertex v for short paths through its region and adds when appropriate.
Definition SPARSdb.cpp:1168
boost::disjoint_sets< boost::property_map< Graph, boost::vertex_rank_t >::type, boost::property_map< Graph, boost::vertex_predecessor_t >::type > disjointSets_
Data structure that maintains the connected components.
Definition SPARSdb.h:759
boost::property_map< Graph, vertex_interface_data_t >::type interfaceDataProperty_
Access to the interface pair information for the vertices.
Definition SPARSdb.h:754
void abandonLists(base::State *st)
When a new guard is added at state st, finds all guards who must abandon their interface information ...
Definition SPARSdb.cpp:1579
boost::property_map< Graph, boost::edge_weight_t >::type edgeWeightProperty_
Access to the weights of each Edge.
Definition SPARSdb.h:742
double distanceFunction(const Vertex a, const Vertex b) const
Compute distance between two milestones (this is simply distance between the states of the milestones...
Definition SPARSdb.h:696
boost::adjacency_list< boost::vecS, boost::vecS, boost::undirectedS, VertexProperties, EdgeProperties > Graph
Definition SPARSdb.h:289
EdgeCollisionStateMap edgeCollisionStateProperty_
Access to the collision checking state of each Edge.
Definition SPARSdb.h:745
long unsigned int getIterations() const
Get the number of iterations the algorithm performed.
Definition SPARSdb.h:549
double denseDeltaFraction_
Maximum range for allowing two samples to support an interface as a fraction of maximum extent.
Definition SPARSdb.h:727
boost::property_map< Graph, vertex_color_t >::type colorProperty_
Access to the colors for the vertices.
Definition SPARSdb.h:751
void computeX(Vertex v, Vertex vp, Vertex vpp, std::vector< Vertex > &Xs)
Computes all nodes which qualify as a candidate x for v, v', and v".
Definition SPARSdb.cpp:1505
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition SPARSdb.cpp:134
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition SPARSdb.cpp:161
InterfaceData & getData(Vertex v, Vertex vp, Vertex vpp)
Retrieves the Vertex data associated with v,vp,vpp.
Definition SPARSdb.cpp:1529
void printDebug(std::ostream &out=std::cout) const
Print debug information about planner.
Definition SPARSdb.cpp:554
void checkQueryStateInitialization()
Check that the query vertex is initialized (used for internal nearest neighbor searches).
Definition SPARSdb.cpp:1045
PathSimplifierPtr psimp_
A path simplifier used to simplify dense paths added to the graph.
Definition SPARSdb.h:739
void setMaxFailures(unsigned int m)
Sets the maximum failures until termination.
Definition SPARSdb.h:409
void approachGraph(Vertex v)
Approaches the graph from a given vertex.
Definition SPARSdb.cpp:1327
void setDenseDeltaFraction(double d)
Sets interface support tolerance as a fraction of max. extent.
Definition SPARSdb.h:401
bool lazyCollisionCheck(std::vector< Vertex > &vertexPath, const base::PlannerTerminationCondition &ptc)
Check recalled path for collision and disable as needed.
Definition SPARSdb.cpp:480
double stretchFactor_
Stretch Factor as per graph spanner literature (multiplicative bound on path quality).
Definition SPARSdb.h:720
void findGraphNeighbors(base::State *state, std::vector< Vertex > &graphNeighborhood, std::vector< Vertex > &visibleNeighborhood)
Finds visible nodes in the graph near state.
Definition SPARSdb.cpp:1272
double denseDelta_
Maximum range for allowing two samples to support an interface.
Definition SPARSdb.h:776
Vertex addGuard(base::State *state, GuardType type)
Construct a guard for a given state (state) and store it in the nearest neighbors data structure.
Definition SPARSdb.cpp:1596
Graph g_
Connectivity graph.
Definition SPARSdb.h:708
unsigned int getMaxFailures() const
Retrieve the maximum consecutive failure limit.
Definition SPARSdb.h:415
std::shared_ptr< NearestNeighbors< Vertex > > nn_
Nearest neighbors data structure.
Definition SPARSdb.h:705
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 SPARSdb.cpp:1054
void freeMemory()
Free all the memory allocated by the planner.
Definition SPARSdb.cpp:172
unsigned int nearSamplePoints_
Number of sample points to use when trying to detect interfaces.
Definition SPARSdb.h:736
void distanceCheck(Vertex rep, const base::State *q, Vertex r, const base::State *s, Vertex rp)
Performs distance checking for the candidate new state, q against the current information.
Definition SPARSdb.cpp:1534
Vertex findGraphRepresentative(base::State *st)
Finds the representative of the input state, st.
Definition SPARSdb.cpp:1341
bool sameComponent(Vertex m1, Vertex m2)
Check if two milestones (m1 and m2) are part of the same connected component. This is not a const fun...
Definition SPARSdb.cpp:544
std::pair< VertexIndexType, VertexIndexType > VertexPair
Pair of vertices which support an interface.
Definition SPARSdb.h:107
void computeVPP(Vertex v, Vertex vp, std::vector< Vertex > &VPPs)
Computes all nodes which qualify as a candidate v" for v and vp.
Definition SPARSdb.cpp:1496
void updatePairPoints(Vertex rep, const base::State *q, Vertex r, const base::State *s)
High-level method which updates pair point information for repV_ with neighbor r.
Definition SPARSdb.cpp:1484
void clearEdgeCollisionStates()
Clear all past edge state information about in collision or not.
Definition SPARSdb.cpp:1830
double getDenseDeltaFraction() const
Retrieve the dense graph interface support delta.
Definition SPARSdb.h:421
long unsigned int iterations_
A counter for the number of iterations of the algorithm.
Definition SPARSdb.h:770
bool getPaths(const std::vector< Vertex > &candidateStarts, const std::vector< Vertex > &candidateGoals, const base::State *actualStart, const base::State *actualGoal, CandidateSolution &candidateSolution, const base::PlannerTerminationCondition &ptc)
Check if there exists a solution, i.e., there exists a pair of milestones such that the first is in s...
Definition SPARSdb.cpp:251
unsigned int getNumVertices() const
Get the number of vertices in the sparse roadmap.
Definition SPARSdb.h:510
boost::property_map< Graph, vertex_state_t >::type stateProperty_
Access to the internal base::state at each Vertex.
Definition SPARSdb.h:748
bool verbose_
Option to enable debugging output.
Definition SPARSdb.h:783
void setPlannerData(const base::PlannerData &data)
Set the sparse graph from file.
Definition SPARSdb.cpp:1765
GuardType
Enumeration which specifies the reason a guard is added to the spanner.
Definition SPARSdb.h:90
SPARSdb(const base::SpaceInformationPtr &si)
Constructor.
Definition SPARSdb.cpp:99
void connectGuards(Vertex v, Vertex vp)
Connect two guards in the roadmap.
Definition SPARSdb.cpp:1621
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...
@ GOAL_SAMPLEABLE_REGION
This bit is set if casting to sampleable goal regions (ompl::base::GoalSampleableRegion) is possible.
Definition GoalTypes.h:56
A class to store the exit status of Planner::solve().
@ TIMEOUT
The planner failed to find a solution.
Struct for passing around partially solved solutions.
Definition SPARSdb.h:233
Interface information storage class, which does bookkeeping for criterion four.
Definition SPARSdb.h:112
double d_
Last known distance between the two interfaces supported by points_ and sigmas.
Definition SPARSdb.h:122
void clear(const base::SpaceInformationPtr &si)
Clears the given interface data.
Definition SPARSdb.h:128
void setSecond(const base::State *p, const base::State *s, const base::SpaceInformationPtr &si)
Sets information for the second interface (i.e. interface with larger index vertex).
Definition SPARSdb.h:169
base::State * pointA_
States which lie inside the visibility region of a vertex and support an interface.
Definition SPARSdb.h:114
void setFirst(const base::State *p, const base::State *s, const base::SpaceInformationPtr &si)
Sets information for the first interface (i.e. interface with smaller index vertex).
Definition SPARSdb.h:154
base::State * sigmaA_
States which lie just outside the visibility region of a vertex and support an interface.
Definition SPARSdb.h:118