Path Planning using Probabilistic Cell Decomposition

Similar documents
vizmo++: a Visualization, Authoring, and Educational Tool for Motion Planning

Sampling-based Planning 2

CS 4649/7649 Robot Intelligence: Planning

Sampling-Based Robot Motion Planning. Lydia Kavraki Department of Computer Science Rice University Houston, TX USA

Autonomous and Mobile Robotics Prof. Giuseppe Oriolo. Motion Planning 1 Retraction and Cell Decomposition

6.141: Robotics systems and science Lecture 9: Configuration Space and Motion Planning

Robot Motion Planning

Probabilistic roadmaps for efficient path planning

Path Planning using Probabilistic Cell Decomposition FRANK LINGELBACH

Path Planning among Movable Obstacles: a Probabilistically Complete Approach

Probabilistic Motion Planning: Algorithms and Applications

Figure 1: A typical industrial scene with over 4000 obstacles. not cause collisions) into a number of cells. Motion is than planned through these cell

Exploiting collision information in probabilistic roadmap planning

II. RELATED WORK. A. Probabilistic roadmap path planner

Mobile Robot Path Planning in Static Environments using Particle Swarm Optimization

Collided Path Replanning in Dynamic Environments Using RRT and Cell Decomposition Algorithms

The Corridor Map Method: Real-Time High-Quality Path Planning

Workspace-Guided Rapidly-Exploring Random Tree Method for a Robot Arm

Iteratively Locating Voronoi Vertices for Dispersion Estimation

6.141: Robotics systems and science Lecture 9: Configuration Space and Motion Planning

Probabilistic Roadmap Planner with Adaptive Sampling Based on Clustering

Introduction to State-of-the-art Motion Planning Algorithms. Presented by Konstantinos Tsianos

Variable-resolution Velocity Roadmap Generation Considering Safety Constraints for Mobile Robots

Learning to Guide Random Tree Planners in High Dimensional Spaces

CHAPTER SIX. the RRM creates small covering roadmaps for all tested environments.

biasing the sampling based on the geometric characteristics of configurations known to be reachable from the assembled configuration (the start). In p

for Motion Planning RSS Lecture 10 Prof. Seth Teller

Probabilistic Roadmaps of Trees for Parallel Computation of Multiple Query Roadmaps

Efficient Motion Planning for Humanoid Robots using Lazy Collision Checking and Enlarged Robot Models

Incrementally Reducing Dispersion by Increasing Voronoi Bias in RRTs

ECE276B: Planning & Learning in Robotics Lecture 5: Configuration Space

Configuration Space of a Robot

Providing Haptic Hints to Automatic Motion Planners

Motion Planning with Dynamics, Physics based Simulations, and Linear Temporal Objectives. Erion Plaku

COMPLETE AND SCALABLE MULTI-ROBOT PLANNING IN TUNNEL ENVIRONMENTS. Mike Peasgood John McPhee Christopher Clark

Balancing Exploration and Exploitation in Motion Planning

Mobile Robots Path Planning using Genetic Algorithms

Probabilistic Methods for Kinodynamic Path Planning

Algorithms for Sensor-Based Robotics: Sampling-Based Motion Planning

1 Proximity via Graph Spanners

Advanced Robotics Path Planning & Navigation

Nonholonomic motion planning for car-like robots

Path Planning for a Robot Manipulator based on Probabilistic Roadmap and Reinforcement Learning

RRT-Connect: An Efficient Approach to Single-Query Path Planning

Algorithms for Sensor-Based Robotics: Sampling-Based Motion Planning

T S. Configuration Space S1 LP S0 ITM. S3 Start cfg

A Hybrid Approach for Complete Motion Planning

SPATIAL GUIDANCE TO RRT PLANNER USING CELL-DECOMPOSITION ALGORITHM

Geometric Path Planning for General Robot Manipulators

An Eternal Domination Problem in Grids

Useful Cycles in Probabilistic Roadmap Graphs

Path Planning. Jacky Baltes Dept. of Computer Science University of Manitoba 11/21/10

Motion Planning 2D. Corso di Robotica Prof. Davide Brugali Università degli Studi di Bergamo

UOBPRM: A Uniformly Distributed Obstacle-Based PRM

D-Plan: Efficient Collision-Free Path Computation for Part Removal and Disassembly

crrt : Planning loosely-coupled motions for multiple mobile robots

Incremental Map Generation (IMG)

