Loading...
Searching...
No Matches
SPARStwo.h
1/*********************************************************************
2* Software License Agreement (BSD License)
3*
4* Copyright (c) 2013, Rutgers the State University of New Jersey, New Brunswick
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 Rutgers University nor the names of its
18* contributors may be used to endorse or promote products derived
19* from this software without specific prior written permission.
20*
21* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32* POSSIBILITY OF SUCH DAMAGE.
33*********************************************************************/
34
35/* Author: Andrew Dobson */
36
37#ifndef OMPL_GEOMETRIC_PLANNERS_SPARS_TWO_
38#define OMPL_GEOMETRIC_PLANNERS_SPARS_TWO_
39
40#include "ompl/geometric/planners/PlannerIncludes.h"
41#include "ompl/datastructures/NearestNeighbors.h"
42#include "ompl/geometric/PathSimplifier.h"
43#include "ompl/util/Time.h"
44#include "ompl/util/Hash.h"
45
46#include <boost/range/adaptor/map.hpp>
47#include <unordered_map>
48#include <boost/graph/graph_traits.hpp>
49#include <boost/graph/adjacency_list.hpp>
50#include <boost/pending/disjoint_sets.hpp>
51#include <mutex>
52#include <iostream>
53#include <fstream>
54#include <utility>
55#include <vector>
56#include <map>
57
58namespace ompl
59{
60 namespace geometric
61 {
77 class SPARStwo : public base::Planner
78 {
79 public:
82 {
83 START,
84 GOAL,
85 COVERAGE,
86 CONNECTIVITY,
87 INTERFACE,
88 QUALITY,
89 };
90
92 using VertexIndexType = unsigned long;
93
95 using VertexPair = std::pair<VertexIndexType, VertexIndexType>;
96
99 {
102 base::State *pointB_{nullptr};
103
106 base::State *sigmaB_{nullptr};
107
109 double d_{std::numeric_limits<double>::infinity()};
110
112 InterfaceData() = default;
113
115 void clear(const base::SpaceInformationPtr &si)
116 {
117 if (pointA_ != nullptr)
118 {
119 si->freeState(pointA_);
120 pointA_ = nullptr;
121 }
122 if (pointB_ != nullptr)
123 {
124 si->freeState(pointB_);
125 pointB_ = nullptr;
126 }
127 if (sigmaA_ != nullptr)
128 {
129 si->freeState(sigmaA_);
130 sigmaA_ = nullptr;
131 }
132 if (sigmaB_ != nullptr)
133 {
134 si->freeState(sigmaB_);
135 sigmaB_ = nullptr;
136 }
137 d_ = std::numeric_limits<double>::infinity();
138 }
139
141 void setFirst(const base::State *p, const base::State *s, const base::SpaceInformationPtr &si)
142 {
143 if (pointA_ != nullptr)
144 si->copyState(pointA_, p);
145 else
146 pointA_ = si->cloneState(p);
147 if (sigmaA_ != nullptr)
148 si->copyState(sigmaA_, s);
149 else
150 sigmaA_ = si->cloneState(s);
151 if (pointB_ != nullptr)
152 d_ = si->distance(pointA_, pointB_);
153 }
154
156 void setSecond(const base::State *p, const base::State *s, const base::SpaceInformationPtr &si)
157 {
158 if (pointB_ != nullptr)
159 si->copyState(pointB_, p);
160 else
161 pointB_ = si->cloneState(p);
162 if (sigmaB_ != nullptr)
163 si->copyState(sigmaB_, s);
164 else
165 sigmaB_ = si->cloneState(s);
166 if (pointA_ != nullptr)
167 d_ = si->distance(pointA_, pointB_);
168 }
169 };
170
172 using InterfaceHash = std::unordered_map<VertexPair, InterfaceData>;
173
175 {
176 using kind = boost::vertex_property_tag;
177 };
178
180 {
181 using kind = boost::vertex_property_tag;
182 };
183
185 {
186 using kind = boost::vertex_property_tag;
187 };
188
204 using Graph = boost::adjacency_list<
205 boost::vecS, boost::vecS, boost::undirectedS,
206 boost::property<
208 boost::property<
209 boost::vertex_predecessor_t, VertexIndexType,
210 boost::property<boost::vertex_rank_t, VertexIndexType,
211 boost::property<vertex_color_t, GuardType,
212 boost::property<vertex_interface_data_t, InterfaceHash>>>>>,
213 boost::property<boost::edge_weight_t, base::Cost>>;
214
216 using Vertex = boost::graph_traits<Graph>::vertex_descriptor;
217
219 using Edge = boost::graph_traits<Graph>::edge_descriptor;
220
222 SPARStwo(const base::SpaceInformationPtr &si);
223
225 ~SPARStwo() override;
226
227 void setProblemDefinition(const base::ProblemDefinitionPtr &pdef) override;
228
230 void setStretchFactor(double t)
231 {
232 stretchFactor_ = t;
233 }
234
237 {
239 if (sparseDelta_ > 0.0) // setup was previously called
240 sparseDelta_ = D * si_->getMaximumExtent();
241 }
242
245 {
247 if (denseDelta_ > 0.0) // setup was previously called
248 denseDelta_ = d * si_->getMaximumExtent();
249 }
250
252 void setMaxFailures(unsigned int m)
253 {
254 maxFailures_ = m;
255 }
256
258 unsigned int getMaxFailures() const
259 {
260 return maxFailures_;
261 }
262
265 {
266 return denseDeltaFraction_;
267 }
268
271 {
273 }
274
276 double getStretchFactor() const
277 {
278 return stretchFactor_;
279 }
280
283
287 void constructRoadmap(const base::PlannerTerminationCondition &ptc, bool stopOnMaxFail);
288
302
307 void clearQuery() override;
308
309 void clear() override;
310
312 template <template <typename T> class NN>
314 {
315 if (nn_ && nn_->size() == 0)
316 OMPL_WARN("Calling setNearestNeighbors will clear all states.");
317 clear();
318 nn_ = std::make_shared<NN<Vertex>>();
319 if (isSetup())
320 setup();
321 }
322
323 void setup() override;
324
326 const Graph &getRoadmap() const
327 {
328 return g_;
329 }
330
332 unsigned int milestoneCount() const
333 {
334 return boost::num_vertices(g_);
335 }
336
337 void getPlannerData(base::PlannerData &data) const override;
338
340 void printDebug(std::ostream &out = std::cout) const;
341
343 // Planner progress property functions
344 std::string getIterationCount() const
345 {
346 return std::to_string(iterations_);
347 }
348 std::string getBestCost() const
349 {
350 return std::to_string(bestCost_.value());
351 }
352
353 protected:
355 void freeMemory();
356
359
361 bool checkAddCoverage(const base::State *qNew, std::vector<Vertex> &visibleNeighborhood);
362
364 bool checkAddConnectivity(const base::State *qNew, std::vector<Vertex> &visibleNeighborhood);
365
368 bool checkAddInterface(const base::State *qNew, std::vector<Vertex> &graphNeighborhood,
369 std::vector<Vertex> &visibleNeighborhood);
370
372 bool checkAddPath(Vertex v);
373
375 void resetFailures();
376
378 void findGraphNeighbors(base::State *st, std::vector<Vertex> &graphNeighborhood,
379 std::vector<Vertex> &visibleNeighborhood);
380
382 void approachGraph(Vertex v);
383
385 Vertex findGraphRepresentative(base::State *st);
386
388 void findCloseRepresentatives(base::State *workArea, const base::State *qNew, Vertex qRep,
389 std::map<Vertex, base::State *> &closeRepresentatives,
390 const base::PlannerTerminationCondition &ptc);
391
393 void updatePairPoints(Vertex rep, const base::State *q, Vertex r, const base::State *s);
394
396 void computeVPP(Vertex v, Vertex vp, std::vector<Vertex> &VPPs);
397
399 void computeX(Vertex v, Vertex vp, Vertex vpp, std::vector<Vertex> &Xs);
400
402 VertexPair index(Vertex vp, Vertex vpp);
403
405 InterfaceData &getData(Vertex v, Vertex vp, Vertex vpp);
406
408 void distanceCheck(Vertex rep, const base::State *q, Vertex r, const base::State *s, Vertex rp);
409
412 void abandonLists(base::State *st);
413
416 Vertex addGuard(base::State *state, GuardType type);
417
419 void connectGuards(Vertex v, Vertex vp);
420
424 bool haveSolution(const std::vector<Vertex> &starts, const std::vector<Vertex> &goals,
425 base::PathPtr &solution);
426
428 void checkForSolution(const base::PlannerTerminationCondition &ptc, base::PathPtr &solution);
429
432 bool reachedTerminationCriterion() const;
433
435 bool reachedFailureLimit() const;
436
439 base::PathPtr constructSolution(Vertex start, Vertex goal) const;
440
443 bool sameComponent(Vertex m1, Vertex m2);
444
447 double distanceFunction(const Vertex a, const Vertex b) const
448 {
449 return si_->distance(stateProperty_[a], stateProperty_[b]);
450 }
451
453 base::ValidStateSamplerPtr sampler_;
454
456 std::shared_ptr<NearestNeighbors<Vertex>> nn_;
457
460
462 std::vector<Vertex> startM_;
463
465 std::vector<Vertex> goalM_;
466
469
471 double stretchFactor_{3.};
472
475
479
481 unsigned int maxFailures_{5000};
482
484 unsigned int nearSamplePoints_;
485
487 boost::property_map<Graph, vertex_state_t>::type stateProperty_;
488
491
493 boost::property_map<Graph, boost::edge_weight_t>::type weightProperty_;
494
496 boost::property_map<Graph, vertex_color_t>::type colorProperty_;
497
499 boost::property_map<Graph, vertex_interface_data_t>::type interfaceDataProperty_;
500
502 boost::disjoint_sets<boost::property_map<Graph, boost::vertex_rank_t>::type,
503 boost::property_map<Graph, boost::vertex_predecessor_t>::type> disjointSets_;
506
508 bool addedSolution_{false};
509
511 unsigned int consecutiveFailures_{0};
512
514 double sparseDelta_{0.};
515
517 double denseDelta_{0.};
518
520 mutable std::mutex graphMutex_;
521
523 base::OptimizationObjectivePtr opt_;
524
528
530 // Planner progress properties
532 long unsigned int iterations_{0ul};
534 base::Cost bestCost_{std::numeric_limits<double>::quiet_NaN()};
535 };
536 }
537}
538
539#endif
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition Cost.h:48
double value() const
The value of the cost.
Definition Cost.h:56
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Base class for a planner.
Definition Planner.h:216
bool isSetup() const
Check if setup() was called for this planner.
Definition Planner.cpp:113
SpaceInformationPtr si_
The space information for which planning is done.
Definition Planner.h:410
Definition of an abstract state.
Definition State.h:50
A shared pointer wrapper for ompl::geometric::PathSimplifier.
SPArse Roadmap Spanner Version 2.0
Definition SPARStwo.h:78
bool reachedFailureLimit() const
Returns whether we have reached the iteration failures limit, maxFailures_.
Definition SPARStwo.cpp:209
bool addedSolution_
A flag indicating that a solution has been added during solve()
Definition SPARStwo.h:508
boost::property_map< Graph, vertex_color_t >::type colorProperty_
Access to the colors for the vertices.
Definition SPARStwo.h:496
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 SPARStwo.cpp:698
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
Definition SPARStwo.h:313
std::vector< Vertex > goalM_
Array of goal milestones.
Definition SPARStwo.h:465
unsigned long VertexIndexType
The type used internally for representing vertex IDs.
Definition SPARStwo.h:92
double denseDeltaFraction_
Maximum range for allowing two samples to support an interface as a fraction of maximum extent.
Definition SPARStwo.h:478
const Graph & getRoadmap() const
Retrieve the computed roadmap.
Definition SPARStwo.h:326
boost::property_map< Graph, vertex_interface_data_t >::type interfaceDataProperty_
Access to the interface pair information for the vertices.
Definition SPARStwo.h:499
void setDenseDeltaFraction(double d)
Sets interface support tolerance as a fraction of max. extent.
Definition SPARStwo.h:244
void resetFailures()
A reset function for resetting the failures count.
Definition SPARStwo.cpp:547
void setStretchFactor(double t)
Sets the stretch factor.
Definition SPARStwo.h:230
double getSparseDeltaFraction() const
Retrieve the sparse graph visibility range delta.
Definition SPARStwo.h:270
bool checkAddConnectivity(const base::State *qNew, std::vector< Vertex > &visibleNeighborhood)
Checks to see if the sample needs to be added to ensure connectivity.
Definition SPARStwo.cpp:395
void freeMemory()
Free all the memory allocated by the planner.
Definition SPARStwo.cpp:147
long unsigned int iterations_
A counter for the number of iterations of the algorithm.
Definition SPARStwo.h:532
boost::graph_traits< Graph >::edge_descriptor Edge
Edge in Graph.
Definition SPARStwo.h:219
base::Cost bestCost_
Best cost found so far by algorithm.
Definition SPARStwo.h:534
double sparseDelta_
Maximum visibility range for nodes in the graph.
Definition SPARStwo.h:514
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 SPARStwo.cpp:428
double getStretchFactor() const
Retrieve the spanner's set stretch factor.
Definition SPARStwo.h:276
unsigned int maxFailures_
The number of consecutive failures to add to the graph before termination.
Definition SPARStwo.h:481
double denseDelta_
Maximum range for allowing two samples to support an interface.
Definition SPARStwo.h:517
bool checkAddPath(Vertex v)
Checks vertex v for short paths through its region and adds when appropriate.
Definition SPARStwo.cpp:458
void approachGraph(Vertex v)
Approaches the graph from a given vertex.
Definition SPARStwo.cpp:566
void setSparseDeltaFraction(double D)
Sets vertex visibility range as a fraction of max. extent.
Definition SPARStwo.h:236
void computeVPP(Vertex v, Vertex vp, std::vector< Vertex > &VPPs)
Computes all nodes which qualify as a candidate v" for v and vp.
Definition SPARStwo.cpp:660
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 SPARStwo.cpp:204
unsigned int getMaxFailures() const
Retrieve the maximum consecutive failure limit.
Definition SPARStwo.h:258
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 SPARStwo.cpp:648
unsigned int consecutiveFailures_
A counter for the number of consecutive failed iterations of the algorithm.
Definition SPARStwo.h:511
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 SPARStwo.h:503
GuardType
Enumeration which specifies the reason a guard is added to the spanner.
Definition SPARStwo.h:82
PathSimplifierPtr psimp_
A path simplifier used to simplify dense paths added to the graph.
Definition SPARStwo.h:490
std::pair< VertexIndexType, VertexIndexType > VertexPair
Pair of vertices which support an interface.
Definition SPARStwo.h:95
RNG rng_
Random number generator.
Definition SPARStwo.h:505
boost::property_map< Graph, vertex_state_t >::type stateProperty_
Access to the internal base::state at each Vertex.
Definition SPARStwo.h:487
std::vector< Vertex > startM_
Array of start milestones.
Definition SPARStwo.h:462
void constructRoadmap(const base::PlannerTerminationCondition &ptc)
While the termination condition permits, construct the spanner graph.
Definition SPARStwo.cpp:231
Graph g_
Connectivity graph.
Definition SPARStwo.h:459
std::mutex graphMutex_
Mutex to guard access to the Graph member (g_)
Definition SPARStwo.h:520
base::OptimizationObjectivePtr opt_
Objective cost function for PRM graph edges.
Definition SPARStwo.h:523
void printDebug(std::ostream &out=std::cout) const
Print debug information about planner.
Definition SPARStwo.cpp:825
std::shared_ptr< NearestNeighbors< Vertex > > nn_
Nearest neighbors data structure.
Definition SPARStwo.h:456
VertexPair index(Vertex vp, Vertex vpp)
Rectifies indexing order for accessing the vertex data.
Definition SPARStwo.cpp:683
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 SPARStwo.cpp:875
base::PathPtr constructSolution(Vertex start, Vertex goal) const
Given two milestones from the same connected component, construct a path connecting them and set it a...
Definition SPARStwo.cpp:790
double stretchFactor_
Stretch Factor as per graph spanner literature (multiplicative bound on path quality)
Definition SPARStwo.h:471
void abandonLists(base::State *st)
When a new guard is added at state st, finds all guards who must abandon their interface information ...
Definition SPARStwo.cpp:743
void checkForSolution(const base::PlannerTerminationCondition &ptc, base::PathPtr &solution)
Definition SPARStwo.cpp:365
void checkQueryStateInitialization()
Check that the query vertex is initialized (used for internal nearest neighbor searches)
Definition SPARStwo.cpp:288
void connectGuards(Vertex v, Vertex vp)
Connect two guards in the roadmap.
Definition SPARStwo.cpp:778
void findCloseRepresentatives(base::State *workArea, 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 SPARStwo.cpp:598
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition SPARStwo.cpp:87
boost::graph_traits< Graph >::vertex_descriptor Vertex
Vertex in Graph.
Definition SPARStwo.h:216
bool haveSolution(const std::vector< Vertex > &starts, const std::vector< Vertex > &goals, base::PathPtr &solution)
Check if there exists a solution, i.e., there exists a pair of milestones such that the first is in s...
Definition SPARStwo.cpp:166
unsigned int nearSamplePoints_
Number of sample points to use when trying to detect interfaces.
Definition SPARStwo.h:484
InterfaceData & getData(Vertex v, Vertex vp, Vertex vpp)
Retrieves the Vertex data associated with v,vp,vpp.
Definition SPARStwo.cpp:693
base::ValidStateSamplerPtr sampler_
Sampler user for generating valid samples in the state space.
Definition SPARStwo.h:453
double sparseDeltaFraction_
Maximum visibility range for nodes in the graph as a fraction of maximum extent.
Definition SPARStwo.h:474
boost::property_map< Graph, boost::edge_weight_t >::type weightProperty_
Access to the weights of each Edge.
Definition SPARStwo.h:493
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 SPARStwo.cpp:298
Vertex findGraphRepresentative(base::State *st)
Finds the representative of the input state, st
Definition SPARStwo.cpp:580
double getDenseDeltaFraction() const
Retrieve the dense graph interface support delta.
Definition SPARStwo.h:264
void setMaxFailures(unsigned int m)
Sets the maximum failures until termination.
Definition SPARStwo.h:252
boost::adjacency_list< boost::vecS, boost::vecS, boost::undirectedS, boost::property< vertex_state_t, base::State *, boost::property< boost::vertex_predecessor_t, VertexIndexType, boost::property< boost::vertex_rank_t, VertexIndexType, boost::property< vertex_color_t, GuardType, boost::property< vertex_interface_data_t, InterfaceHash > > > > >, boost::property< boost::edge_weight_t, base::Cost > > Graph
The underlying roadmap graph.
Definition SPARStwo.h:213
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 SPARStwo.cpp:669
void clearQuery() override
Clear the query previously loaded from the ProblemDefinition. Subsequent calls to solve() will reuse ...
Definition SPARStwo.cpp:128
std::unordered_map< VertexPair, InterfaceData > InterfaceHash
the hash which maps pairs of neighbor points to pairs of states
Definition SPARStwo.h:172
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 SPARStwo.cpp:386
bool reachedTerminationCriterion() const
Returns true if we have reached the iteration failures limit, maxFailures_ or if a solution was added...
Definition SPARStwo.cpp:214
unsigned int milestoneCount() const
Get the number of vertices in the sparse roadmap.
Definition SPARStwo.h:332
~SPARStwo() override
Destructor.
Definition SPARStwo.cpp:82
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition SPARStwo.cpp:135
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 SPARStwo.h:447
Vertex queryVertex_
Vertex for performing nearest neighbor queries.
Definition SPARStwo.h:468
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 SPARStwo.cpp:760
void findGraphNeighbors(base::State *st, std::vector< Vertex > &graphNeighborhood, std::vector< Vertex > &visibleNeighborhood)
Finds visible nodes in the graph near st.
Definition SPARStwo.cpp:552
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 SPARStwo.cpp:839
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition Console.h:66
Main namespace. Contains everything in this library.
A class to store the exit status of Planner::solve()
Interface information storage class, which does bookkeeping for criterion four.
Definition SPARStwo.h:99
double d_
Last known distance between the two interfaces supported by points_ and sigmas.
Definition SPARStwo.h:109
base::State * sigmaA_
States which lie just outside the visibility region of a vertex and support an interface.
Definition SPARStwo.h:105
base::State * pointA_
States which lie inside the visibility region of a vertex and support an interface.
Definition SPARStwo.h:101
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 SPARStwo.h:141
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 SPARStwo.h:156
void clear(const base::SpaceInformationPtr &si)
Clears the given interface data.
Definition SPARStwo.h:115