Asymptotic Optimality of Rapidly Exploring Random Tree Titas Bera 1 and Debasish Ghose 2 and Suresh Sundaram 3 Abstract — In this paper we investigate the asymptotic op- timality property of a randomized sampling based motion planner, namely RRT. We prove that a RRT planner is not an asymptotically optimal motion planner. Our result, while being consistent with similar results which exist in the literature, however, brings out an important characteristics of a RRT plan- ner. We show that the degree distribution of the tree vertices follows a power law in an asymptotic sense. A simulation result is presented to support the theoretical claim. Based on these results we also try to establish a simple necessary condition for sampling based motion planners to be asymptotically optimal. I. INTRODUCTION Several early studies have shown that the basic problem of robot motion planning is PSPACE-complete [1] and exact deterministic algorithms show exponential complexity with the dimension of the configuration space [2]. To avoid such curse of dimensionality, several sampling based probabilistic motion planners have been proposed and widely used for motion planning for robots in high dimensional configu- ration spaces. Although, such randomized sampling based algorithms show polynomial complexity, it is well known that these algorithms can only guarantee completeness in a probabilistic sense. Two most extensively used and studied sampling based approaches are Probabilistic Roadmap Method or PRM, [3], and Rapidly Exploring Random Tree or RRT, [4]. A very general characteristics of both these methods are that these algorithms work in two consecutive phases. In the first phase, called a processing phase, a graph/tree structure is created which consist of nodes, representing the free configurations and edges, representing a planning phase which should be executed by a local planner. The main purpose of this local planner is to connect a pair of selected nodes by means of solving a small scale local planning problem. At the end of the processing phase, a network of achievable configurations within the configuration space is created. The second phase or a query phase, uses a graph search algorithm to identify a path between any two nodes corre- sponding to two given user input configuration. Because of various types of sampling scheme and local planners, there *This work was supported byt ST-Engineering under project CRP3-P2P 1 Titas Bera is a research fellow in the School of Electrical and Electronic Engineering, Nanyang Technological University, Singapore btitas@ntu.edu.sg 2 Debasish Ghose is with the Faculty in the Department of Aerospace Engineering, Indian Institute of Science, India dghose@aero.iisc.ernet.in 3 Suresh Sundaram is with the Faculty in the School of Computer Science and Engineering, Nanyang Technological University, Singapore Ssundaram@ntu.edu.sg exist many variants of these sampling based planners. For example, EST [6], Lazy-PRM [7], sampling based roadmap of trees [8], and RRT*[9], to name a few. For necessary details about these planners, see [11] and for a somewhat old but excellent survey see [12]. Since its inception, several attempts have been made to formalize the performance of these algorithms in terms of various parameters such as properties of the free configura- tions space, type of sampling sequence, etc. The objective was to understand the completeness and optimality of the algorithmic solution to the problem. For example, In [13], [14] using various combinatorial and measure theoretic ap- proach, failure probability of s-PRM is analyzed. In [15] it is shown that the performance of PRM is dependent on the expansiveness property of the free configuration space. It is shown that, with an expansive free space, failure probability to find a path decreases exponentially as number of samples increases. In [16], a smoothed analysis of PRM is given which shows how such planners utilizes discrepancies in input specifications. In [9], the asymptotic optimality of many such sampling based algorithms analysed and char- acterized in terms of algorithmic completeness, asymptotic convergence to optimal solution, and time complexities. This paper also points out the lack of asymptotic optimality of the solution returned and consequently proposes new algorithms which are asymptotically optimal. In [17] the completeness and optimality properties of various PRM planners are inves- tigated in the light of different random sampling sequence. In this paper, we present an analysis of the asymptotic optimality property of RRT. Note that, in [9], using a series of complex argument, it is already established that RRT is not an asymptotically optimal planner. In this work we present a much simpler proof of the asymptotic sub-optimality property of RRT. Although our work re-establishes a known result, it also brings out an important property of such planners related to the behaviour of asymptotically optimal sampling based planner, in general. In particular, we focus on the degree distribution of the RRT node vertices and the relationship to this with asymptotic optimality property. We also substantiate the findings with a numerical simulation presented at the end of the paper. Our work is primarily based on the analyse of scale free properties of a random network, more specifically on the power law of the asymptotic degree distribution of the network. For details of this problem and definitions, see [18],[19]. This paper is organized as follows. In section II we define the problem of motion planning and define the notion of asymptotically optimal motion planning. Following in section III, we present and discuss the RRT planner in detail. arXiv:1707.03976v1 [cs.RO] 13 Jul 2017 Section IV contains the main result regarding the asymptotic optimality of RRT. Section V contains a simulation results and discussion on the validity of our theoretical claim. Finally, in VI we conclude and enlists the future work. II. M OTION P LANNING P ROBLEM F ORMULATION The configuration of an autonomous agent, with d degrees of freedom, can be represented as a point in a d -dimensional space, called the configuration space C , which is locally like a d − dimensional Euclidean space R d . A configuration q in C is free if the robot placed at q does not collide with the obstacles in C . Let us augment this definition of configuration space with its tangent bundle. A tangent bundle of C is defined as T ( C ) = ∪ q ∈ C T q ( C ) , where T q ( C ) is the collection of all tangent vectors at q . The configuration space together with its tangent bundle is called a state space X , in which a state x ∈ X is simply defined as x = ( q , ̇ q ) . Holonomic constraints can be defined as h i ( q , t ) = 0. Non-holonomic constraints require the use of rate variables and or inequalities, that is l i ( q , ̇ q , t ) = 0 or l i ( q , ̇ q , t ) < 0. Differential constraints can be written in Lagrangian dynamics as a set of equations of the form g i ( q , ̇ q , ̈ q , t ) = 0, additionally involving acceleration. The use of state space formulation allows representations of the dynamic constraints as a set of m equations G i ( x , ̇ x ) = 0, m < 2 d , where, d is the dimension of the configuration space. These equations can be rewritten in the form ̇ x = f ( x , u ) , where u ∈ U , where U is the set of allowable control inputs to the system. The equations thus describe the state transitions resulting from a control input. To define state space obstacles apart from defining x ∈ X obs ⇔ q ∈ C obs for x = ( q , ( ̇ q )) , we need to define the reachable set from an initial configuration. For the system defined by the expression ̇ x = f ( x , u ) , a state x ′ can be obtained by applying a control input u over time t from an initial state of x 0 . The set of all possible x ′ is called the reachable state of x 0 for a time t . For each state x , among the set of reachable states, one can define future collision states X fc and free state space X free = X \ X fc . Note that, X fc grows as the speed of the system increases and may look rather different from X obs . This makes finding a valid kinodynamic trajectory more difficult. The goal of a motion planner is to find a trajectory x ( t ) ∈ X free from an initial state x init ∈ X free to a final state x final ∈ X free and to find a time parametrized function of control input u ( t ) that results in such a trajectory. For convergence issues, a general goal subset x goal is assumed, rather than a specific x final . Clearly, x final ∈ x goal . III. RAPIDLY EXPLORING RANDOM TREE Rapidly Exploring Random Tree (RRT) has been shown to be very effective in solving robot motion planning prob- lems in a complex state space with kinodynamic motion constraints. RRT is introduced in [4],[5] as an efficient data structure and sampling scheme to quickly search high dimensional spaces that have algebraic constraints (arising from the obstacle) and differential constraints (arising from nonholonomy and system dynamics). The algorithm incre- mentally builds a tree whose nodes are different states of the robot/vehicle. These nodes are added randomly to the tree until one of the node comes close enough to any of the states in x goal . Next, that goal state is added to the tree and a solution trajectory connecting x final ∈ x goal and x init can be found by backtracking the nodes. The edges of the tree forms a feasible path or solution trajectory connecting a pair of initial and final states. The key idea behind RRT is to bias the tree growth towards unexplored regions of the state space by random sampling and extending tree nodes to those regions. The selection of tree nodes for expansion is heavily dependent on current spatial distribution of tree nodes within the state space. Implicitly, the nodes with larger Voronoi cells are more probable for expansion. This is because the probability that a node is selected for expansion is directly proportional to the volume measure of its Voronoi cell. The tree node extension logic is based on forward simulation of system dynamics upon random control input. In the following, we present the basic RRT algorithm. The RRT algorithm consists of two subroutines, Build-RRT (Algorithm 1) and Extend- RRT (Algorithm 2). Algorithm 1: Build-RRT T · init ( x init ) B Initialize tree T ; for i=1,. . . ,K do x rand ← Random Configuration; Extend ( T , x rand ) end return T Algorithm 2: Extend RRT x near ← Nearest Neighbor ( x , T ) ; x new ← New State ( x near , u ) ; if x new is Not in Obstacle then T · add vertex ( x new ) ; T · add edge ( x near , x new , u new ) ; if x new ∈ X goal then return Reached ; else return Continue end end end The Build-RRT algorithm initially samples a random state or x rand . In the Extend-RRT function, a nearest node x near from the tree to the generated random state x rand is selected for future expansion. The function New State( x near , u ), does a forward simulation of system dynamics for ∆ t time period by applying a control input u ∈ U , where U is a finite input set, to the state at x near . This input can be chosen at random or can be selected from all possible inputs by choosing one which yields a new state x new which is as close as possible to x rand . The selection of input u can also be based on minimization of some performance criterion. Further, x new is checked for collision and system constraint violation. If x new does not collide with any of the state space obstacles and satisfies all the constraints, then x new is added to the tree as a child node of x near ; otherwise it is discarded. If x new ∈ x goal , the algorithm stops. This way the vertices or nodes of the RRT tree eventually forms a large connected component within X f ree and can come arbitrarily close to any specified x goal . Note that, since the algorithm is only probabilistically complete, the algorithm continues to search for a solution until it finds a close enough node to x goal . Heuristic termination condition can be added to stop the algorithm after a certain number of iterations. Before we move on to the asymptotically optimality analyse of the RRT planner it is worthwhile to look into a few aspects of the algorithm. For example, although RRT vertices can come arbitrarily close to any state in x goal , the convergence to the solution trajectory may be slow. One solution may be to sample certain x goal ∈ X goal repeatedly in random sampling stage so that this introduces a biased sample generation towards X goal . In such a way, a quick convergence towards the solution trajectory can be found, although it may lead RRT vertices to fall into a trap formed by certain spatial distribution of state space obstacle. The choice of step size and ∆ t used in forward simulation of the Extend function is also important. If the obstacles are located far away and system dynamics is considerably simple, then a larger step size can be used. In such cases, instead of attempting to extend x near by incremental step size, one can use the Extend function repeatedly until the extension is no longer possible. That is, a forward simulation produces states that violate system constraints or collide with the obstacle. Obviously, the success of this heuristics method is heavily dependent on the chosen problem. As reported in [10], this modification works best for holonomic planning. RRT can be used as a single directional or bidirectional planner. A single directional RRT planner builds a tree starting from x init towards X goal . A bidirectional planner however builds two separate trees. One from x init to X goal , and the other is from any state x ∈ X goal to x init . Once the distance between a pair of vertices from either tree is within a certain tolerance bound, the two trees gets connected and forms a large single connected component. For holonomic planning, a bidirectional planner is faster than the single directional planner. This heuristics, however, does not work for non-holonomic or for differential systems, because of reachability problem. Finally, an important subroutine in the RRT algorithm is the nearest neighbour search. Currently, the basic RRT’s nearest neighbour search algorithm works based on the principle of exhaustive search. For a fixed dimension d , if at any instant the RRT tree contains n vertices, the task of searching for a true nearest neighbour node from a given query point has O ( n ) time complexity. This approach, although linear with the number of vertices, eventually slows down (in the sense of computational time) the growth of RRT as the number of vertices increases. It should be noted that any approximate nearest neighbour searching degrades the RRT’s exploration capability. For example, suppose at every iteration, a random vertex is selected as the nearest neighbour and RRT is expanded from this vertex. The probability of selecting any node from the n number of nodes is 1 / n . While for a basic RRT, probability of selecting any node q as nearest neighbour for some query point, is O ( Vor ( q )) , where Vor ( q ) is the associated Voronoi cell of the node q . Since the node with largest Voronoi area has a higher probability of selection, the RRT vertices tend to grow to the region of largest Voronoi regions or, in other words, to the unexplored regions of state space. Clearly, selecting a random vertex as nearest neighbour is a compromise with the search of unexplored areas. However, after a large number of iterations if O ( Vor ( q )) ≈ 1 / n then selection of any vertex, as nearest neighbour, may be effective, specially for holonomic cases. IV. A SYMPTOTIC O PTIMALITY OF RRT Sometimes it is necessary to find an optimal solution for certain motion planning problems. For example, a motion planning task may contain additional objectives such as minimization of control effort or determination of a shortest path to minimize fuel cost. Except for a very simplistic situation, in general, the search for an optimal solution is difficult. For example, consider the general problem of shortest path calculation in 3-dimension among polyhedral obstacles. There are a number of solutions that exist only for a restricted class of problems, as can be found in [20]. These solutions are algorithms with polynomial time complexity, applicable in an environment which consists of a few convex polyhedra. In [21] a polynomial time approximate algorithm is given which finds a sub-optimal path in 3-dimension. In [22] a 2 2 O ( n ) complexity algorithm is proposed to construct the shortest path by reducing the problem to an algebraic decision problem. The best bound is obtained in [23], which is 2 n O ( 1 ) . These results indicate that finding an optimal path in a very general condition is computationally expensive. Since sampling based algorithms are used to avoid computational complexity issues that are present in obstacle avoidance and motion planning problems, it is natural to investigate the quality of the path returned by a sampling based motion planner. In this context, only [9] discusses and show the asymptotic optimality properties of various sampling based motion planning algorithms including RRT. For sampling based motion planning algorithms, optimal- ity of the solution can only be analysed in an asymptotic sense. Naturally, a definition of the asymptotic optimality of the solution is required. We outline the definition according to [9]. Definition 1: An algorithm is asymptotically optimal if, for any path planning problem and cost function c that admits a robustly optimal solution with finite cost c ∗ , P ( { lim sup n → ∞ Y n = c ∗ } ) = 1, where Y n is the algorithmic solution after n iterations. In the argument presented in [9], first it is defined that the set of vertices that contains the k th child of the root along with all its descendants in the tree is called the k th branch of the tree. Then, it is shown that a necessary condition for the asymptotic optimality of RRT is that infinitely many branches of the tree contain vertices outside a small ball centred at the initial condition. This is captured in the following lemma. Lemma 1: Let 0 < R < inf y ∈ X goal || y − x init || . The event { lim N → ∞ Y n = c ∗ } occurs only if the k th branch of the RRT has vertices outside the R -ball centred at x init , for infinitely many k . We observe that a necessary condition for optimality should be applicable to all the nodes in the tree and not just only x init . Consequently, we hypothesize that for a tree like planner to return an asymptotically optimal solution it is a necessary condition to have a mechanism which creates infinite degree of the tree vertices. Next, it is shown that the RRT algorithm does not sat- isfy the condition for asymptotic optimality. In the detailed analysis, as can be found in [9], the authors note that if U = { X 1 , X 2 , . . . , X n } be a set of independently sampled and uniformly distributed points in the d -dimensional unit cube [ 0 , 1 ] d , and if X n + 1 is a newly sampled i.i.d. point, then the probability, that among all points in U the point in X i is the one that is closest to X n + 1 , is 1 / n . An immediate consequence of this result is that each vertex of the RRT has unbounded degree almost surely as the number of samples approaches infinity. We note that, although in the sample configuration phase of RRT algorithm, a new sample is chosen according to a uniform distribution, the selection of a node as nearest neighbour to this sample also depends on the existing geo- metric Voronoi partition of all nodes. The node with higher Voronoi volume will have a higher chance of being selected as the nearest neighbour. Only when the Voronoi partition is approximately equal for every node, the selection of the nearest neighbour will be independent of spatial distribution of nodes. Secondly, even if the nearest neighbour selection is according to a uniform distribution, this does not guarantee that each vertex will have an unbounded degree. We present a theoretical argument as well as a simulation to support our claim. Additionally, an extension of this observation leads to an alternate proof of non-optimality of RRT algorithm in an asymptotic sense. Theorem 1: The solution trajectory returned by the RRT algorithm is not asymptotically optimal. Proof: Before giving the proof, in the following, some definitions are presented which was used in the deduction. Definition 2: Let the state space X be a metric space. We assume X is path connected. That is, any pair of states A , B ∈ X can be connected by a continuous path ζ ∈ X which is appropriately parametrized. Denote d ( x , y ) as a distance metric in X . For simplicity, we consider a holonomic planning problem. Definition 3: Let the tree nodes, defined as { x 0 , x 1 , . . . , x i , . . . } , form an incremental construction of the RRT tree where indexes are identified with time instances. Definition 4: Given a region R and a set of points in P X ∈ R , there exists a unique arrangement of partition of the region, denoted as Voronoi partitions V P X for each x ∈ P X as the set of points closer to x than any other point y ∈ P X . Note that, for an n th incremental construction, the obtained RRT vertices are defined as { x 0 , x 1 , . . . , x n } . The Voronoi volume of x i , V x i , n is a non increasing function in n . That is, V x i , n ≥ V x i , n + 1 . We emphasize this fact continuing in the similar way as in [19]. Let x n be a point, uniformly at random, in a convex region R . Let x c be a point in R considered as the origin. Now, we can divide R into f ( d ) number of disjoint cones, defined as c 1 , . . . , c f ( d ) [26]. Suppose x n falls into some such cone c i . If y is any other point in c i then let R ′ be the set of points in R which is closer to x n than x c . Now we can write that R \ R ′ contains a segment of c i which is shrunk by a factor of two in every dimension. So, in this case, μ ( R \ R ′ ) ≥ μ ( c i ) / 2 d (1) where, d is the dimension and μ is the d dimensional Lebesgue measure. Note that, the probability that x n will be within any of such c i s is equal to the volume ratio of c i to R . Taking the expectation over all c i , E ( μ ( R \ R ′ ) = f ( d ) ∑ i = 1 p i μ ( c i ) / 2 d (2) where, p i is the probability that x n will fall within of the c i . Since, p i = μ ( c i ) / μ ( R ) , therefore, E ( μ ( R \ R ′ )) ≥ f ( d ) ∑ i = 1 μ ( c i ) 2 / ( 2 d μ ( R )) (3) = μ ( R ) / ( 2 d f ( d )) (4) Naturally, this implies E ( μ ( R ′ )) ≤ ( 2 d f ( d ) − 1 )( μ ( R )) / ( 2 d f ( d )) . Let, at any instant t 0 , the Voronoi volume of the i th node is μ ( V x i , n ) 0 and γ = ( 2 d f ( d ) − 1 ) / ( 2 d f ( d )) . From recursion, E ( μ ( V t 0 + k x i , n )) ≤ γ k μ ( V 0 x i , n ) (5) Now, we try to show an upper bound on the probability of the event that a RRT vertex increases its degree from k to k + 1 at some instant. Let the degree of x i be k . Then, in order to have a degree of k + 1 in the next instant of the tree generation, either of the following event should happen. For any volume v x , either the Voronoi volume of V x i , n is more than v x , or the dispersions created by the other vertices of the tree should have a volume less than v x . Taking an union bound, p ( deg ( x i ) ≥ k + 1 ) ≤ p ( μ ( V x i , n ) k ≥ v x ) + p ( μ ( V x j , n ) ≤ v x ) (6) ∀ j ∈ { x 0 , x 1 , . . . , x n } , j 6 = i Now, using Markov’s inequality, we have p ( μ ( V x i , n ) k ≥ v x ) ≤ E ( μ ( V x i , n ) k ) / v x . For the other probability we can use again the union bound over all x 0 , . . . , x n and, p ( μ ( V x j , n ) ≤ v x ) ≤ α nv x , for some constant α . Therefore, p ( deg ( x i ) ≥ k + 1 ) ≤ E ( μ ( V x i , n ) k ) / v x + α nv x (7) If, μ ( V x i , n ) 0 = O ( 1 / n ) , using (5), v x can be chosen optimally as v x = γ k / 2 O ( 1 / n ) . The choice of μ ( V x i , n ) 0 = O ( 1 / n ) is justified as it is shown in [28]. Then summing over all the n nodes, the expected number of nodes with degree at least k + 1 is at most αγ k / 2 O ( 1 ) . Hence, it is evident that the degree distribution of the vertices of the RRT tree follows a power law. This implies that the RRT tree will contain fewer and fewer vertices with higher and higher degree. In other words, the chance that nodes will create an infinite number of branches becomes lesser and lesser as the number of iterations increases. However, since for a sampling based planner, the measure of the event that the planner finds the optimal path within any finite iteration is zero; hence, there must be a sequence of paths which converges to the optimum path. For existence of such a sequence, it is necessary that the vertex degrees should be infinite, which is in opposition to the present findings. Hence, an RRT planner with such node degree distribution cannot be an asymptotically optimal planner. As a corollary to the above theorem, it can be said that a sampling based planner for which its degree distribution follows a power law cannot be a candidate for optimal motion planning. In the following section, to further establish Theorem 1, a numerical simulation is provided which clearly shows that the cumulative degree distribution follows a power law, if not exponential. V. R ESULTS AND D ISCUSSION To validate the theoretical claim the following simulation of an RRT is performed. The system is a simple non- holonomic car, shown in Figure 1, and defined by the following equations: ̇ x = v cos θ (8) ̇ y = v sin θ (9) ̇ θ = ( v / L ) tan φ (10) where, L is the length between the wheels, v is the velocity and φ is the steering angle. The position of the car and its orientation is denoted by a 3-tuple ( x , y , θ ) . The control variables are velocity v and steering angle. The configuration space is R 2 × S 1 . Figure 2 shows the histogram of vertex out degree of the RRT planner after 5000, 10000, 15000, and 20000 iterations. The vertex out degree is an indication of how many branches are emitted from a single vertex. Clearly, the histogram shows that a vertex with very high value of out degree is less frequent compared to the vertices with lesser out degree. The simulation strongly supports the theoretical claim. Note that this characteristics of RRT vertices are actually L θ φ x y Fig. 1. A Non-holonomic car (a) (b) (c) (d) Fig. 2. (a) Histogram of RRT vertices out degree after 5000 iterations (b) after 10000 iterations (c) after 150000 iterations (d) after 20000 iterations. The abscissa represents node out degree and the ordinate represents the number of RRT nodes having the same out degree. independent of system dynamics. This is because the addi- tional node generation is only dependent on random samples and nearest neighbour subroutines. VI. C ONCLUSION In this paper we investigated the asymptotic optimality of an existing randomized sampling based algorithms, namely RRT. We showed that the degree distribution in RRT plan- ner follows a power law. This also implies that the RRT planner is not an asymptotically optimal planner which is consistent with existing results. We also present a simulation which strongly supports the theoretical claim. It would be interesting to analyse other sampling based algorithms in the perspective of asymptotic degree distribution. R EFERENCES [1] Schwartz, J. T. and Sharir, M., “On the piano mover’s problem: II. General techniques for computing topological properties of algebraic manifolds,” Communications on pure and Applied mathematics , vol. 36, pp. 345-398, 1983. [2] Reif, J. H., “Complexity of the mover’s problem and generalization,” In: Proc. of 20th Annual Symposium on Foundations of Computer Science , San Juan, Puerto Rico, pp. 421-427, 1979. [3] Kavraki, L. E., Svestka, P., Latombe, J. C. and Overmars, M. H., “Probabilistic roadmap for path planning in high dimensional config- uration spaces,” IEEE Transaction on Robotics and Automation , vol. 12, no. 4, pp. 566-580, 1996. [4] Lavalle, S. M., “Rapidly exploring random tree,” Technical Report TR 98 -11, Computer Science Department , Iowa State University, 1998. [5] S. M. LaValle and J. J. Kuffner. “Randomized kinodynamic planning”. The International Journal of Robotics Research , 20(5):378?400, 2001 [6] D. Hsu, J.-C. Latombe, and R. Motwani. “Path planning in expansive configuration spaces,” International Journal of Computational Geom- etry and Applications , 9(4):495?512, 1999. [7] Bohlin, Robert, and Lydia E. Kavraki. “Path planning using lazy PRM.” International Conference on Robotics and Automation , Vol. 1. IEEE, 2000. [8] Plaku, E., Bekris, K. E., Chen, B. Y., Ladd, A. M., and Kavraki, L. E. “Sampling-based roadmap of trees for parallel motion planning, IEEE Transactions on Robotics , 21(4), 597-608. [9] Karaman, S. and Frazzoli, E., “Sampling-based algorithms for optimal motion planning,” International Journal of Robotic Research , vol. 30, no. 7, pp. 846-894, 2011. [10] S. R. Lindemann and S. M. LaValle. “Current issues in sampling- based motion planning,” In The Eleventh International Symposium on Robotics Research , pp. 36?54, Siena, Italy, 2003. [11] Choset, H. et al., “Principles of robot motion: theory algorithms and implementations,” MIT Press , Cambridge, Massachusetts, 2005. [12] Carpin, S., “Randomized motion planning - a tutorial,” International Journal of Robotics and Automation , vol. 21, no. 3, pp. 184-196, 2006. [13] Kavraki, L. E., Kolountzakis, M. N. and Latombe, J. C., “Analysis of probabilistic roadmaps for path planning,” IEEE Transactions on Robotics and Automation , vol. 14, no. 1, pp. 166-171, 1998 [14] Ladd, A. M. and Kavraki, L. E., “Measure theoretic analysis of probabilistic path planning,” IEEE Transactions on Robotics , vol. 20, no. 2, pp. 229-242, 2004. [15] Hsu, D., Latombe, J. C. and Kurniawati, H., “On the probabilistic foundations of probabilistic roadmap planning,” In Proc. International Symposium on Robotics Research , vol. 25, no. 7, pp. 627-643, 2005. [16] Chaudhuri, S. and Koltun, V., “Smoothed analysis of probabilis- tic roadmaps,” Computational Geometry: Theory and Applications archive , vol. 42, no. 8, pp. 731-747, 2009. [17] Bera, T., Bhat. M. S and Ghose D., “Probabilistic analysis of sampling based path planning algorithms,” IEEE Multi-Conference on Systems and Control , Hyderabad, India, 2013 [18] Fabrikant, Alex, Elias Koutsoupias, and Christos H. Papadimitriou. “Heuristically optimized trade-offs: A new paradigm for power laws in the Internet.” International Colloquium on Automata, Languages, and Programming . Springer Berlin Heidelberg, 2002. [19] Berger, N., Bollobs, B., Borgs, C., Chayes, J., and Riordan, O. “Degree distribution of the FKP network model”. International Colloquium on Automata, Languages, and Programming , (pp. 725-738). Springer Berlin Heidelberg, 2003 [20] D. M. Mount. “On finding shortest paths on convex polyhedra,” Technical report, DTIC Document , CS-TR-1495, 1985. [21] C. H. Papadimitriou.“ An algorithm for shortest-path motion in three dimensions,” Information Processing Letters , 20(5):259?263, 1985. [22] A. Sharir and A. Baltsan. “On shortest paths amidst convex polyhedra,” In Proceedings of the Second Annual Symposium on Computational Geometry , pages 193-206, Yorktown Heights, NY, USA, 1986. [23] J. H. Reif and J. A. Storer. “Shortest paths in euclidean space with polyhedral obstacles,” Technical report, DTIC Document, 1985 [24] Steven M LaValle and James J Kuffner Jr. “Rapidly-exploring random trees: Progress and prospects. In New Directions in Algorithmic and Computational Robotics”, pages 293-308, Hannovar, Germany, 2000 [25] Bollobas, B. and Riordan, O., “Percolation,” Cambridge University Press , 2006. [26] Yukich, J., “Probability theory of classical euclidean optimization problem,” Springer , 1998. [27] Niederreiter, H., “Random Number Generation and Quasi-Monte- Carlo Methods,” Society for Industrial and Applied Mathematics , Philadelphia, USA, 1992. [28] Janson, Lucas, Brian Ichter, and Marco Pavone.“Deterministic Sampling-Based Motion Planning: Optimality, Complexity, and Per- formance,” arXiv preprint arXiv:1505.00023 (2015).