Geometric Path Planning McGill COMP 765 Oct 12 th, 2017

Dynamic-Domain RRTs: Efficient Exploration by Controlling the Sampling Domain

Specialized PRM Trajectory Planning For Hyper-Redundant Robot Manipulators

Adaptive Tuning of the Sampling Domain for Dynamic-Domain RRTs

RESAMPL: A Region-Sensitive Adaptive Motion Planner

Robot Motion Planning

Customizing PRM Roadmaps at Query Time Λ

Steps Toward Derandomizing RRTs

Stable Trajectory Design for Highly Constrained Environments using Receding Horizon Control

G 6i try. On the Number of Minimal 1-Steiner Trees* Discrete Comput Geom 12:29-34 (1994)

CS Path Planning

Visibility: Finding the Staircase Kernel in Orthogonal Polygons

Configuration Space. Ioannis Rekleitis

A Slicing Connection Strategy for Constructing PRMs in High-Dimensional Cspaces

Connected Components of Underlying Graphs of Halving Lines

Spring 2010: Lecture 9. Ashutosh Saxena. Ashutosh Saxena

Incremental Map Generation (IMG)

Optimizing Schedules for Prioritized Path Planning of Multi-Robot Systems

f-v v-f f-e e-f f-f e-e-cross e-v v-e degenerate PCs e-e-touch v-v

A Hybrid Approach for Complete Motion Planning

Part I Part 1 Sampling-based Motion Planning

Path Planning in Repetitive Environments

Introduction to Robotics

Star-shaped Roadmaps - A Deterministic Sampling Approach for Complete Motion Planning

Part I Part 1 Sampling-based Motion Planning

1 The range query problem

OOPS for Motion Planning: An Online, Open-source, Programming System

Workspace Skeleton Tools for Motion Planning

(Refer Slide Time: 00:02:00)

Planning with Reachable Distances: Fast Enforcement of Closure Constraints

PRM path planning optimization algorithm research

Last update: May 6, Robotics. CMSC 421: Chapter 25. CMSC 421: Chapter 25 1

6.141: Robotics systems and science Lecture 10: Implementing Motion Planning

Kinodynamic Motion Planning on Roadmaps in Dynamic Environments

Lecture 3: Art Gallery Problems and Polygon Triangulation

Sampling Techniques for Probabilistic Roadmap Planners

This chapter explains two techniques which are frequently used throughout

Clearance Based Path Optimization for Motion Planning

Geometric Computations for Simulation

Algorithms for Grid Graphs in the MapReduce Model

Robot Motion Planning in Eight Directions

Planning in Mobile Robotics

Motion Planning. Howie CHoset

Transcription:

