Loading...
Searching...
No Matches
LazyPRM.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2013, Willow Garage
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 Willow Garage 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/* Author: Ioan Sucan, Ryan Luna, Henning Kayser */
36
37#include "ompl/geometric/planners/prm/LazyPRM.h"
38#include "ompl/base/objectives/PathLengthOptimizationObjective.h"
39#include "ompl/base/goals/GoalSampleableRegion.h"
40#include "ompl/geometric/planners/prm/ConnectionStrategy.h"
41#include "ompl/tools/config/SelfConfig.h"
42#include <boost/graph/astar_search.hpp>
43#include <boost/graph/incremental_components.hpp>
44#include <boost/graph/lookup_edge.hpp>
45#include <boost/foreach.hpp>
46#include <queue>
47
48#include "GoalVisitor.hpp"
49
50#define foreach BOOST_FOREACH
51
52namespace ompl
53{
54 namespace magic
55 {
58 static const unsigned int DEFAULT_NEAREST_NEIGHBORS_LAZY = 5;
59
63 static const unsigned int MIN_ADDED_SEGMENTS_FOR_LAZY_OPTIMIZATION = 5;
64 } // namespace magic
65} // namespace ompl
66
67ompl::geometric::LazyPRM::LazyPRM(const base::SpaceInformationPtr &si, bool starStrategy)
68 : base::Planner(si, "LazyPRM")
69 , starStrategy_(starStrategy)
70 , indexProperty_(boost::get(boost::vertex_index_t(), g_))
71 , stateProperty_(boost::get(vertex_state_t(), g_))
72 , weightProperty_(boost::get(boost::edge_weight, g_))
75 , edgeValidityProperty_(boost::get(edge_flags_t(), g_))
76{
77 specs_.recognizedGoal = base::GOAL_SAMPLEABLE_REGION;
78 specs_.approximateSolutions = false;
79 specs_.optimizingPaths = true;
80
81 Planner::declareParam<double>("range", this, &LazyPRM::setRange, &LazyPRM::getRange, "0.:1.:10000.");
82 if (!starStrategy_)
83 Planner::declareParam<unsigned int>("max_nearest_neighbors", this, &LazyPRM::setMaxNearestNeighbors,
84 std::string("8:1000"));
85
86 addPlannerProgressProperty("iterations INTEGER", [this] { return getIterationCount(); });
87 addPlannerProgressProperty("best cost REAL", [this] { return getBestCost(); });
88 addPlannerProgressProperty("milestone count INTEGER", [this] { return getMilestoneCountString(); });
89 addPlannerProgressProperty("edge count INTEGER", [this] { return getEdgeCountString(); });
90}
91
93 : LazyPRM(data.getSpaceInformation(), starStrategy)
94{
95 if (data.numVertices() > 0)
96 {
97 // mapping between vertex id from PlannerData and Vertex in Boost.Graph
98 std::map<unsigned int, Vertex> vertices;
99 // helper function to create vertices as needed and update the vertices mapping
100 const auto &getOrCreateVertex = [&](unsigned int vertex_index)
101 {
102 if (!vertices.count(vertex_index))
103 {
104 const auto &data_vertex = data.getVertex(vertex_index);
105 Vertex graph_vertex = boost::add_vertex(g_);
106 stateProperty_[graph_vertex] = si_->cloneState(data_vertex.getState());
107 vertexValidityProperty_[graph_vertex] = VALIDITY_UNKNOWN;
108 unsigned long int newComponent = componentCount_++;
109 vertexComponentProperty_[graph_vertex] = newComponent;
110 vertices[vertex_index] = graph_vertex;
111 }
112 return vertices.at(vertex_index);
113 };
114
115 specs_.multithreaded = false; // temporarily set to false since nn_ is used only in single thread
117 specs_.multithreaded = true;
118 nn_->setDistanceFunction([this](const Vertex a, const Vertex b) { return distanceFunction(a, b); });
119
120 for (size_t vertex_index = 0; vertex_index < data.numVertices(); ++vertex_index)
121 {
122 Vertex m = getOrCreateVertex(vertex_index);
123 std::vector<unsigned int> neighbor_indices;
124 data.getEdges(vertex_index, neighbor_indices);
125 for (const unsigned int neighbor_index : neighbor_indices)
126 {
127 Vertex n = getOrCreateVertex(neighbor_index);
128 base::Cost weight;
129 data.getEdgeWeight(vertex_index, neighbor_index, &weight);
130 const Graph::edge_property_type properties(weight);
131 const Edge &edge = boost::add_edge(m, n, properties, g_).first;
133 uniteComponents(m, n);
134 }
135 nn_->add(m);
136 }
137 }
138}
139
140ompl::geometric::LazyPRM::~LazyPRM()
141{
142 clear();
143};
144
146{
147 Planner::setup();
150
151 if (!nn_)
152 {
154 nn_->setDistanceFunction([this](const Vertex a, const Vertex b) { return distanceFunction(a, b); });
155 }
159 connectionFilter_ = [](const Vertex &, const Vertex &) { return true; };
160
161 // Setup optimization objective
162 //
163 // If no optimization objective was specified, then default to
164 // optimizing path length as computed by the distance() function
165 // in the state space.
166 if (pdef_)
167 {
168 if (pdef_->hasOptimizationObjective())
169 opt_ = pdef_->getOptimizationObjective();
170 else
171 {
172 opt_ = std::make_shared<base::PathLengthOptimizationObjective>(si_);
173 if (!starStrategy_)
174 opt_->setCostThreshold(opt_->infiniteCost());
175 }
176 }
177 else
178 {
179 OMPL_INFORM("%s: problem definition is not set, deferring setup completion...", getName().c_str());
180 setup_ = false;
181 }
182
183 sampler_ = si_->allocStateSampler();
184}
185
187{
188 maxDistance_ = distance;
191 if (isSetup())
192 setup();
193}
194
196{
197 if (starStrategy_)
198 throw Exception("Cannot set the maximum nearest neighbors for " + getName());
199 if (!nn_)
200 {
202 nn_->setDistanceFunction([this](const Vertex a, const Vertex b) { return distanceFunction(a, b); });
203 }
206 if (isSetup())
207 setup();
208}
209
211{
212 if (!nn_)
213 {
215 nn_->setDistanceFunction([this](const Vertex a, const Vertex b) { return distanceFunction(a, b); });
216 }
217
218 if (starStrategy_)
219 connectionStrategy_ = KStarStrategy<Vertex>([this] { return milestoneCount(); }, nn_, si_->getStateDimension());
220 else
222}
223
224void ompl::geometric::LazyPRM::setProblemDefinition(const base::ProblemDefinitionPtr &pdef)
225{
226 Planner::setProblemDefinition(pdef);
227 clearQuery();
228}
229
231{
232 startM_.clear();
233 goalM_.clear();
234 pis_.restart();
235}
236
238{
239 foreach (const Vertex v, boost::vertices(g_))
241 foreach (const Edge e, boost::edges(g_))
243}
244
246{
247 Planner::clear();
248 freeMemory();
249 if (nn_)
250 nn_->clear();
251 clearQuery();
252
253 componentCount_ = 0;
254 iterations_ = 0;
255 bestCost_ = base::Cost(std::numeric_limits<double>::quiet_NaN());
256}
257
259{
260 foreach (Vertex v, boost::vertices(g_))
261 si_->freeState(stateProperty_[v]);
262 g_.clear();
263}
264
266{
267 Vertex m = boost::add_vertex(g_);
268 stateProperty_[m] = state;
270 unsigned long int newComponent = componentCount_++;
271 vertexComponentProperty_[m] = newComponent;
272 componentSize_[newComponent] = 1;
273
274 // Which milestones will we attempt to connect to?
275 const std::vector<Vertex> &neighbors = connectionStrategy_(m);
276 foreach (Vertex n, neighbors)
277 if (connectionFilter_(m, n))
278 {
279 const base::Cost weight = opt_->motionCost(stateProperty_[m], stateProperty_[n]);
280 const Graph::edge_property_type properties(weight);
281 const Edge &e = boost::add_edge(m, n, properties, g_).first;
283 uniteComponents(m, n);
284 }
285
286 nn_->add(m);
287
288 return m;
289}
290
292{
294 auto *goal = dynamic_cast<base::GoalSampleableRegion *>(pdef_->getGoal().get());
295
296 if (goal == nullptr)
297 {
298 OMPL_ERROR("%s: Unknown type of goal", getName().c_str());
300 }
301
302 // Add the valid start states as milestones
303 while (const base::State *st = pis_.nextStart())
304 startM_.push_back(addMilestone(si_->cloneState(st)));
305
306 if (startM_.empty())
307 {
308 OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
310 }
311
312 if (!goal->couldSample())
313 {
314 OMPL_ERROR("%s: Insufficient states in sampleable goal region", getName().c_str());
316 }
317
318 // Ensure there is at least one valid goal state
319 if (goal->maxSampleCount() > goalM_.size() || goalM_.empty())
320 {
321 const base::State *st = goalM_.empty() ? pis_.nextGoal(ptc) : pis_.nextGoal();
322 if (st != nullptr)
323 goalM_.push_back(addMilestone(si_->cloneState(st)));
324
325 if (goalM_.empty())
326 {
327 OMPL_ERROR("%s: Unable to find any valid goal states", getName().c_str());
329 }
330 }
331
332 unsigned long int nrStartStates = boost::num_vertices(g_);
333 OMPL_INFORM("%s: Starting planning with %lu states already in datastructure", getName().c_str(), nrStartStates);
334
335 bestCost_ = opt_->infiniteCost();
336 base::State *workState = si_->allocState();
337 std::pair<std::size_t, std::size_t> startGoalPair;
338 base::PathPtr bestSolution;
339 bool fullyOptimized = false;
340 bool someSolutionFound = false;
341 unsigned int optimizingComponentSegments = 0;
342
343 // Grow roadmap in lazy fashion -- add vertices and edges without checking validity
344 while (!ptc)
345 {
346 ++iterations_;
347 sampler_->sampleUniform(workState);
348 Vertex addedVertex = addMilestone(si_->cloneState(workState));
349
350 const long int solComponent = solutionComponent(&startGoalPair);
351 // If the start & goal are connected and we either did not find any solution
352 // so far or the one we found still needs optimizing and we just added an edge
353 // to the connected component that is used for the solution, we attempt to
354 // construct a new solution.
355 if (solComponent != -1 &&
356 (!someSolutionFound || (long int)vertexComponentProperty_[addedVertex] == solComponent))
357 {
358 // If we already have a solution, we are optimizing. We check that we added at least
359 // a few segments to the connected component that includes the previously found
360 // solution before attempting to construct a new solution.
361 if (someSolutionFound)
362 {
363 if (++optimizingComponentSegments < magic::MIN_ADDED_SEGMENTS_FOR_LAZY_OPTIMIZATION)
364 continue;
365 optimizingComponentSegments = 0;
366 }
367 Vertex startV = startM_[startGoalPair.first];
368 Vertex goalV = goalM_[startGoalPair.second];
369 base::PathPtr solution;
370 do
371 {
372 solution = constructSolution(startV, goalV);
373 } while (!solution && vertexComponentProperty_[startV] == vertexComponentProperty_[goalV] && !ptc);
374 if (solution)
375 {
376 someSolutionFound = true;
377 base::Cost c = solution->cost(opt_);
378 if (opt_->isSatisfied(c))
379 {
380 fullyOptimized = true;
381 bestSolution = solution;
382 bestCost_ = c;
383 break;
384 }
385 if (opt_->isCostBetterThan(c, bestCost_))
386 {
387 bestSolution = solution;
388 bestCost_ = c;
389 }
390 }
391 }
392 }
393
394 si_->freeState(workState);
395
396 if (bestSolution)
397 {
398 base::PlannerSolution psol(bestSolution);
399 psol.setPlannerName(getName());
400 // if the solution was optimized, we mark it as such
401 psol.setOptimized(opt_, bestCost_, fullyOptimized);
402 pdef_->addSolutionPath(psol);
403 }
404
405 OMPL_INFORM("%s: Created %u states", getName().c_str(), boost::num_vertices(g_) - nrStartStates);
406
408}
409
410void ompl::geometric::LazyPRM::uniteComponents(Vertex a, Vertex b)
411{
412 unsigned long int componentA = vertexComponentProperty_[a];
413 unsigned long int componentB = vertexComponentProperty_[b];
414 if (componentA == componentB)
415 return;
416 if (componentSize_[componentA] > componentSize_[componentB])
417 {
418 std::swap(componentA, componentB);
419 std::swap(a, b);
420 }
421 markComponent(a, componentB);
422}
423
424void ompl::geometric::LazyPRM::markComponent(Vertex v, unsigned long int newComponent)
425{
426 std::queue<Vertex> q;
427 q.push(v);
428 while (!q.empty())
429 {
430 Vertex n = q.front();
431 q.pop();
432 unsigned long int &component = vertexComponentProperty_[n];
433 if (component == newComponent)
434 continue;
435 if (componentSize_[component] == 1)
436 componentSize_.erase(component);
437 else
438 componentSize_[component]--;
439 component = newComponent;
440 componentSize_[newComponent]++;
441 boost::graph_traits<Graph>::adjacency_iterator nbh, last;
442 for (boost::tie(nbh, last) = boost::adjacent_vertices(n, g_); nbh != last; ++nbh)
443 q.push(*nbh);
444 }
445}
446
447long int ompl::geometric::LazyPRM::solutionComponent(std::pair<std::size_t, std::size_t> *startGoalPair) const
448{
449 for (std::size_t startIndex = 0; startIndex < startM_.size(); ++startIndex)
450 {
451 long int startComponent = vertexComponentProperty_[startM_[startIndex]];
452 for (std::size_t goalIndex = 0; goalIndex < goalM_.size(); ++goalIndex)
453 {
454 if (startComponent == (long int)vertexComponentProperty_[goalM_[goalIndex]])
455 {
456 startGoalPair->first = startIndex;
457 startGoalPair->second = goalIndex;
458 return startComponent;
459 }
460 }
461 }
462 return -1;
463}
464
465ompl::base::PathPtr ompl::geometric::LazyPRM::constructSolution(const Vertex &start, const Vertex &goal)
466{
467 // Need to update the index map here, becuse nodes may have been removed and
468 // the numbering will not be 0 .. N-1 otherwise.
469 unsigned long int index = 0;
470 boost::graph_traits<Graph>::vertex_iterator vi, vend;
471 for (boost::tie(vi, vend) = boost::vertices(g_); vi != vend; ++vi, ++index)
472 indexProperty_[*vi] = index;
473
474 boost::property_map<Graph, boost::vertex_predecessor_t>::type prev;
475 try
476 {
477 // Consider using a persistent distance_map if it's slow
478 boost::astar_search(
479 g_, start, [this, goal](Vertex v) { return costHeuristic(v, goal); },
480 boost::predecessor_map(prev)
481 .distance_compare([this](base::Cost c1, base::Cost c2) { return opt_->isCostBetterThan(c1, c2); })
482 .distance_combine([this](base::Cost c1, base::Cost c2) { return opt_->combineCosts(c1, c2); })
483 .distance_inf(opt_->infiniteCost())
484 .distance_zero(opt_->identityCost())
485 .visitor(AStarGoalVisitor<Vertex>(goal)));
486 }
487 catch (AStarFoundGoal &)
488 {
489 }
490 if (prev[goal] == goal)
491 throw Exception(name_, "Could not find solution path");
492
493 // First, get the solution states without copying them, and check them for validity.
494 // We do all the node validity checks for the vertices, as this may remove a larger
495 // part of the graph (compared to removing an edge).
496 std::vector<const base::State *> states(1, stateProperty_[goal]);
497 std::set<Vertex> milestonesToRemove;
498 for (Vertex pos = prev[goal]; prev[pos] != pos; pos = prev[pos])
499 {
500 const base::State *st = stateProperty_[pos];
501 unsigned int &vd = vertexValidityProperty_[pos];
502 if ((vd & VALIDITY_TRUE) == 0)
503 if (si_->isValid(st))
504 vd |= VALIDITY_TRUE;
505 if ((vd & VALIDITY_TRUE) == 0)
506 milestonesToRemove.insert(pos);
507 if (milestonesToRemove.empty())
508 states.push_back(st);
509 }
510
511 // We remove *all* invalid vertices. This is not entirely as described in the original LazyPRM
512 // paper, as the paper suggest removing the first vertex only, and then recomputing the
513 // shortest path. Howeve, the paper says the focus is on efficient vertex & edge removal,
514 // rather than collision checking, so this modification is in the spirit of the paper.
515 if (!milestonesToRemove.empty())
516 {
517 unsigned long int comp = vertexComponentProperty_[start];
518 // Remember the current neighbors.
519 std::set<Vertex> neighbors;
520 for (auto it = milestonesToRemove.begin(); it != milestonesToRemove.end(); ++it)
521 {
522 boost::graph_traits<Graph>::adjacency_iterator nbh, last;
523 for (boost::tie(nbh, last) = boost::adjacent_vertices(*it, g_); nbh != last; ++nbh)
524 if (milestonesToRemove.find(*nbh) == milestonesToRemove.end())
525 neighbors.insert(*nbh);
526 // Remove vertex from nearest neighbors data structure.
527 nn_->remove(*it);
528 // Free vertex state.
529 si_->freeState(stateProperty_[*it]);
530 // Remove all edges.
531 boost::clear_vertex(*it, g_);
532 // Remove the vertex.
533 boost::remove_vertex(*it, g_);
534 }
535 // Update the connected component ID for neighbors.
536 for (auto neighbor : neighbors)
537 {
538 if (comp == vertexComponentProperty_[neighbor])
539 {
540 unsigned long int newComponent = componentCount_++;
541 componentSize_[newComponent] = 0;
542 markComponent(neighbor, newComponent);
543 }
544 }
545 return base::PathPtr();
546 }
547
548 // start is checked for validity already
549 states.push_back(stateProperty_[start]);
550
551 // Check the edges too, if the vertices were valid. Remove the first invalid edge only.
552 std::vector<const base::State *>::const_iterator prevState = states.begin(), state = prevState + 1;
553 Vertex prevVertex = goal, pos = prev[goal];
554 do
555 {
556 Edge e = boost::lookup_edge(pos, prevVertex, g_).first;
557 unsigned int &evd = edgeValidityProperty_[e];
558 if ((evd & VALIDITY_TRUE) == 0)
559 {
560 if (si_->checkMotion(*state, *prevState))
561 evd |= VALIDITY_TRUE;
562 }
563 if ((evd & VALIDITY_TRUE) == 0)
564 {
565 boost::remove_edge(e, g_);
566 unsigned long int newComponent = componentCount_++;
567 componentSize_[newComponent] = 0;
568 markComponent(pos, newComponent);
569 return base::PathPtr();
570 }
571 prevState = state;
572 ++state;
573 prevVertex = pos;
574 pos = prev[pos];
575 } while (prevVertex != pos);
576
577 auto p(std::make_shared<PathGeometric>(si_));
578 for (std::vector<const base::State *>::const_reverse_iterator st = states.rbegin(); st != states.rend(); ++st)
579 p->append(*st);
580 return p;
581}
582
584{
585 return opt_->motionCostHeuristic(stateProperty_[u], stateProperty_[v]);
586}
587
589{
590 Planner::getPlannerData(data);
591
592 // Explicitly add start and goal states. Tag all states known to be valid as 1.
593 // Unchecked states are tagged as 0.
594 for (auto i : startM_)
596
597 for (auto i : goalM_)
599
600 // Adding edges and all other vertices simultaneously
601 foreach (const Edge e, boost::edges(g_))
602 {
603 const Vertex v1 = boost::source(e, g_);
604 const Vertex v2 = boost::target(e, g_);
606
607 // Add the reverse edge, since we're constructing an undirected roadmap
609
610 // Add tags for the newly added vertices
611 data.tagState(stateProperty_[v1], (vertexValidityProperty_[v1] & VALIDITY_TRUE) == 0 ? 0 : 1);
612 data.tagState(stateProperty_[v2], (vertexValidityProperty_[v2] & VALIDITY_TRUE) == 0 ? 0 : 1);
613 }
614}
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 a goal region that can be sampled.
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition PlannerData.h:59
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
bool getEdgeWeight(unsigned int v1, unsigned int v2, Cost *weight) const
Returns the weight of the edge between the given vertex indices. If there exists an edge between v1 a...
bool tagState(const State *st, int tag)
Set the integer tag associated with the given state. If the given state does not exist in a vertex,...
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)....
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...
bool isSetup() const
Check if setup() was called for this planner.
Definition Planner.cpp:113
PlannerInputStates pis_
Utility class to extract valid input states.
Definition Planner.h:407
void addPlannerProgressProperty(const std::string &progressPropertyName, const PlannerProgressProperty &prop)
Add a planner progress property called progressPropertyName with a property querying function prop to...
Definition Planner.h:394
PlannerSpecs specs_
The specifications of the planner (its capabilities).
Definition Planner.h:413
ProblemDefinitionPtr pdef_
The user set problem definition.
Definition Planner.h:404
const SpaceInformationPtr & getSpaceInformation() const
Get the space information this planner is using.
Definition Planner.cpp:66
std::string name_
The name of this planner.
Definition Planner.h:410
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
Return at most k neighbors, as long as they are also within a specified bound.
Make the minimal number of connections required to ensure asymptotic optimality.
void clearQuery() override
Clear the query previously loaded from the ProblemDefinition. Subsequent calls to solve() will reuse ...
Definition LazyPRM.cpp:230
static const unsigned int VALIDITY_UNKNOWN
Flag indicating validity of an edge of a vertex.
Definition LazyPRM.h:254
void clearValidity()
change the validity flag of each node and edge to VALIDITY_UNKNOWN
Definition LazyPRM.cpp:237
void setRange(double distance)
Set the maximum length of a motion to be added to the roadmap.
Definition LazyPRM.cpp:186
std::vector< Vertex > startM_
Array of start milestones.
Definition LazyPRM.h:335
unsigned long int componentCount_
Number of connected components created so far. This is used as an ID only, does not represent the act...
Definition LazyPRM.h:360
void freeMemory()
Free all the memory allocated by the planner.
Definition LazyPRM.cpp:258
bool userSetConnectionStrategy_
Flag indicating whether the employed connection strategy was set by the user (or defaults are assumed...
Definition LazyPRM.h:320
void setMaxNearestNeighbors(unsigned int k)
Convenience function that sets the connection strategy to the default one with k nearest neighbors.
Definition LazyPRM.cpp:195
base::Cost costHeuristic(Vertex u, Vertex v) const
Given two vertices, returns a heuristic on the cost of the path connecting them. This method wraps Op...
Definition LazyPRM.cpp:583
ompl::base::PathPtr constructSolution(const Vertex &start, const Vertex &goal)
Given two milestones from the same connected component, construct a path connecting them and set it a...
Definition LazyPRM.cpp:465
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition LazyPRM.cpp:245
boost::property_map< Graph, vertex_component_t >::type vertexComponentProperty_
Access the connected component of a vertex.
Definition LazyPRM.h:350
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 LazyPRM.cpp:291
std::map< unsigned long int, unsigned long int > componentSize_
The number of elements in each component in the LazyPRM roadmap.
Definition LazyPRM.h:363
static const unsigned int VALIDITY_TRUE
Flag indicating validity of an edge of a vertex.
Definition LazyPRM.h:257
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition LazyPRM.h:323
Vertex addMilestone(base::State *state)
Construct a milestone for a given state (state), store it in the nearest neighbors data structure and...
Definition LazyPRM.cpp:265
bool starStrategy_
Flag indicating whether the default connection strategy is the Star strategy.
Definition LazyPRM.h:310
Graph g_
Connectivity graph.
Definition LazyPRM.h:332
boost::property_map< Graph, boost::edge_weight_t >::type weightProperty_
Access to the weights of each Edge.
Definition LazyPRM.h:347
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 LazyPRM.cpp:588
boost::property_map< Graph, vertex_flags_t >::type vertexValidityProperty_
Access the validity state of a vertex.
Definition LazyPRM.h:353
double getRange() const
Get the range the planner is using.
Definition LazyPRM.h:158
unsigned long int milestoneCount() const
Return the number of milestones currently in the graph.
Definition LazyPRM.h:224
LazyPRM(const base::SpaceInformationPtr &si, bool starStrategy=false)
Constructor.
Definition LazyPRM.cpp:67
boost::adjacency_list_traits< boost::vecS, boost::listS, boost::undirectedS >::vertex_descriptor Vertex
The type for a vertex in the roadmap.
Definition LazyPRM.h:97
RoadmapNeighbors nn_
Nearest neighbors data structure.
Definition LazyPRM.h:329
boost::property_map< Graph, vertex_state_t >::type stateProperty_
Access to the internal base::state at each Vertex.
Definition LazyPRM.h:344
std::vector< Vertex > goalM_
Array of goal milestones.
Definition LazyPRM.h:338
void setDefaultConnectionStrategy()
Definition LazyPRM.cpp:210
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 LazyPRM.h:300
ConnectionStrategy connectionStrategy_
Function that returns the milestones to attempt connections with.
Definition LazyPRM.h:313
boost::graph_traits< Graph >::edge_descriptor Edge
The type for an edge in the roadmap.
Definition LazyPRM.h:130
long int solutionComponent(std::pair< std::size_t, std::size_t > *startGoalPair) const
Check if any pair of a start state and goal state are part of the same connected component....
Definition LazyPRM.cpp:447
boost::property_map< Graph, boost::vertex_index_t >::type indexProperty_
Access to the internal base::state at each Vertex.
Definition LazyPRM.h:341
boost::property_map< Graph, edge_flags_t >::type edgeValidityProperty_
Access the validity state of an edge.
Definition LazyPRM.h:356
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition LazyPRM.cpp:145
base::StateSamplerPtr sampler_
Sampler user for generating random in the state space.
Definition LazyPRM.h:326
base::OptimizationObjectivePtr opt_
Objective cost function for PRM graph edges.
Definition LazyPRM.h:366
ConnectionFilter connectionFilter_
Function that can reject a milestone connection.
Definition LazyPRM.h:316
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
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
This namespace includes magic constants used in various places in OMPL.
Definition Constraint.h:52
static const unsigned int DEFAULT_NEAREST_NEIGHBORS_LAZY
The number of nearest neighbors to consider by default in the construction of the PRM roadmap.
Definition LazyPRM.cpp:58
static const unsigned int MIN_ADDED_SEGMENTS_FOR_LAZY_OPTIMIZATION
When optimizing solutions with lazy planners, this is the minimum number of path segments to add befo...
Definition LazyPRM.cpp:63
Main namespace. Contains everything in this library.
Representation of a solution to a planning problem.
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.
@ EXACT_SOLUTION
The planner found an exact solution.
@ INVALID_GOAL
Invalid goal state.
@ UNRECOGNIZED_GOAL_TYPE
The goal is of a type that a planner does not recognize.
@ TIMEOUT
The planner failed to find a solution.