A Unifying Formalism for Shortest Path Problems with Expensive Edge Evaluations via Lazy Best-First Search over Paths with Edge Selectors Christopher M. Dellin and Siddhartha S. Srinivasa The Robotics Institute, Carnegie Mellon University {cdellin, siddh}@cs.cmu.edu Abstract While the shortest path problem has myriad applications, the computational efficiency of suitable algorithms depends inti- mately on the underlying problem domain. In this paper, we focus on domains where evaluating the edge weight function dominates algorithm running time. Inspired by approaches in robotic motion planning, we define and investigate the Lazy Shortest Path class of algorithms which is differentiated by the choice of an edge selector function. We show that sev- eral algorithms in the literature are equivalent to this lazy al- gorithm for appropriate choice of this selector. Further, we propose various novel selectors inspired by sampling and sta- tistical mechanics, and find that these selectors outperform existing algorithms on a set of example problems. 1 Introduction Graphs provide a powerful abstraction capable of represent- ing problems in a wide variety of domains from computer networking to puzzle solving to robotic motion planning. In particular, many important problems can be captured as shortest path problems (Figure 1), wherein a path p∗of min- imal length is desired between two query vertices through a graph G with respect to an edge weight function w. Despite the expansive applicability of this single abstrac- tion, there exist a wide variety of algorithms in the literature for solving the shortest path problem efficiently. This is be- cause the measure of computational efficiency, and therefore the correct choice of algorithm, is inextricably tied to the un- derlying problem domain. The computational costs incurred by an algorithm can be broadly categorized into three sources corresponding to the blocks in Figure 1. One such source consists of queries on the structure of the graph G itself. The most commonly dis- cussed such operation, expanding a vertex (determining its successors), is especially fundamental when the graph is rep- resented implicitly, e.g. for domains with large graphs such as the 15-puzzle or Rubik’s cube. It is with respect to ver- tex expansions that A* (Hart, Nilsson, and Raphael 1968) is optimally efficient. A second source of computational cost consists of main- taining ordered data structures inside the algorithm it- self, which is especially important for problems with large Presented at ICAPS 2016, London. This extended version includes proofs and timing results in the appendix. Graph G = (V, E) Weight Function w : E →[0, +∞] Shortest Path Algorithm Query u Path p∗ Figure 1: While solving a shortest path query, a shortest path algorithm incurs computation cost from three sources: ex- amining the structure of the graph G, evaluating the edge weight function w, and maintaining internal data structures. branching factors. For such domains, approaches such as partial expansion (Yoshizumi, Miura, and Ishida 2000) or it- erative deepening (Korf 1985) significantly reduce the num- ber of vertices generated and stored by either selectively fil- tering surplus vertices from the frontier, or by not storing the frontier at all. The third source of computational cost arises not from reasoning over the structure of G, but instead from evaluat- ing the edge weight function w (i.e. we treat discovering an out-edge and determining its weight separately). Consider for example the problem of articulated robotic motion plan- ning using roadmap methods (Kavraki et al. 1996). While these graphs are often quite small (fewer than 105 vertices), determining the weight of each edge requires performing many collision and distance computations for the complex geometry of the robot and environment, resulting in plan- ning times of multiple seconds to find a path. In this paper, we consider problem domains in which eval- uating the edge weight function w dominates algorithm run- ning time and investigate the following research question: How can we minimize the number of edges we need to evaluate to answer shortest-path queries? We make three primary contributions. First, inspired by lazy collision checking techniques from robotic motion planning (Bohlin and Kavraki 2000), we formulate a class of shortest-path algorithms that is well-suited to problem do- mains with expensive edge evaluations. Second, we show that several existing algorithms in the literature can be ex- pressed as special cases of this algorithm. Third, we show that the extensibility afforded by the algorithm allows for arXiv:1603.03490v2 [cs.DS] 14 Jun 2016 Algorithm 1 Lazy Shortest Path (LazySP) 1: function LAZYSHORTESTPATH(G, u, w, west) 2: Eeval ←∅ 3: wlazy(e) ←west(e) ∀e ∈E 4: loop 5: pcandidate ←SHORTESTPATH(G, u, wlazy) 6: if pcandidate ⊆Eeval then 7: return pcandidate 8: Eselected ←SELECTOR(G, pcandidate) 9: for e ∈Eselected \ Eeval do 10: wlazy(e) ←w(e) ▷Evaluate (expensive) 11: Eeval ←Eeval ∪e novel edge evaluation strategies, which can outperform ex- isting algorithms over a set of example problems. 2 Lazy Shortest Path Algorithm We describe a lazy approach to finding short paths which is well-suited to domains with expensive edge evaluations. Problem Definition A path p in a graph G = (V, E) is composed of a sequence of adjacent edges connecting two endpoint vertices. Given an edge weight function w : E →[0, +∞], the length of the path with respect to w is then: len(p, w) = X e∈p w(e). (1) Given a single-pair planning query u : (vstart, vgoal) inducing a set of satisfying paths Pu, the shortest-path problem is: p∗= arg min p ∈Pu len(p, w). (2) A shortest-path algorithm computes p∗given (G, u, w). Many such algorithms have been proposed to efficiently ac- commodate a wide array of underlying problem domains. The well-known principle of best-first search (BFS) is com- monly employed to select vertices for expansion so as to minimize such expansions while guaranteeing optimality. Since we seek to minimize edge evaluations, we apply BFS to the question of selecting candidate paths in G for evalua- tion. The resulting algorithm, Lazy Shortest Path (LazySP), is presented in Algorithm 1, and can be applied to graphs defined implicitly or explicitly. The Algorithm We track evaluated edges with the set Eeval. We are given an estimator function west of the true edge weight w. This estimator is inexpensive to compute (e.g. edge length or even 0). We then define a lazy weight function wlazy which returns the true weight of an evaluated edge and otherwise uses the inexpensive estimator west. At each iteration of the search, the algorithm uses wlazy to compute a candidate path pcandidate by calling an existing solver SHORTESTPATH (note that this invocation requires no evaluations of w). Once a candidate path has been found, it is Algorithm 2 Various Simple LazySP Edge Selectors 1: function SELECTEXPAND(G, pcandidate) 2: efirst ←first unevaluated e ∈pcandidate 3: vfrontier ←G.source(efirst) 4: Eselected ←G.out edges(vfrontier) 5: return Eselected 6: function SELECTFORWARD(G, pcandidate) 7: return {first unevaluated e ∈pcandidate} 8: function SELECTREVERSE(G, pcandidate) 9: return {last unevaluated e ∈pcandidate} 10: function SELECTALTERNATE(G, pcandidate) 11: if LazySP iteration number is odd then 12: return {first unevaluated e ∈pcandidate} 13: else 14: return {last unevaluated e ∈pcandidate} 15: function SELECTBISECTION(G, pcandidate) 16: return  unevaluated e ∈pcandidate furthest from nearest evaluated edge  returned if it is fully evaluated. Otherwise, an edge selector is employed which selects graph edge(s) for evaluation. The true weights of these edges are then evaluated (incurring the requisite computational cost), and the algorithm repeats. LazySP is complete and optimal: Theorem 1 (Completeness of LazySP) If the graph G is finite, SHORTESTPATH is complete, and the set Eselected re- turned by SELECTOR returns at least one unevaluated edge on pcandidate, then LAZYSHORTESTPATH is complete. Theorem 2 (Optimality of LazySP) If west is chosen such that west(e) ≤ϵ w(e) for some parameter ϵ ≥1 and LAZYSHORTESTPATH terminates with some path pret, then len(pret, w) ≤ϵ ℓ∗with ℓ∗the length of an optimal path. The optimality of LazySP depends on the admissibility of west in the same way that the optimality of A* depends on the admissibility of its goal heuristic h. Theorem 2 estab- lishes the general bounded suboptimality of LazySP w.r.t. the inflation parameter ϵ. While our theoretical results (e.g. equivalences) hold for any choice of ϵ, for clarity our ex- amples and experimental results focus on cases with ϵ = 1. Proofs are available in the appendix. The Edge Selector: Key to Efficiency The LazySP algorithm exhibits a rough similarity to optimal replanning algorithms such as D* (Stentz 1994) which plan a sequence of shortest paths for a mobile robot as new edge weights are discovered during its traverse. D* treats edge changes passively as an aspect of the problem setting (e.g. a sensor with limited range). The key difference is that our problem setting treats edge evaluations as an active choice that can be exploited. While any choice of edge selector that meets the conditions above will lead to an algorithm that is complete and optimal, its efficiency is dictated by the choice of this selector. This mo- tivates the theoretical and empirical investigation of different edge selectors in this paper. 30 20 10 (a) Expand[77] 10 (b) Forward[34] 10 (c) Reverse[24] 10 (d) Alternate[23] 10 (e) Bisection[25] 10 (f) WeightSamp[22] 10 (g) Partition[22] Figure 2: Snapshots of the LazySP algorithm using each edge selector discussed in this paper on the same obstacle roadmap graph problem, with start ( ) and goal ( ). At top, the algorithms after evaluating five edges (evaluated edges labeled as valid or invalid). At middle, the final set of evaluated edges. At bottom, for each unique path considered from left to right, the number of edges on the path that are already evaluated, evaluated and valid, evaluated and invalid, and unevaluated. The total number of edges evaluated is noted in brackets. Note that the scale on the Expand plot has been adjusted because the selector evaluates many edges not on the candidate path at each iteration. Simple selectors. We codify five common strategies in Al- gorithm 2. The Expand selector captures the edge weights that are evaluated during a conventional vertex expansion. The selector identifies the first unevaluated edge efirst on the candidate path, and considers the source vertex of this edge a frontier vertex. It then selects all out-edges of this frontier vertex for evaluation. The Forward and Reverse selectors se- lect the first and last unevaluated edge on the candidate path, respectively (note that Forward returns a subset of Expand). The Alternate selector simply alternates between Forward and Reverse on each iteration. This can be motivated by both bidirectional search algorithms as well as motion plan- ning algorithms such as RRT-Connect (Kuffner and LaValle 2000) which tend to perform well w.r.t. state evaluations. The Bisection selector chooses among those unevaluated edges the one furthest from an evaluated edge on the candi- date path. This selector is roughly analogous to the collision checking strategy employed by the Lazy PRM (Bohlin and Kavraki 2000) as applied to our problem on abstract graphs. In the following section, we demonstrate that instances of LazySP using simple selectors yield equivalent results to ex- isting vertex algorithms. We then discuss two more sophis- ticated selectors motivated by weight function sampling and statistical mechanics. 3 Edge Equivalence to A* Variants In the previous section, we introduced LazySP as the path- selection analogue to BFS vertex-selection algorithms. In this section, we make this analogy more precise. In partic- ular, we show that LazySP-Expand is edge-equivalent to a LazySP Existing Selector Algorithm Result Expand (Weighted) A* Edge-equivalent (Theorems 3, 4) Forward Lazy Weighted A* Edge-equivalent (Theorems 5, 6) Alternate Bidirectional Heuristic Conjectured Front-to-Front Algorithm Table 1: LazySP equivalence results. The A*, LWA*, and BHFFA algorithms use reopening and the dynamic hlazy heuristic (4). variant of A* (and Weighted A*), and that LazySP-Forward is edge-equivalent to a variant of Lazy Weighted A* (see Table 1). It is important to be specific about the conditions under which these equivalences arise, which we detail here. Proofs are available in the appendix. Edge equivalence. We say that two algorithms are edge- equivalent if they evaluate the same edges in the same order. We consider an algorithm to have evaluated an edge the first time the edge’s true weight is requested. Arbitrary tiebreaking. For some graphs, an algorithm may have multiple allowable choices at each iteration (e.g. LazySP with multiple candidate shortest paths, or A* with multiple vertices in OPEN with lowest f-value). We will say that algorithm A is equivalent to algorithm B if for any Pcandidate (LazySP) Scandidate (A*) Vfrontier Figure 3: Illustration of the equivalence between A* and LazySP-Expand. After evaluating the same set of edges, the next edges to be evaluated by each algorithm can both be expressed as a surjective mapping onto a common set of un- expanded frontier vertices. choice available to A, there exists an allowable choice avail- able to B such that the same edge(s) are evaluated by each. A* with reopening. We show equivalence to variants of A* and Lazy Weighted A* that do not use a CLOSED list to prevent vertices from being visited more than once. A* with a dynamic heuristic. In order to apply A* and Lazy Weighted A* to our problem, we need a goal heuristic over vertices. The most simple may be hest(v) = min p:v→vg len(p, west). (3) Note that the value of this heuristic could be computed as a pre-processing step using Dijkstra’s algorithm (Dijkstra 1959) before iterations begin. However, in order for the equivalences to hold, we require the use of the lazy heuristic hlazy(v) = min p:v→vg len(p, wlazy). (4) This heuristic is dynamic in that it depends on wlazy which changes as edges are evaluated. Therefore, heuristic values must be recomputed for all affected vertices on OPEN after each iteration. Equivalence to A* We show that the LazySP-Expand algorithm is edge- equivalent to a variant of the A* shortest-path algorithm. We make use of two invariants that are maintained during the progression of A*. Invariant 1 If v is discovered by A* and v′ is undiscovered, with v′ a successor of v, then v is on OPEN. Invariant 2 If v and v′ are discovered by A*, with v′ a suc- cessor of v, and g[v] + w(v, v′) < g[v′], then v is on OPEN. When we say a vertex is discovered, we mean that it is either on OPEN or CLOSED. Note that Invariant 2 holds because we allow vertices to be reopened; without reopening (and with an inconsistent heuristic), later finding a cheaper path to v (and not reopening v′) would invalidate the invariant. We will use the goal heuristic hlazy from (4). Note that if an admissible edge weight estimator ˆw exists (that is, ˆw ≤ w), then our A* can approximate the Weighted A* algorithm (Pohl 1970) with parameter ϵ by using west = ϵ ˆw, and the suboptimality bound from Theorem 2 holds. Equivalence. In order to show edge-equivalence, we con- sider the case where both algorithms are beginning a new iteration having so far evaluated the same set of edges. LazySP-Expand has some set Pcandidate of allowable can- didate paths minimizing len(p, wlazy); the Expand selector will then identify a vertex on the chosen path for expansion. A* will iteratively select a set of vertices from OPEN to expand. Because it is possible that a vertex is expanded mul- tiple times (and only the first expansion results in edge eval- uations), we group iterations of A* into sequences, where each sequence s consists of (a) zero or more vertices from OPEN that have already been expanded, followed by (b) one vertex from OPEN that is to be expanded for the first time. We show that both the set of allowable candidate paths Pcandidate available to LazySP-Expand and the set of allow- able candidate vertex sequences Scandidate available to A* map surjectively to the same set of unexpanded frontier ver- tices Vfrontier as illustrated in Figure 3. This is established by way of Theorems 3 and 4 below. Theorem 3 If LazySP-Expand and A* have evaluated the same set of edges, then for any candidate path pcandidate cho- sen by LazySP yielding frontier vertex vfrontier, there exists an allowable A* sequence scandidate which also yields vfrontier. Theorem 4 If LazySP-Expand and A* have evaluated the same set of edges, then for any candidate sequence scandidate chosen by A* yielding frontier vertex vfrontier, there exists an allowable LazySP path pcandidate which also yields vfrontier. Equivalence to Lazy Weighted A* In a conventional vertex expansion algorithm, determining a successor’s cost is a function of both the cost of the edge and the value of the heuristic. If either of these components is expensive to evaluate, an algorithm can defer its compu- tation by maintaining the successor on the frontier with an approximate cost until it is expanded. The Fast Downward algorithm (Helmert 2006) is motivated by expensive heuris- tic evaluations in planning, whereas the Lazy Weighted A* (LWA*) algorithm (Cohen, Phillips, and Likhachev 2014) is motivated by expensive edge evaluations in robotics. We show that the LazySP-Forward algorithm is edge- equivalent to a variant of the Lazy Weighted A* shortest- path algorithm. For a given candidate path, the Forward se- lector returns the first unevaluated edge. Variant of Lazy Weighted A*. We reproduce a variant of LWA* without a CLOSED list in Algorithm 3. For the purposes of our analysis, the reproduction differs from the original presentation, and we detail those differences here. With the exception of the lack of CLOSED, the differences do not affect the behavior of the algorithm. The most obvious difference is that we present the orig- inal OPEN list as separate vertex (Qv) and edge (Qe) pri- ority queues, with sorting keys shown on lines 3 and 4. A vertex v in the original OPEN with trueCost(v) = true corresponds to a vertex v in Qv, whereas a vertex v′ in the original OPEN with trueCost(v′) = false (and parent v) corresponds to an edge (v, v′) in Qe. Use of the edge queue Algorithm 3 Lazy Weighted A* (without CLOSED list) 1: function LAZYWEIGHTEDA*(G, w, ˆw, h) 2: g[vstart] ←0 ▷For uninitialized, g[v] = ∞ 3: Qv ←{vstart} ▷Key: g[v] + h(v) 4: Qe ←∅ ▷Key: g[v] + ˆw(v, v′) + h(v′) 5: while min(Qv.TopKey, Qe.TopKey) < g[vgoal] do 6: if Qv.TopKey ≤Qe.TopKey then 7: v ←Qv.Pop() 8: for v′ ∈G.GetSuccessors(v) do 9: Qe.Insert((v, v′)) 10: else 11: (v, v′) ←Qe.Pop() 12: if g[v′] ≤g[v] + ˆw(v, v′) then 13: continue 14: gnew ←g[v] + w(v, v′) ▷evaluate 15: if gnew < g[v′] then 16: g[v′] = gnew 17: Qv.Insert(v′) obviates the need for duplicate vertices on OPEN with dif- ferent parents and the conf(v) test for identifying such du- plicates. This presentation also highlights the similarity be- tween LWA* and the inner loop of the Batch Informed Trees (BIT*) algorithm (Gammell, Srinivasa, and Barfoot 2015). The second difference is that the edge usefulness test (line 12 of the original algorithm) has been moved from before inserting into OPEN to after being popped from OPEN, but before being evaluated (line 12 of Algorithm 3). This change is partially in compensation for removing the CLOSED list. This adjustment does not affect the edges evaluated. We make use of an invariant that is maintained during the progression of Lazy Weighted A*. Invariant 3 For all vertex pairs v and v′, with v′ a succes- sor of v, if g[v] + max(w(v, v′), ˆw(v, v′)) < g[v′], then ei- ther vertex v is on Qv or edge (v, v′) is on Qe. We will use h(v) = hlazy(v) from (4) and ˆw = wlazy. Note that the use of these dynamic heuristics requires that the Qv and Qe be resorted after every edge is evaluated. Equivalence. The equivalence follows similarly to that for A* above. Given the same set of edges evaluated, the set of allowable next evaluations is identical for each algorithm. Theorem 5 If LazySP-Forward and LWA* have evaluated the same set of edges, then for any allowable candidate path pcandidate chosen by LazySP yielding first unevaluated edge eab, there exists an allowable LWA* sequence scandidate which also yields eab. Theorem 6 If LazySP-Forward and LWA* have evaluated the same set of edges, then for any allowable sequence of vertices and edges scandidate considered by LWA* yielding evaluated edge eab, there exists an allowable LazySP can- didate path pcandidate which also yields eab. Relation to Bidirectional Heuristic Search LazySP-Alternate chooses unevaluated edges from either the beginning or the end of the candidate path at each it- known edges ? path distribution . . . edge indicator distributions Figure 4: Illustration of maximum edge probability selec- tors. A distribution over paths (usually conditioned on the known edge evaluations) induces on each edge e a Bernoulli distribution with parameter p(e) giving the probability that it belongs to the path. The selector chooses the edge with the largest such probability. Algorithm 4 Maximum Edge Probability Selector (for WeightSamp and Partition path distributions) 1: function SELECTMAXEDGEPROB(G, pcandidate, Dp) 2: p(e) ←Pr( e ∈P ) for P ∼Dp 3: emax ←unevaluated e ∈pcandidate maximizing p(e) 4: return {emax} eration. We conjecture that an alternating version of the Ex- pand selector is edge-equivalent to the Bidirectional Heuris- tic Front-to-Front Algorithm (Sint and de Champeaux 1977) for appropriate lazy vertex pair heuristic, and that LazySP- Alternate is edge-equivalent to a bidirectional LWA*. 4 Novel Edge Selectors Because we are conducting a search over paths, we are free to implement selectors which are not constrained to evalu- ate edges in any particular order (i.e. to maintain evaluated trees rooted at the start and goal vertices). In this section, we describe a novel class of edge selectors which is designed to reduce the total number of edges evaluated during the course of the LazySP algorithm. These selectors operate by maintaining a distribution over the set of potential paths P at each iteration of the algorithm (see Figure 4). Such a path distribution induces a Bernoulli distribution for each edge e which indicates its probability p(e) to lie on the potential path; at each iteration, the selectors then choose the unevalu- ated edge that maximizes this edge indicator probability (Al- gorithm 4). The two selectors described in this section differ with respect to how they maintain this distribution over po- tential paths. Weight Function Sampling Selector The first selector, WeightSamp, is motivated by the intuition that it is preferable to evaluate edges that are most likely to lie on the true shortest path. Therefore, it computes its path distribution Dp by performing shortest path queries on sampled edge weight functions drawn from a distribution Dw. This edge weight distribution is conditioned on the the known weights of all previously evaluated edges Eeval: Dp : SP(w) for w ∼Dw(Eeval). (5) known edges obstacle distribution . . . weight fn distribution . . . path distribution . . . Figure 5: The WeightSamp selector uses the path distribu- tion induced by solving the shortest path problem on a dis- tribution over possible edge weight functions Dw. In this ex- ample, samples from Dw are computed by drawing samples from DO, the distribution of obstacles that are consistent with the known edge evaluations. For example, the distribution Dw might consist of the edge weights induced by a model of the distribution of en- vironment obstacles (Figure 5). Since this obstacle distribu- tion is conditioned on the results of known edge evaluations, we consider the subset of worlds which are consistent with the edges we have evaluated so far. However, depending on the fidelity of this model, solving the corresponding short- est path problem for a given sampled obstacle arrangement might require as much computation as solving the origi- nal problem, since it requires computing the resulting edge weights. In practice, we can approximate Dw by assuming that each edge is independently distributed. Partition Function Selector While the WeightSamp selector captures the intuition that it is preferable to focus edge evaluations in areas that are use- ful for many potential paths, the computational cost required to calculate it at each iteration may render it intractable. One candidate path distribution that is more efficient to compute has a density function which follows an exponential form: Dp : fP (p) ∝exp(−β len(p, wlazy)). (6) In other words, we consider all potential paths P between the start and goal vertices, with shorter paths assigned more probability than longer ones (with positive parameter β). We call this the Partition selector because this distribution is closely related to calculating partition functions from sta- tistical mechanics. The corresponding partition function is: Z(P) = X p∈P exp(−β len(p, wlazy)). (7) Note that the edge indicator probability required in Algo- rithm 4 can then be written: p(e) = 1 −Z(P \ e) Z(P) . (8) (a) Initial p(e) scores on a constant-weight grid with β: 50, 33, 28 (b) Initial p(e) scores with ∞-weight obstacles with β: 50, 33, 28 (c) Initial p(e) scores (d) Scores after five evaluations Figure 6: Examples of the Partition selector’s p(e) edge score function. (a) With no known obstacles, a high β as- signs near-unity score to only edges on the shortest path; as β decreases and more paths are considered, edges immedi- ately adjacent to the roots score highest. (b) Since all paths must pass through the narrow passage, edges within score highly. (c) For a problem with two a-priori known obstacles (dark gray), the score first prioritizes evaluations between the two. (d) Upon finding these edges are blocked, the next edges that are prioritized lie along the top of the world. Here, P \ e denotes paths in P that do not contain edge e. It may appear advantageous to restrict P to only sim- ple paths, since all optimal paths are simple. Unfortunately, an algorithm for computing (7) efficiently is not currently known in this case. However, in the case that P consists of all paths, there exists an efficient incremental calculation of (7) via a recursive formulation which we detail here. We use the notation Zxy = Z(Pxy), with Pxy the set of paths from x to y. Suppose the values Zxy are known be- tween all pairs of vertices x, y for a graph G. (For a graph with no edges, Zxy is 1 if x = y and 0 otherwise.) Consider a modified graph G′ with one additional edge eab with weight wab. All additional paths use the new edge eab a non-zero number of times; the value Z′ xy can be shown to be Z′ xy = Zxy+ ZxaZby exp(βwab) −Zba if exp(βwab) > Zba. (9) Figure 7: Visualization of the first of three articulated motion planning problems in which the HERB robot must move its right arm from the start configuration (pictured) to any of seven grasp configurations for a mug. Shown is the progression of the Alternate selector on one of the randomly generated roadmaps; approximately 2% of the 7D roadmap is shown in gray by projecting onto the space of end-effector positions. This form is derived from simplifying the induced geomet- ric series; note that if exp(βwab) ≤Zba, the value Z′ xy is infinite. One can also derive the inverse: given values Z′, calculate the values Z if an edge were removed. This incremental formulation of (7) allows for the corre- sponding score p(e) for edges to be updated efficiently dur- ing each iteration of LazySP as the wlazy value for edges chosen for evaluation are updated. In fact, if the values Z are stored in a square matrix, the update for all pairs after an edge weight change consists of a single vector outer product. 5 Experiments We compared the seven edge selectors on three classes of shortest path problems. The average number of edges evalu- ated by each, as well as timing results from our implementa- tions, are shown in Figure 8. In each case, the estimate was chosen so that west ≤w, so that all runs produced optimal paths. The experimental results serve primarily to illustrate that the A* and LWA* algorithms (i.e. Expand and Forward) are not optimally edge-efficient, but they also expose dif- ferences in behavior and prompt future research directions. All experiments were conducted using an open-source im- plementation.1 Motion planning results were implemented using OMPL (S¸ucan, Moll, and Kavraki 2012). Random partially-connected graphs. We tested on a set of 1000 randomly-generated undirected graphs with |V | = 100, with each pair of vertices sharing an edge with prob- ability 0.05. Edges have an independent 0.5 probability of having infinite weight, else the weight is uniformly dis- tributed on [1, 2]; the estimated weight was unity for all edges. For the WeightSamp selector, we drew 1000 w sam- ples at each iteration from the above edge weight distribu- tion. For the Partition selector, we used β = 2. Roadmap graphs on the unit square. We considered roadmap graphs formed via the first 100 points of the (2, 3)- Halton sequence on the unit square with a connection radius of 0.15, with 30 pairs of start and goal vertices chosen ran- domly. The edge weight function was derived from 30 sam- pled obstacle fields consisting of 10 randomly placed axis- 1https://github.com/personalrobotics/lemur aligned boxes with dimensions uniform on [0.1, 0.3], with each edge having infinite weight on collision, and weight equal to its Euclidean length otherwise. One of the resulting 900 example problems is shown in Figure 2. For the Weight- Samp selector, we drew 1000 w samples with a na¨ıve edge weight distribution with each having an independent 0.1 col- lision probability. For the Partition selector, we used β = 21. Roadmap graphs for robot arm motion planning. We considered roadmap graphs in the configuration space corre- sponding to the 7-DOF right arm of the HERB home robot (Srinivasa et al. 2012) across three motion planning prob- lems inspired by a table clearing scenario (see Figure 7). The problems consisted of first moving from the robot’s home configuration to one of 7 feasible grasp configurations for a mug (pictured), second transferring the mug to one of 72 feasible configurations with the mug above the blue bin, and third returning to the home configuration. Each problem was solved independently. This common scenario spans various numbers of starts/goals and allows a comparison w.r.t. diffi- culty at different problem stages as discussed later. For each problem, 50 random graphs were constructed by applying a random offset to the 7D Halton sequence with N = 1000, with additional vertices for each problem start and goal configuration. We used an edge connection radius of 3 radians, resulting |E| ranging from 23404 to 28109. Each edge took infinite weight on collision, and weight equal to its Euclidean length otherwise. For the WeightSamp selector, we drew 1000 w samples with a na¨ıve edge weight distribution in which each edge had an independent 0.1 prob- ability of collision. For the Partition selector, we used β = 3. 6 Discussion The first observation that is evident from the experimen- tal results is that lazy evaluation – whether using Forward (LWA*) or one of the other selectors – grossly outperforms Expand (A*). The relative penalty that Expand incurs by evaluating all edges from each expanded vertex is a func- tion of the graph’s branching factor. Since the Forward and Reverse selectors are simply mir- rors of each other, they exhibit similar performance averaged across the PartConn and UnitSquare problem classes, which E F R A B W P‡ PartConn 87.10 35.86 34.84 22.23 44.81 20.66 20.39 online†(ms) 1.22 1.96 1.86 1.20 2.41 4807.19 3.32 sel (ms) 0.02 0.01 0.01 0.01 0.03 4805.64 2.07 UnitSquare 69.21 27.29 27.69 17.82 32.62 15.58 14.08 online†(ms) 0.91 1.47 1.49 0.94 1.71 3864.95 1.72 sel (ms) 0.01 0.01 0.01 0.01 0.02 3863.49 0.87 ArmPlan(avg) 949.05 63.62 74.94 55.48 68.01 56.93 48.07 online (s) 269.82 5.90 8.22 5.96 7.34 3402.21 5.80 sel (s) 0.00 0.00 0.00 0.00 0.00 3392.76 1.54 eval (s) 269.78 5.87 8.20 5.94 7.31 9.39 4.21 ArmPlan1 344.74 49.72 95.58 59.44 58.90 73.72 50.66 online (s) 109.09 4.81 14.81 7.03 7.91 3375.35 7.25 sel (s) 0.00 0.00 0.00 0.00 0.00 3358.82 1.61 eval (s) 109.07 4.78 14.77 7.01 7.88 16.47 5.59 ArmPlan2 657.02 62.24 98.54 69.96 75.88 66.24 62.16 online (s) 166.19 3.27 7.36 5.95 5.63 4758.04 5.99 sel (s) 0.00 0.00 0.00 0.00 0.00 4750.16 2.03 eval (s) 166.17 3.26 7.34 5.93 5.61 7.82 3.91 ArmPlan3 1845.38 78.90 30.70 37.04 69.26 30.82 31.38 online (s) 534.16 9.61 2.50 4.91 8.47 2073.23 4.17 sel (s) 0.00 0.00 0.00 0.00 0.00 2069.29 0.98 eval (s) 534.10 9.58 2.48 4.89 8.44 3.90 3.15 (a) Average number of edges evaluated for each problem class and selector. The minimum selector, along with any selector within one unit of its standard error, is shown in bold. The ArmPlan class is split into its three constituent problems. Online timing results are also shown, including the components from the invoking the selec- tor and evaluating edges. †PartConn and UnitSquare involve trivial edge evaluation time. ‡Timing for the Partition selector does not include pre-computation time. E F R A B W P 40 60 80 (b) PartConn E F R A B W P 40 60 80 (c) UnitSquare E F R A B W P 60 80 100 ↑ (d) ArmPlan Figure 8: Experimental results for the three problem classes across each of the seven selectors, E:Expand, F:Forward, R:Reverse, A:Alternate, B:Bisection, W:WeightSamp, and P:Partition. In addition to the summary table (a), the plots (b-d) show summary statistics for each problem class. The means and standard errors in (b-c) are across the 1000 and 900 problem instances, respectively. The means and stan- dard errors in (d) are for the average across the three con- stituent problems for each of the 50 sampled roadmaps. are symmetric. However, this need not the case for a particu- lar instance. For example, the start of ArmPlan1 and the goal of ArmPlan3 consist of the arm’s single home configuration in a relatively confined space. As shown in the table in Fig- ure 8a, it appears that the better selector on these problems attempts to solve the more constrained side of the problem first. While it may be difficult to determine a priori which part of the problem will be the most constrained, the simple Alternate selector’s respectable performance suggests that it may be a reasonable compromise. The per-path plots at the bottom of Figure 2 allow us to characterize the selectors’ behavior. For example, Alternate often evaluates several edges on each path before finding an obstacle. Its early evaluations also tend to be useful later, and it terminates after considering 10 paths on the illustrated problem. In contrast, Bisection exhibits a fail-fast strategy, quickly invalidating most paths after a single evaluation, but needing 16 such paths (with very little reuse) before it termi- nates. In general, the Bisection selector did not outperform any of the lazy selectors in terms of number of edges evalu- ated. However, it may be well suited to problem domains in which evaluations that fail tend be less costly. The novel selectors based on path distributions tend to minimize edge evaluations on the problems we considered. While the WeightSamp selector performs similarly to Par- tition on the simpler problems, it performs less well in the ArmPlan domain. This may be because many more samples are needed to approximate the requisite path distribution. The path distribution selectors are motivated by focusing evaluation effort in areas that are useful for many distinct candidate paths, as illustrated in Figure 6. Note that in the absence of a priori knowledge, the edges nearest to the start and goal tend to have the highest p(e) score, since they are members of many potential paths. Because it tends to focus evaluations in a similar way, the Alternate selector may serve as a simple proxy for the more complex selectors. We note that an optimal edge selector could be theoret- ically achieved by posing the edge selection problem as a POMDP, given a probabilistic model of the true costs. While likely intractable in complex domains, exploring this solu- tion may yield useful approximations or insights. Timing results. Figure 8a shows that the five simple se- lectors incur a negligible proportion of the algorithm’s run- time. The WeightSamp and Partition selectors both require additional time (especially the former) in order to reduce the time spent evaluating edges. This tradeoff depends in- timately on the problem domain considered. In the ArmPlan problem class, the Partition selector was able to reduce aver- age total online runtime slightly despite an additional 1.54s of selector time. Note that Partition requires an expensive computation of the graph’s initial Z-values, which are in- dependent of the true weights and start/goal vertices (and can therefore be pre-computed, e.g. across all ArmPlan in- stances). Full timing results are available in the appendix (Figure 9). Optimizations. While we have focused on edge evalua- tions as the dominant source of computational cost, other considerations may also be important. There are a number of optimizations that allow for efficient implementation of LazySP. The first relates to the repeated invocations of the inner shortest path algorithm (line 5 of Algorithm 1). Because only a small number of edges change weights between in- vocations, an incremental search algorithm such as SSSP (Ramalingam and Reps 1996) or LPA* (Koenig, Likhachev, and Furcy 2004) can be used to greatly improve the speed of the inner searches. Since the edge selector determines where on the graph edges are evaluated, the choices of the selector and the inner search algorithm are related. For example, us- ing the Forward selector with an incremental inner search rooted at the goal results in behavior similar to D* (Stentz 1994) (albeit without the need to handle a moving start lo- cation) since a large portion of the inner tree can be reused. An optimization commonly applied to vertex searches called immediate expansion is also applicable to LazySP. If an edge is evaluated with weight w ≤west, the inner search need not be run again before the next edge is evaluated. A third optimization is applicable to domains with infi- nite edge costs (e.g. to represent infeasible transitions). If the length of the path returned by the inner shortest path al- gorithm is infinite, LazySP can return this path immediately even if some of its edges remain unevaluated without af- fecting its (sub)optimality. This reduces the number of edge evaluations needed in the case that no feasible path exists. Other methods for expensive edge evaluations. An al- ternative to lazy evaluations is based on the observation that when solved by vertex expansion algorithms, such problems are characterized by slow vertex expansions. To mitigate this, approaches such as Parallel A* (Irani and Shih 1986) and Parallel A* for Slow Expansions (Phillips, Koenig, and Likhachev 2014) aim to parallelize such expansions. We be- lieve that a similar approach can be applied to LazySP. Another approach to finding short paths quickly is to re- lax the optimization objective (2) itself. While LazySP al- ready supports a bounded-suboptimal objective via an in- flated edge weight estimate (Theorem 2), it may also be pos- sible to adapt the algorithm to address bounded-cost prob- lems (Stern, Puzis, and Felner 2011). Acknowledgements We would like to thank Aaron Johnson and Michael Ko- val for their comments on drafts of this work. This work was (partially) funded by the National Science Foundation IIS (#1409003), Toyota Motor Engineering & Manufactur- ing (TEMA), and the Office of Naval Research. References Bohlin, R., and Kavraki, E. 2000. Path planning using Lazy PRM. In IEEE International Conference on Robotics and Automation, volume 1, 521–528. Cohen, B.; Phillips, M.; and Likhachev, M. 2014. Planning single-arm manipulations with n-arm robots. In Robotics: Science and Systems. Dijkstra, E. W. 1959. A note on two problems in connexion with graphs. Numerishe Mathematik 1(1):269–271. Gammell, J.; Srinivasa, S.; and Barfoot, T. 2015. Batch In- formed Trees (BIT*): Sampling-based optimal planning via the heuristically guided search of implicit random geometric graphs. In IEEE International Conference on Robotics and Automation, 3067–3074. Hart, P.; Nilsson, N.; and Raphael, B. 1968. A formal basis for the heuristic determination of minimum cost paths. IEEE Transactions on Systems Science and Cybernetics 4(2):100– 107. Helmert, M. 2006. The fast downward planning system. Artificial Intelligence Research 26:191–246. Irani, K. B., and Shih, Y. 1986. Parallel A* and AO* al- gorithms: An optimality criterion and performance evalua- tion. In International Conference on Parallel Processing, 274–277. Kavraki, L.; Svestka, P.; Latombe, J.-C.; and Overmars, M. 1996. Probabilistic roadmaps for path planning in high- dimensional configuration spaces. IEEE Transactions on Robotics and Automation 12(4):566–580. Koenig, S.; Likhachev, M.; and Furcy, D. 2004. Lifelong planning A*. Artificial Intelligence 155(1–2):93–146. Korf, R. E. 1985. Depth-first iterative-deepening: An op- timal admissible tree search. Artificial Intelligence 27:97– 109. Kuffner, J., and LaValle, S. 2000. RRT-Connect: An effi- cient approach to single-query path planning. In IEEE Inter- national Conference on Robotics and Automation, volume 2, 995–1001. Phillips, M.; Koenig, S.; and Likhachev, M. 2014. Paral- lel A* for planning with time-consuming state expansions. In International Conference on Automated Planning and Scheduling. Pohl, I. 1970. Heuristic search viewed as path finding in a graph. Artificial Intelligence 1(34):193 – 204. Ramalingam, G., and Reps, T. 1996. An incremental al- gorithm for a generalization of the shortest-path problem. Journal of Algorithms 21(2):267 – 305. Sint, L., and de Champeaux, D. 1977. An improved bidirec- tional heuristic search algorithm. J. ACM 24(2):177–191. Srinivasa, S.; Berenson, D.; Cakmak, M.; Collet, A.; Dogar, M.; Dragan, A.; Knepper, R.; Niemueller, T.; Strabala, K.; Vande Weghe, M.; and Ziegler, J. 2012. HERB 2.0: Lessons learned from developing a mobile manipulator for the home. Proceedings of the IEEE 100(8):2410–2428. Stentz, A. 1994. Optimal and efficient path planning for partially-known environments. In IEEE International Con- ference on Robotics and Automation, volume 4, 3310–3317. Stern, R.; Puzis, R.; and Felner, A. 2011. Potential search: A bounded-cost search algorithm. In International Conference on Automated Planning and Scheduling. S¸ucan, I. A.; Moll, M.; and Kavraki, L. E. 2012. The Open Motion Planning Library. IEEE Robotics & Automation Magazine 19(4):72–82. http://ompl.kavrakilab.org. Yoshizumi, T.; Miura, T.; and Ishida, T. 2000. A* with partial expansion for large branching factor problems. In AAAI Conference on Artificial Intelligence, 923–929. A Appendix: Proofs LazySP Proof of Theorem 2 Let p∗be an optimal path w.r.t. w, with ℓ∗= len(p∗, w). Since west(e) ≤ϵ w(e) and ϵ ≥1, it follows that regardless of which edges are stored in Weval, wlazy(e) ≤ϵ w(e), and therefore len(p∗, wlazy) ≤ϵ ℓ∗. Now, since the inner SHORTESTPATH algorithm terminated with pret, we know that len(pret, wlazy) ≤len(p∗, wlazy). Further, since the algorithm terminated with pret, each edge on pret has been evaluated; therefore, len(pret, w) = len(pret, wlazy). Therefore, len(pret, w) ≤ϵ ℓ∗. □ Proof of Theorem 1 In this case, the algorithm will evalu- ate at least unevaluated edge at each iteration. Since there are a finite number of edges, eventually the algorithm will terminate. □ A* Equivalence Proof of Invariant 1 If v is discovered, then it must either be on OPEN or CLOSED. v can be on CLOSED only after it has been expanded, in which case v′ would be discovered (which it is not). Therefore, v must be on OPEN. □ Proof of Invariant 2 Clearly the invariant holds at the be- ginning of the algorithm, with only vstart on OPEN. If the invariant were to no longer hold after some iteration, then there must exist some pair of discovered vertices v and v′ with v on CLOSED and g[v]+w(v, v′) < g[v′]. Since v is on CLOSED, it must have been expanded at some previous iter- ation, immediately after which the inequality could not have held because g[v′] is updated upon expansion of v. There- fore, the inequality must have newly held after some inter- vening iteration, with v remaining on CLOSED. Since the values g are monotonically non-increasing and w is fixed, this implies that g[v] must have been updated (lower). How- ever, if this had happened, then v would have been removed from CLOSED and placed on OPEN. This contradiction im- plies that the invariant holds at every iteration. □ Proof of Theorem 3 Consider path p∗ lazy with length ℓ∗ lazy yielding frontier vertex vfrontier via SELECTEXPAND. Con- struct a vertex sequence s as follows. Initialize s with the vertices on p∗ lazy from vstart to vfrontier, inclusive. Let N be the number of consecutive vertices at the start of s for which f(v) = ℓ∗ lazy (Note that the first vertex on p∗ lazy, vstart, must have f(vstart) = ℓ∗ lazy, so N ≥1.) Remove from the start of s the first N −1 vertices. Note that at most the first vertex on s has f(v) = ℓ∗ lazy, and the last vertex on s must be vfrontier. Now we show that each vertex in this sequence s, consid- ered by A* in turn, exists on OPEN with minimal f-value. Iteratively consider the following procedure for sequence s. Throughout, we know that there must not be any vertex with f(v) < ℓ∗ lazy; that would imply that a different path through vb shorter than ℓ∗ lazy exists, in which case p∗ lazy could not have been chosen. If the sequence has length > 1, then consider the first two vertices on s, va and vb. By construction, f(va) = ℓ∗ lazy and f(vb) ̸= ℓ∗ lazy. In fact, from above we know that f(vb) > ℓ∗ lazy. Therefore, we have that f(va) < f(vb), therefore and g[va] + w(va, vb) < g[vb]. By Invariant 2, va must be on OPEN, and with f(va) = ℓ∗ lazy, it can therefore be consid- ered by A*. After it is expanded, f(vb) = ℓ∗ lazy, and we can repeat the above procedure with the sequence formed by re- moving the va from s. If instead the sequence has length 1, then it must be ex- actly (vfrontier), with f(vfrontier) = ℓ∗ lazy. Since the edge after f(vfrontier) is not evaluated, then by Invariant 1, vfrontier must be on OPEN, and will therefore be expanded next. □ Proof of Theorem 4 Given that all vertices in scandidate be- sides the last are re-expansions, they can be expanded with no edge evaluations. Once the last vertex, vfrontier, is to be expanded by A*, suppose it has f-value ℓ. First, we will show that there exists a path with length ℓ w.r.t. wlazy wherein all edges before vfrontier have been eval- uated, and the first edge after vfrontier has not. Let pa be a shortest path from vstart to vfrontier consisting of only evalu- ated edges. The length of this pa must be equal to g[vfrontier]; if it were not, there would be some previous vertex on pa with lower f-value than vfrontier, which would necessarily have been expanded first. Let pb be the a shortest path from vfrontier to vgoal. The length of pb must be hlazy(vfrontier) by definition. Therefore, the path (pa, pb) must have length ℓ, and since vfrontier is a new expansion, the first edge on pb must be unevaluated. Second, we will show that there does not exist any path shorter than ℓw.r.t. wlazy. Suppose p′ were such a path, with length ℓ′ < ℓ. Clearly, vstart would have f-value ℓ′ (although it may not be on OPEN). Consider each pair of vertices (va, vb) along p′ in turn. In each case, if vb were either undis- covered, or if g[va]+w(va, vb) < g[vb], then va would be on OPEN (via Invariants 1 and 2, respectively) with f(va) = ℓ′, and would therefore have been expanded before vfrontier. Oth- erwise, we know that f(vb) = ℓ′, and we can continue to the next pair on p′. □ LWA* Equivalence Proof of Invariant 3 Clearly the invariant holds at the be- ginning of the algorithm with only g[vstart] = 0, since the inequality holds only for the out-edges of vstart, with vstart on Qv. Consider each subsequent iteration. If a vertex v is popped from Qv, then this may invalidate the invariant for all successors of v; however, since all out-edges are immedi- ately added to Qe, the invariant must hold. Consider instead if an edge (v, v′) which satisfies the inequality is popped from Qe. Due to the inequality, we know that g[v′] will be recalculated as g[v′] = g[v]+w(v, v′), so that the inequality is no longer satisfied for edge (v, v′). However, reducing the value g[v′] may introduce satisfied inequalities across sub- sequent out-edges of v′, but since v′ is added to Qv, the in- variant continues to hold. □ Proof of Theorem 5 In the first component of the equiva- lence, we will show that for any path p minimizing wlazy allowable to LazySP-Forward, with (va, vb) the first uneval- uated edge on p, there exists a sequence of vertices and edges on Qv and Qe allowable to LWA* such that edge (va, vb) is the first to be newly evaluated. Let the length of p w.r.t. wlazy be ℓ.’ We will first show that no vertex on Qv or edge on Qe can have f(·) < ℓ. Suppose such a vertex v, or edge e with source vertex v, exists. Then g[v] + h(v) < ℓ, and there must be some path p′ consisting of an evaluated segment from vstart to v of length g[v], followed a segment from v to vgoal of length h(v). But then this path should have been chosen by LazySP. Next, we will show a procedure for generating an allow- able sequence for LWA*. We will iteratively consider a se- quence of path segments, starting with the segment from vstart to va, and becoming progressively shorter at each it- eration by removing the first vertex and edge on the path. We will show that the first vertex on each segment vf has g[vf] = ℓ−h(vf). By definition, this is true of the first such segment, since g[vstart] = 0. For each but the last such seg- ment, consider the first edge, (vf, vs). If vs has the correct g[·], we can continue to the next segment immediately. Oth- erwise, either vf is on Qv or (vf, vs) is on Qe by Invariant 3. If the former is true, then vf can be popped from Qv with f = ℓ, thereby adding (vf, vs) to Qe. Then, (vf, vs) can be popped from Qe with f = ℓ, resulting in g[vs] = ℓ−h(vs). We can then move on to the next segment. At the end of this process, we have the trivial segment (va), with g[va] = ℓ−h(va). If va is on Qv, then pop it (with f(va) = ℓ), placing eab on Qe; otherwise, since eab is unevaluated, it must already be on Qe. Since f(eab) = ℓ, we can pop and evaluate it. □ Proof of Theorem 6 Given that all vertices in scandidate en- tail no edge evaluations, and all edges therein are re- expansions, they can be considered with no edge evalua- tions. Once the last edge exy is to be expanded by LWA*, suppose it has f-value ℓ. First, we will show that there exists a path with length ℓ w.r.t. wlazy which traverses unevaluated edge exy wherein all edges before vx have been evaluated. Let px be a shortest path segment from vstart to vx consisting of only evaluated edges. The length of px must be equal to g[vx]; if it were not, there would be some previous vertex on px with lower f- value than vx, which would necessarily have been expanded first. Let py be the a shortest path from vy to vgoal. The length of py must be hlazy(vy) by definition. Therefore, the path (px, exy, py) must have length ℓ. Second, we will show that there does not exist any path shorter than ℓw.r.t. wlazy. Suppose p′ were such a path, with length ℓ′ < ℓ, and with first unevaluated edge e′ xy. Clearly, vstart has g[vstart] = ℓ′ −h(vstart). Consider each evaluated edge e′ ab along p′ in turn. In each case, if g[v′ b] ̸= ℓ′ −h(v′ b), then either v′ a or e′ ab would be on Qv or Qe with f(·) = ℓ′, and would therefore be expanded before exy. Therefore, e′ xy would then be popped from Qe with f(e′ xy) = ℓ′, and it would have been evaluated before exy with f(exy) = ℓ. □ B Appendix: Timing Results We include an accounting of the cumulative computation time taken by each component of LazySP for each of the seven selectors for each problem class (Figure 9). Expand Forward Reverse Alternate Bisect WeightSamp Partition PartConn total (ms) 1.22 ± 0.04 1.96 ± 0.06 1.86 ± 0.06 1.20 ±0.03 2.41 ±0.06 4807.19 ±135.22 15.81 ± 0.16 sel-init (ms) – – – – – – 12.49 ± 0.11 online (ms) 1.22 ± 0.04 1.96 ± 0.06 1.86 ± 0.06 1.20 ±0.03 2.41 ±0.06 4807.19 ±135.22 3.32 ± 0.10 search (ms) 0.48 ± 0.01 1.12 ± 0.03 1.05 ± 0.03 0.68 ±0.02 1.38 ±0.04 0.70 ± 0.02 0.68 ± 0.02 sel (ms) 0.02 ± 0.00 0.01 ± 0.00 0.01 ± 0.00 0.01 ±0.00 0.03 ±0.00 4805.64 ±135.18 2.07 ± 0.06 eval (ms) – – – – – – – eval (edges) 87.10 ± 2.39 35.86 ± 1.04 34.84 ± 1.04 22.23 ±0.60 44.81 ±1.11 20.66 ± 0.57 20.39 ± 0.56 UnitSquare total (ms) 0.91 ± 0.03 1.47 ± 0.06 1.49 ± 0.06 0.94 ±0.03 1.71 ±0.04 3864.95 ±117.66 15.13 ± 0.14 sel-init (ms) – – – – – – 13.41 ± 0.12 online (ms) 0.91 ± 0.03 1.47 ± 0.06 1.49 ± 0.06 0.94 ±0.03 1.71 ±0.04 3864.95 ±117.66 1.72 ± 0.06 search (ms) 0.35 ± 0.01 0.79 ± 0.03 0.82 ± 0.03 0.51 ±0.02 0.92 ±0.02 0.75 ± 0.02 0.45 ± 0.01 sel (ms) 0.01 ± 0.00 0.01 ± 0.00 0.01 ± 0.00 0.01 ±0.00 0.02 ±0.00 3863.49 ±117.62 0.87 ± 0.03 eval (ms) – – – – – – – eval (edges) 69.21 ± 2.55 27.29 ± 1.03 27.69 ± 1.02 17.82 ±0.60 32.62 ±0.72 15.58 ± 0.47 14.08 ± 0.46 ArmPlan (avg) total (s) 269.82 ± 17.95 5.90 ± 0.46 8.22 ± 0.53 5.96 ±0.31 7.34 ±0.43 3402.21 ±172.20 496.57 ± 5.53 sel-init (s) – – – – – – 490.77 ± 5.51 online (s) 269.82 ± 17.95 5.90 ± 0.46 8.22 ± 0.53 5.96 ±0.31 7.34 ±0.43 3402.21 ±172.20 5.80 ± 0.28 search (s) 0.02 ± 0.00 0.02 ± 0.00 0.02 ± 0.00 0.02 ±0.00 0.02 ±0.00 0.02 ± 0.00 0.04 ± 0.00 sel (s) 0.00 ± 0.00 0.00 ± 0.00 0.00 ± 0.00 0.00 ±0.00 0.00 ±0.00 3392.76 ±171.74 1.54 ± 0.09 eval (s) 269.78 ± 17.95 5.87 ± 0.45 8.20 ± 0.52 5.94 ±0.31 7.31 ±0.43 9.39 ± 0.57 4.21 ± 0.22 eval (edges) 949.05 ± 63.46 63.62 ± 4.15 74.94 ± 5.07 55.48 ±2.95 68.01 ±3.86 56.93 ± 3.37 48.07 ± 2.44 ArmPlan1 total (s) 109.09 ± 14.15 4.81 ± 0.49 14.81 ± 1.45 7.03 ±0.63 7.91 ±0.70 3375.35 ±319.81 496.74 ± 8.22 sel-init (s) – – – – – – 489.49 ± 8.18 online (s) 109.09 ± 14.15 4.81 ± 0.49 14.81 ± 1.45 7.03 ±0.63 7.91 ±0.70 3375.35 ±319.81 7.25 ± 0.66 search (s) 0.02 ± 0.00 0.02 ± 0.00 0.03 ± 0.00 0.02 ±0.00 0.02 ±0.00 0.02 ± 0.00 0.04 ± 0.00 sel (s) 0.00 ± 0.00 0.00 ± 0.00 0.00 ± 0.00 0.00 ±0.00 0.00 ±0.00 3358.82 ±318.17 1.61 ± 0.16 eval (s) 109.07 ± 14.15 4.78 ± 0.49 14.77 ± 1.44 7.01 ±0.63 7.88 ±0.70 16.47 ± 1.68 5.59 ± 0.51 eval (edges) 344.74 ± 39.63 49.72 ± 4.25 95.58 ± 9.67 59.44 ±5.06 58.90 ±4.74 73.72 ± 7.63 50.66 ± 4.43 ArmPlan2 total (s) 166.19 ± 9.29 3.27 ± 0.25 7.36 ± 0.69 5.95 ±0.52 5.63 ±0.45 4758.04 ±407.56 495.21 ±12.65 sel-init (s) - - – – – – – 489.22 ±12.64 online (s) 166.19 ± 9.29 3.27 ± 0.25 7.36 ± 0.69 5.95 ±0.52 5.63 ±0.45 4758.04 ±407.56 5.99 ± 0.48 search (s) 0.01 ± 0.00 0.01 ± 0.00 0.02 ± 0.00 0.01 ±0.00 0.01 ±0.00 0.02 ± 0.00 0.03 ± 0.00 sel (s) 0.00 ± 0.00 0.00 ± 0.00 0.00 ± 0.00 0.00 ±0.00 0.00 ±0.00 4750.16 ±406.98 2.03 ± 0.22 eval (s) 166.17 ± 9.28 3.26 ± 0.25 7.34 ± 0.69 5.93 ±0.52 5.61 ±0.45 7.82 ± 0.61 3.91 ± 0.27 eval (edges) 657.02 ± 29.24 62.24 ± 6.12 98.54 ±10.89 69.96 ±6.98 75.88 ±7.47 66.24 ± 6.36 62.16 ± 6.10 ArmPlan3 total (s) 534.16 ± 55.64 9.61 ± 1.33 2.50 ± 0.23 4.91 ±0.56 8.47 ±0.99 2073.23 ±198.75 497.76 ±10.27 sel-init (s) – – – – – – 493.59 ±10.21 online (s) 534.16 ± 55.64 9.61 ± 1.33 2.50 ± 0.23 4.91 ±0.56 8.47 ±0.99 2073.23 ±198.75 4.17 ± 0.43 search (s) 0.02 ± 0.01 0.02 ± 0.00 0.02 ± 0.00 0.02 ±0.00 0.02 ±0.00 0.03 ± 0.01 0.04 ± 0.00 sel (s) 0.00 ± 0.00 0.00 ± 0.00 0.00 ± 0.00 0.00 ±0.00 0.00 ±0.00 2069.29 ±198.53 0.98 ± 0.13 eval (s) 534.10 ± 55.63 9.58 ± 1.33 2.48 ± 0.23 4.89 ±0.56 8.44 ±0.99 3.90 ± 0.31 3.15 ± 0.32 eval (edges) 1845.38 ±195.57 78.90 ±10.36 30.70 ± 3.62 37.04 ±4.59 69.26 ±7.97 30.82 ± 3.60 31.38 ± 3.80 Figure 9: Detailed timing results for each selector. The actual edge weights for the illustrative PartConn and UnitSquare prob- lems were pre-computed, and therefore their timings are not included. The Partition selector requires initialization of the Z- values (7) for the graph using only the estimated edge weights. Since this is not particular to either the actual edge weights (e.g. from the obstacle distribution) or the start/goal vertices from a particular instance, this initialization (sel-init) is considered separately. The online running time (online) is broken into LazySP’s three primary steps: the inner search (search), invoking the edge selector (sel), and evaluating edges (eval). We also show the number of edges evaluated.