Path Planning using Probabilistic Cell Decomposition Frank Lingelbach Centre for Autonomous Systems Royal Institute of Technology SE-100 44 Stockholm, Sweden Email: frank.lingelbach@s3.kth.se Abstract In this paper we present a new approach to path planning in high-dimensional static configuration spaces. The concept of cell decomposition is combined with probabilistic sampling to obtain a method called Probabilistic Cell Decomposition (PCD). The use of lazy evaluation techniques and supervised sampling in important areas leads to a very competitive path planning method. It is shown that PCD is probabilistic complete. PCD is easily scalable and applicable to many different kinds of problems. Experimental results show that PCD performs well under various conditions. Rigid body movements, maze like problems as well as path planning problems for chainlike robotic platforms have been solved successfully using the proposed algorithm. I. INTRODUCTION Motion planning is a key acquirement demanded of autonomous robots. Given a task to fulfill, the robot has to plan its actions including collision-free movements of actuators or the whole robotic platform. The problem of path planning is not confined to the field of robotics but applications exist in various genres. For example, molecule folding [1], assembly/disassembly problems [2] and computer animations [3] are areas where comparable problems arise. Unfortunately the underlying generalized mover s problem and several related problems were shown to be PSPACE hard [4]. Complete algorithms exist, but their area of application is limited to simple problems as they suffer from the curse of dimensionality. The execution time depends exponentially on the dimension of the search space. In the field of robotics the search space is typically the configuration space C. A robotic system consisting of a manipulator mounted on a moving platform has many degrees of freedom. As every degree of freedom corresponds to a dimension in the corresponding configuration space C, this increases the cost of finding a collision-free path. This paper contributes to the problem by incorporating stateof-the-art in the field of probabilistic path planning into the underlying method of cell decomposition. In this manner an approximate representation of the collision-free part of the configuration space (C free ) is obtained, which is then used to guide probabilistic sampling in interesting areas. Section III-B introduces the algorithm and presents elementary components in more detail. In particular, different sampling techniques are investigated. In Section IV these are tested using a set of benchmark problems and results are compared to another probabilistic path planning method. II. RELATED WORK Most complete algorithms can be classified as deterministic cell decomposition and roadmap methods or potential field methods, where in the latter a potential field attracts the state in configuration space towards the desired goal configuration, while obstacles have a repelling effect. An overview of these classical methods can, e.g., be found in [4]. Probabilistic path planning techniques have achieved substantial attention throughout the last decade as they are capable of solving high dimensional problems in acceptable execution times [5]. Two very effective techniques in this field are Probabilistic Roadmap Methods (PRM) [6], [7], [8], and Rapidlyexploring Random Trees (RRT) [9]. Both these methods have been developed over the last years. PRM usually distinguish between a learning phase and a query phase. In the learning phase a road map is built by randomly sampling the configuration space. Those samples that correspond to collision-free configurations form the vertices of the roadmap. Neighboring vertices are then connected by edges, if all states along these edges also are collision-free. In the query phase, the initial and the goal state are connected to the roadmap, which is then searched for a path connecting these two states. A variation of this algorithm giving very good results, especially if collision checking is very costly, is the Lazy PRM [10]. Here the roadmap is not built in the collisionfree configuration space C free, but in the whole configuration space C. First after a path has been found in the query phase, this path is checked whether it is feasible or not. Thereby the number of collision checks needed is reduced drastically. This concept of lazy evaluation is utilized in PCD. In the basic RRT algorithm a tree is grown from the initial configuration to explore C free. In each step a random sample in C is taken. Starting from the nearest vertex in the tree a new edge pointing at the sample is added. One of the most efficient variations of this algorithm is RRTConCon [11]. Here one tree is grown from the initial configuration and another from the desired goal configuration. In every step both trees try to connect to the same state in C free. Thus a path is often found very quickly at the cost of diverging a lot from an optimal path. This can be corrected by a subsequent smoothing

step. The major advantage of RRT-like methods is that they are perfectly suitable for non-holonomic and kinodynamic planning problems. For these types of problems, PRM and the proposed PCD method face the difficulty that connecting two states by an edge raises a possibly non-trivial control problem. Recently, excellent results have been obtained using RRT as a local planner within a PRM framework where each node of the roadmap is a tree [12]. All methods described above have in common that they are planning in a perfectly known world. For robotic applications this is unfortunately only true for simulations or approximately for robotic work cells in industry, where CAD models are available and the whole environment is static. III. PROBABILISTIC CELL DECOMPOSITION In this section, we first give a brief introduction to the classical concept of cell decomposition. Then the modifications and extensions to Probabilistic Cell Decomposition are presented. A. Cell Decomposition The idea behind cell decomposition methods is to partition C free into disjoint sets, called cells [4]. These cells form the nodes of a non-directed connectivity graph G. Two nodes are connected by an edge if and only if the corresponding cells are adjacent. A feasible path connecting a start configuration x init with a goal configuration x goal is found if there exists a path in G connecting the cells containing x init and x goal respectively. Such a cell path in G is called a channel. Cell decomposition methods can be classified as exact and approximate. PCD is based on the latter, where all cells have a predefined shape and cell boundaries do not necessarily have any physical meaning, e.g. correspond to changes in motion constraints. The most commonly used decomposition technique is the 2 m -tree decomposition, where m is the dimension of the configuration space. A cell that is not entirely contained in C free or the complement of C free in C, C obst, is called mixed and is split up into 2 m subcells. These are then recursively refined in the same manner until a path in G has been found or a given minimum resolution is reached. This indicates that the complexity of these algorithms is exponentially in m constraining the applicability for planning in high-dimensional spaces. Besides the complexity problem caused by the splitting technique, the classical method suffers mainly from the high cost of determining whether a cell is entirely contained in C free or not. B. Method To handle this problem in PCD, a cell is not checked but assumed to be free until disproval. A cell is called possibly free, as long as all collision checks of samples in this cell have negative outcome. Accordingly it is called possibly occupied if all checks are positive. If both collision-free and colliding samples occur in the same cell, it is named known to be mixed and has to be split up into possibly free and possibly occupied cells. This implies unfortunately that a cell path in G does no longer automatically deduce an existing path in C free, but the states along a path through this channel have to be checked for collision. Let us introduce the basic notation. A cell κ i might be possibly free, i.e. P (κ i C free ) > 0 possibly occupied, i.e. P (κ i C obst ) > 0 known to be mixed, i.e. κ i C free κ i C obst Let κ init and κ goal denote the possibly free cells containing the initial and the goal configuration respectively. Note that throughout the decomposition process these labels might be passed to different cells. The nodes of the connectivity graph G are the possibly free cells. Two nodes are connected by an edge if and only if the corresponding cells are adjacent. The set of cells corresponding to the connected component of G containing κ init is called the start region R init, accordingly for the goal region R goal. The basic PCD algorithm is given as WHILE (!success ) IF ( path <- findcellpath(g) ) IF ( checkpath(path) ) success <- true ELSE ELSE x <- randomstate(pocccells) IF (!collision(x) ) Initially set κ init = κ goal = C. Whenever there exists a channel in G connecting κ init with κ goal, check the states along a path through these cells connecting x init with x goal. If no collision occurs, a feasible path has been found. The cells are evaluated lazily. Otherwise, a cell that was marked as possibly free contains free and colliding states. Thus this cell has to be marked as known to be mixed and split up into possibly free and possibly occupied cells. If no such channel exists in G, check random states in the possibly occupied cells for collision. If the test is negative, a cell that was marked as possibly occupied contains free and colliding states and has to be relabelled and split up. In this manner the possibly occupied cells are refined until a path in G has been found. All states that are checked for collision, either in the sampling step or while path checking, that do not lie on the boundary between two cells, are stored as samples in the respective cell. In the following the important parts of the algorithm are described in some more detail and possible extensions are shown. 1) Cell Shape: We chose to decompose the configuration space into rectangloid cells as the advantages of this shape clearly outrange existing drawbacks. Trivially any rectangloid is convex. Furthermore it is defined by only 2n values (one upper and the opposing lower vertex), which is beneficial with respect to both memory consumption and execution time. In contrast an arbitrary n-dimensional polytope with the same

number of vertices as the corresponding rectangloid is defined by n 2 n values. Starting with rectangloid cells aligned to the coordinate axes, the cells obtained by splitting a cell orthogonal to any coordinate axis are trivially also rectangloid. The check if two cells are adjacent is simplified considerably as it is divided up into two easily verifiable parts. First checking if one of the coordinates of the upper vertex of one cell is equal to the respective coordinate of the lower vertex of the other cell and - if so - check if the measure of the shared area on the (n-1)-dimensional hyperplane orthogonal to this coordinate axis is larger than zero. An obvious drawback of the rectangloid cell shape is that even geometrically simple obstacles can hardly ever be made up by a finite number of cells. Additionally the resulting path planner is not independent of the internal alignment of the problem. This second argument will vanish if the obstacles in C are mainly not oriented in a common direction. 2) Graph Search: The possibly free cells form the vertices in a non-directed, possibly not connected graph. Two adjacent cells are connected by an edge. Adjacency in this context is defined as indicated above. The (n-1)-dimensional measure of the shared area on the boundary between two cells has to be larger than zero. This allows for multiple edges connecting the same two vertices depending on the topology of the configuration space. A*-search [13] is then used to find a channel φ connecting κ init with κ goal. 3) Probabilistic Sampling: Whenever a channel is not found, the possibly occupied cells are sampled in order to refine them and make them better adopt the obstacles in C. Different ways of distributing the samples are possible. One sample could be taken in every possibly occupied cell, uniformly distributed within each cell (scheme (i)) A number of samples could be distributed uniformly over the accumulated volume of all possibly occupied cells (ii) A number of samples could be distributed in a list of interesting cells (iii) In [14] an uncertain cell (in our case a possibly occupied cell) is called interesting if it is adjacent to R init or R goal.asit turned out in the experiments, for the chosen problems almost all possibly occupied cells are adjacent to at least one of these regions. Tightening the requirements, a possibly occupied cell is called interesting if it is adjacent to R init and R goal.to maintain probabilistic completeness (see Section III-C), with a given probability of p > 0 sampling scheme (i) is used instead of (iii). For scheme (ii) it remains to determine the parameter q of how many samples to distribute in each sampling step. This will be investigated in Section IV. Figure (1) shows a 2D example where the circle in the lower left corner has to be connected to the circle in the upper right corner. Those cells marked dark gray in the left illustration will be omitted by scheme (iii) as they are not separating the goal from the start region. Fig. 1. Left figure: cell decomposition after some iterations; right: path found after a few more iterations; obstacles: ( ), possibly free cells: white; interesting / not interesting possibly occupied cells according to sampling scheme (ii): light gray / dark gray; path ( ) 4) Cell Splitting: Whenever a collision-free state is found within a possibly colliding cell or a colliding state is found within a possibly free cell, this cell has to be marked as known to be mixed and split up into possibly free and possibly colliding cells. The requirement for rectangloid cells restricts us to cuts along the coordinate axes. A cell that is known to be mixed might not be divided into one possibly free and one possibly colliding cell only, but further splitting could be necessary. Lemma 1: A n-dimensional rectangloid cell that is known to be mixed containing m collision-free samples and one colliding sample (accordingly vice versa) can be split up into at most min(2n, m) free cells and one colliding cell. The strategy used to determine where to cut a cell was finding the nearest existing sample and then cut orthogonal to the dimension of the largest distance right in the middle between those two samples. 5) Local Path Planning: If a channel φ = {κ init = κ p0,κ p1,...,κ pn = κ goal } in G has been found connecting κ init with κ goal a local path planner tries to find a path in C free connecting x init with x goal.inan-dimensional configuration space, two adjacent cells are separated by a (n-1)-dimensional hyperplane. To find a path through a possibly free cell κ pi, the local path planner simply tries to connect the center of the shared area on the hyperplane separating κ pi 1 and κ pi with the center of the shared area on the hyperplane separating κ pi and κ pi+1 by a straight line. Similarly x init and x goal are connected to the center of the shared boundary to the next cell on φ. This path in C is then checked for collisions to determine whether it is entirely lying in C free or not. For the moment this check is done at r discrete points along the path. Observe that for any finite step size between these points and for arbitrary robot shapes and obstacles this can not guarantee that the continuous path is collision-free as well. Here adaptive step size methods using distance measures or a swept volume approach could give certainty at the cost of higher computational effort. Discrete point collision checking has been studied in the context of PRM [15]. Mainly two techniques, incremental and binary checking, have drawn major attention. The incremental method checks a path by successively checking configurations at a given step size along the path. In contrast, the binary

method checks the configuration midway on the path and then recursively uses this technique to check the first and the second half until a given step size has been reached. In general the binary checking detects a collision faster as it is more likely that colliding states lie in the middle of the path than close to the collision-free ends. Therefore binary checking is used within PCD. C. Probabilistic Completeness For simplicity, probabilistic completeness is proven for C = R n and the Euclidian metric. Nevertheless it can easily be carried over to topologically different spaces and metrics. Let γ :[0,L] C free, γ(0) = x init, γ(l) =x goal denote a continuous path of length L connecting x init with x goal parameterized by arc length. Let furthermore B n (r, x) be the n-dimensional ball of radius r around a point x and P S (k) be the probability of successfully finding a path using PCD within k iterations. Theorem 1: If there exists a path γ and an ɛ>0, such that for all l [0,L] the ball B n (ɛ, γ(l)) is entirely contained in C free, then lim k P S (k) =1. Outline of proof: The algorithm in III-B is equivalent to WHILE (!success ) WHILE ( ( path <- findcellpath(g) ) &&!success ) IF ( checkpath(path) ) success <- true ELSE IF (!success ) x <- randomstate(pocccells) IF (!collision(x) ) Refer to the inner while loop with (a) and to the remaining if-clause with (b). (a) While a cell path φ exists, the collision checking of states along a path through these cells may either result in success or at least one cell has to be split. Observe that following the steps described earlier in this chapter, no collision-free samples will lie exactly on the boundary between two cells. This is important to avoid a possible deadlock in this inner while loop. Thus, after a bounded number of iterations, the search will end with either success or a situation (b). (b) Whenever no cell path φ exists connecting κ init with κ goal random samples are taken from possibly occupied cells and checked for collision. Provided that γ : [0,L] C free exists inside an ɛ-tunnel T ɛ = l [0,L] B n(ɛ, γ(l)) as given in the theorem, the probability of a sample to lie inside this ɛ-tunnel is larger than zero. As (a) results in either success or situation (b) after a finite number of iterations and the expected number of iterations needed to find a cell path covering the ɛ-tunnel is bounded from above, lim k P S (k) =1. Remark: Observe that the assumption of an ɛ-tunnel around the whole path including x init and x goal prohibits a setup where e.g. a robot in its goal configuration is in contact with an obstacle, as e.g. in a grasping task. Fortunately it suffices to assume that x init and x goal can be connected to some ˆx init and ˆx goal on which the theorem can be applied. IV. EXPERIMENTAL RESULTS In this section experimental results are presented for various kinds of problems followed by an interpretation of these results. The PCD planner presented in Section III-B is used comparing the performance of the different sampling schemes. Please observe that the algorithm can easily be customized for different kinds of robots or environments yielding improvements in efficiency. Taking the Puma 560 robotic arm as an example: For more than 50 % of the configuration space C = [ π, π] 6 the robot is in self-collision (more than 70 % if the tool of Problem IV is attached). A rather fine cell decomposition of C, representing this self-collision areas, could be computed in advance and used as a starting point for individual motion planning problems. Another aspect for chain-like robots is that from the type of collision conclusions can be drawn regarding further progress. If, e.g., the base is in collision with an obstacle, it is already known that all other configurations with the same base state also are colliding. In PCD this information can be exploited in the cell splitting step. These customizations have not been carried out here and would go beyond the scope of this paper but have to be considered when motion planning problems for one specific agent have to be solved. A. Experimental Setup The different sampling strategies presented in Section III- B have been tested on the set of benchmark problems shown in figure (2). To get an estimate of the performance of PCD, results are compared with those given by RRTConCon. To demonstrate the whole application area, maze like problems, rigid body motion planning and path planning for chainlike robots are presented. The computation times were measured on a 1700 MHz machine with 512 MB of physical RAM. We used the Motion Strategy Library developed at the University of Illinois to compare the different algorithms. RRTConCon came with this package. Also three of the five problems 2dpoint1, cage and multi3 were taken from this library, where the last one was modified by exchanging the rigid bodies. Since all methods use probabilistic sampling, the results are not directly repeatable. Therefore the data presented is based on 100 independent runs for each method and problem in case of the 48D multi rigid body problem on 25 runs. Beneath minimum, maximum and average values of the execution time, its variance and the number of collision checks are presented. For PCD the average number of possibly free and possibly occupied cells is given additionally, while for RRTConCon

the average number of nodes is presented. As the geometry of the chosen examples is quite simple resulting in fast collision checks, the performance is expected to be shifted towards those methods requiring less checks for more complicated environments. The upper row of figure (2) shows a 2D maze (problem 2dpoint1 in MSL) and typical solutions given by PCD and RRTConCon to the left and to the right respectively. The almost dot-like agent has to traverse the maze from the lower right corner to the goal in the upper right corner. Next a narrow corridor problem has been investigated. Again the goal is in the upper right corner. The corridor is only slightly wider than the dot that has to pass through it. Almost the whole configuration space is collision-free making this problem perfect for the PCD algorithm. The obstacles are identified and the corridor is found instantly. The nibs on both sides of the corridor make it very hard for RRT methods to find a path while not decreasing PCD performance substantially. In Problem (III) the L-shaped free flying rigid body has to escape a cage (cage in MSL). In Problem (IV) a PUMA 560 robot arm has to operate an unwieldy tool through a window. With its six degrees of freedom it has to move the tool from a position on the other side of the window to the configuration shown. The position of the platform in front of the window is fixed. The last benchmark problem can be seen to the right in the lower row of figure (2) The eight Stanford Bunnies can move freely in space, thus each has six degrees of freedom, summing up to a 48 dimensional configuration space. The objects have to interchange places without colliding with each other. Obviously there are more elegant ways to solve this problem than searching for a path in the composed configuration space. Nevertheless it is still interesting to compare the performance of the different algorithms. Each bunny is made up of approximately 2200 triangles. (multi3 in MSL, Stanford Bunnies instead of rods) B. Summary of the Results The results are presented in table (I). For the uniform sampling over the accumulated volume of possibly occupied cells, three tests have been carried out with q = min(#κ occ, ˆq) with ˆq =5, 50 and 500, respectively. Clearly, sampling strategy (iii) gives the best results for the problems chosen. It outperforms strategy (i) by concentrating the sampling on possibly occupied cells that are likely to connect the start with the goal region. The relative performance of strategy (ii) compared to the other ones is very volatile and depends much on the problem. When the solution path has to pass a narrow corridor like in Problems (II) or (IV) the execution time for a low number of samples explodes. This is due to the fact that during the solution process the corridor can be blocked by a small possibly occupied cell. If only a few samples are taken uniformly distributed over the accumulated volume of possibly occupied cells, it is very unlikely that a sample falls into this blocking Fig. 2. Benchmark problems: 2D maze with typical solution paths given by PCD (upper left) and RRTConCon (ur); 2D narrow corridor with nibs (ml); 6D rigid body in cage (mr); 6D Puma 560 in goal configuration (ll); 48D multi rigid body problem (lr) cell. In contrast, these cells will be chosen for sampling by strategies (i) and (iii). The experiments show also the dependency of the number of samples to take for strategy (ii) on the type of problem. If many different paths are possible, like in Problems (III) and (V), already a few samples are sufficient to open up new routes for the graph search. More samples will mainly burden the remaining solution process with a lot of unnecessary cells. As we are looking for a planner without problem dependent parameter settings, uniform sampling over the accumulated volume of occupied cells might only be the method of choice if an adaptive way of varying the number of samples thrown out is found. From the experiments it is not obvious that even an optimal number of samples results in an improvement of planning time. Therefore we will not investigate this sampling scheme further for the moment. As the local planner simply connects the centers of boundaries of adjacent cells by a straight line, the path obtained from PCD is piecewise linear. Before letting a real robot move according to the planned path it makes sense to add a smoothing step. Comparing the typical paths obtained by PCD and RRTConCon respectively in the upper row of figure

TABLE I EXPERIMENTAL RESULTS; EXECUTION TIME, NUMBER OF COLLISION CHECKS AND NUMBER OF CELLS FOR VARIOUS METHODS AND PROBLEMS (i) (ii) - 5 (ii) - 50 (ii) - 500 (iii) RRTCC Problem I: 2D maze t min 0.05 0.12 0.11 0.10 0.11 0.16 t max 2.05 1.05 0.92 0.60 0.63 8.10 t avg 0.33 0.30 0.25 0.25 0.24 1.35 var(t) 0.041 0.019 0.012 0.0064 0.0065 1.58 Checks 3581 2660 2725 2766 2659 6259 #κ free 150 128 139 138 128 Nodes: #κ occ 81 80 88 88 75 539 Problem II: 2D narrow corridor t min 0.10 0.44 0.02 0.01 0.04 351.66 t max 1.61 744.13 2.38 4.03 0.89 6011.63 t avg 0.33 49.21 0.80 0.94 0.28 2020.17 var(t) 0.036 7848.84 0.30 0.52 0.022 2.88e6 Checks 3533 18800 10506 12894 2531 136741 #κ free 131 1347 99 101 98 Nodes: #κ occ 70 1732 60 63 56 29093 Problem III: 6D rigid body / cage t min 0.02 0.03 0.27 0.05 0.04 0.17 t max 13.85 36.48 40.88 51.41 7.60 6.27 t avg 1.96 8.23 5.90 7.90 1.30 1.58 var(t) 6.24 93.59 40.81 84.84 2.40 1.38 Checks 4308 8050 8175 8343 3781 10698 #κ free 463 828 847 914 283 Nodes: #κ occ 516 1375 1390 1489 442 481 Problem IV: 6D chain-like robot / Puma 560 t min 0.17 1.58 0.29 1.00 0.29 2.04 t max 58.38 1184.67 290.00 156.57 24.12 90.77 t avg 8.39 175.41 45.83 30.76 4.24 20.29 var(t) 95.52 59743.47 3465.05 1448.26 18.00 350.34 Checks 6022 18937 16672 16223 4278 10261 #κ free 613 1245 1171 1182 328 Nodes: #κ occ 624 1624 1532 1530 447 1855 Problem V: 48D multi rigid body / bunnies t min 325.48 41.32 115.02 281.11 13.94 2861.54 t max 11461.50 5545.59 6168.08 5209.15 5919.85 75880.98 t avg 2731.24 1838.99 1952.18 2073.44 1319.23 39874.23 var(t) 7.07e6 2.06e6 2.73e6 1.74e6 1.67e6 7.77e8 Checks 29270 41231 41639 35685 18652 881234 #κ free 2349 1414 1474 1491 1595 Nodes: #κ occ 6120 6292 6508 6506 4272 69875 (2) it seems reasonable that less post processing is necessary for the PCD path. Comparable results have been obtained for the other problems, too. The RRTConCon solution shows the tendency of bouncing around and sliding along C-obstacles while the PCD path is smoother and tends to keep a safety margin. V. CONCLUSION AND FUTURE WORK In this paper a new path planning method for high dimensional configuration spaces has been presented. Lazy evaluation techniques and probabilistic sampling turned the classical cell decomposition into a highly competitive path planning method. It has been shown that PCD gives promising results for a wide variety of path planning problems. Already in this early stage of investigation PCD matches state-of-the-art implementations of other probabilistic path planning methods. So far, the performance of PCD decreases, if C free is just a very small fraction of C. A more theoretical analysis of the proposed algorithm is still to come. Here upper bounds as well as expected value estimates of the computation time needed are of special interest. Improvements are conceivable in many areas of the algorithm. The question of which cells to take for sampling was brought up in this paper but is definitely not solved. Furthermore it might be interesting where and how to sample in these cells. Another point of interest might be the search for a path through possibly free cells. Here the question arises if it is necessary to carry out a complete graph search every time or if there might be a clever way of keeping track of which cells have been split so that only local replanning is needed. ACKNOWLEDGMENT The author would like to thank Morten Strandberg for many fruitful discussions and providing the Puma 560 model. The Stanford Bunny came with the Proximity Query Package (PQP) from the University of North Carolina which was used for collision checks. This research has been sponsored by the Swedish Foundation for Strategic Research. The support is gratefully acknowledged. REFERENCES [1] G. Song and N. M. Amato, Using motion planning to study protein folding pathways, in Proceedings of the fifth annual international conference on Computational biology. ACM Press, 2001, pp. 287 296. [2] S. Sundaram, I. Remmler, and N. Amato, Disassembly sequencing using a motion planning approach, in Proc. IEEE Int. Conf. Robot. Autom. (ICRA), 2001. [3] D. Nieuwenhuisen and M. Overmars, Motion planning for camera movements in virtual environments, Utrecht University: Information and Computing Sciences, Utrecht, the Netherlands, Tech. Rep. UU-CS- 2003-004, 2002. [4] J.-C. Latombe, Robot Motion Planning. Kluwer Academic Publishers, 1991. [5] E. Mazer, J. M. Ahuactzin, and P. Bessiere, The Ariadne s Clew algorithm, Journal of Artificial Intelligence Research, vol. 9, pp. 295 316, 1998. [6] L. Kavraki, P. Svestka, J.-C. Latombe, and M. Overmars, Probabilistic roadmaps for path planning in high dimensional configuration spaces, IEEE Transactions on Robotics and Automation, vol. 12, no. 4, pp. 566 580, 1996. [7] N. Amato, O. Bayazit, L. Dale, C. Jones, and D. Vallejo, OBPRM: An obstacle-based PRM for 3D workspaces, in Proc. Int. Workshop on Algorithmic Foundations of Robotics (WAFR), 1998. [8] L. K. Dale and N. M. Amato, Probabilistic roadmaps - putting it all together, in Proceedings of the International Conference on Robotics and Automation (ICRA), 2001, pp. 1940 1947. [9] S. LaValle, Rapidly-exploring random trees: A new tool for path planning, Computer Science Dept., Iowa State University, Tech. Rep. 98-11, 1998. [10] R. Bohlin and L. Kavraki, Path planning using lazy PRM, in Proceedings of the International Conference on Robotics and Automation, vol. 1, 2000, pp. 521 528. [11] S. LaValle and J. Kuffner, Rapidly-exploring random trees: Progress and prospects, in Proc. Int. Workshop on Algorithmic Foundations of Robotics (WAFR), 2000. [12] M. Akinc, K. E. Bekris, B. Y. Chen, A. M. Ladd, E. Plakue, and L. E. Kavraki, Probabilistic roadmaps of trees for parallel computation of multiple query roadmaps, in Proceedings of International Symposium of Robotics Research (ISRR), 2003. [13] G. F. Luger and W. A. Stubblefield, Artificial Intelligence and the Design of Expert Systems. Benjamin/Cummings, 1989. [14] B. J. H. Verwer, A multiresolution work space, multiresolution configuration space approach to solve the path-planning problem, in Proc. IEEE Int. Conf. on Rob. & Aut., 1990, pp. 2107 2112. [15] R. Geraerts and M. Overmars, A comparative study of probabilistic roadmap planners, in Proceedings of the 5th International Workshop on Algorithmic Foundations of Robotics (WAFR), 2002.