Path Planning using Probabilistic Cell Decomposition

Size: px
Start display at page:

Download "Path Planning using Probabilistic Cell Decomposition"

Transcription

1 Path Planning using Probabilistic Cell Decomposition Frank Lingelbach Centre for Autonomous Systems Royal Institute of Technology SE Stockholm, Sweden 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

2 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

3 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

4 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

5 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

6 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) (iii) RRTCC Problem I: 2D maze t min t max t avg var(t) Checks #κ free Nodes: #κ occ Problem II: 2D narrow corridor t min t max t avg var(t) e6 Checks #κ free Nodes: #κ occ Problem III: 6D rigid body / cage t min t max t avg var(t) Checks #κ free Nodes: #κ occ Problem IV: 6D chain-like robot / Puma 560 t min t max t avg var(t) Checks #κ free Nodes: #κ occ Problem V: 48D multi rigid body / bunnies t min t max t avg var(t) 7.07e6 2.06e6 2.73e6 1.74e6 1.67e6 7.77e8 Checks #κ free Nodes: #κ occ (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 [2] S. Sundaram, I. Remmler, and N. Amato, Disassembly sequencing using a motion planning approach, in Proc. IEEE Int. Conf. Robot. Autom. (ICRA), [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 , [4] J.-C. Latombe, Robot Motion Planning. Kluwer Academic Publishers, [5] E. Mazer, J. M. Ahuactzin, and P. Bessiere, The Ariadne s Clew algorithm, Journal of Artificial Intelligence Research, vol. 9, pp , [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 , [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), [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 [9] S. LaValle, Rapidly-exploring random trees: A new tool for path planning, Computer Science Dept., Iowa State University, Tech. Rep , [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 [11] S. LaValle and J. Kuffner, Rapidly-exploring random trees: Progress and prospects, in Proc. Int. Workshop on Algorithmic Foundations of Robotics (WAFR), [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), [13] G. F. Luger and W. A. Stubblefield, Artificial Intelligence and the Design of Expert Systems. Benjamin/Cummings, [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 [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.

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

vizmo++: a Visualization, Authoring, and Educational Tool for Motion Planning vizmo++: a Visualization, Authoring, and Educational Tool for Motion Planning Aimée Vargas E. Jyh-Ming Lien Nancy M. Amato. aimee@cs.tamu.edu neilien@cs.tamu.edu amato@cs.tamu.edu Technical Report TR05-011

More information

Sampling-based Planning 2

Sampling-based Planning 2 RBE MOTION PLANNING Sampling-based Planning 2 Jane Li Assistant Professor Mechanical Engineering & Robotics Engineering http://users.wpi.edu/~zli11 Problem with KD-tree RBE MOTION PLANNING Curse of dimension

More information

CS 4649/7649 Robot Intelligence: Planning

CS 4649/7649 Robot Intelligence: Planning CS 4649/7649 Robot Intelligence: Planning Probabilistic Roadmaps Sungmoon Joo School of Interactive Computing College of Computing Georgia Institute of Technology S. Joo (sungmoon.joo@cc.gatech.edu) 1

More information

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

Sampling-Based Robot Motion Planning. Lydia Kavraki Department of Computer Science Rice University Houston, TX USA Sampling-Based Robot Motion Planning Lydia Kavraki Department of Computer Science Rice University Houston, TX USA Motion planning: classical setting Go from Start to Goal without collisions and while respecting

More information

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

Autonomous and Mobile Robotics Prof. Giuseppe Oriolo. Motion Planning 1 Retraction and Cell Decomposition Autonomous and Mobile Robotics Prof. Giuseppe Oriolo Motion Planning 1 Retraction and Cell Decomposition motivation robots are expected to perform tasks in workspaces populated by obstacles autonomy requires

More information

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

6.141: Robotics systems and science Lecture 9: Configuration Space and Motion Planning 6.141: Robotics systems and science Lecture 9: Configuration Space and Motion Planning Lecture Notes Prepared by Daniela Rus EECS/MIT Spring 2012 Figures by Nancy Amato, Rodney Brooks, Vijay Kumar Reading:

More information

Robot Motion Planning

Robot Motion Planning Robot Motion Planning slides by Jan Faigl Department of Computer Science and Engineering Faculty of Electrical Engineering, Czech Technical University in Prague lecture A4M36PAH - Planning and Games Dpt.

More information

Probabilistic roadmaps for efficient path planning

Probabilistic roadmaps for efficient path planning Probabilistic roadmaps for efficient path planning Dan A. Alcantara March 25, 2007 1 Introduction The problem of finding a collision-free path between points in space has applications across many different

More information

Path Planning using Probabilistic Cell Decomposition FRANK LINGELBACH

Path Planning using Probabilistic Cell Decomposition FRANK LINGELBACH Path Planning using Probabilistic Cell Decomposition FRANK LINGELBACH Licentiate Thesis Stockholm, Sweden 2005 TRITA-S3-REG-0501 ISSN 1404-2150 ISBN 91-7283-961-9 KTH Signaler Sensorer och System SE-100

More information

Path Planning among Movable Obstacles: a Probabilistically Complete Approach

Path Planning among Movable Obstacles: a Probabilistically Complete Approach Path Planning among Movable Obstacles: a Probabilistically Complete Approach Jur van den Berg 1, Mike Stilman 2, James Kuffner 3, Ming Lin 1, and Dinesh Manocha 1 1 Department of Computer Science, University

More information

Probabilistic Motion Planning: Algorithms and Applications

Probabilistic Motion Planning: Algorithms and Applications Probabilistic Motion Planning: Algorithms and Applications Jyh-Ming Lien Department of Computer Science George Mason University Motion Planning in continuous spaces (Basic) Motion Planning (in a nutshell):

More information

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

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 Recent Developments in Motion Planning Λ Mark H. Overmars Institute of Information and Computing Sciences, Utrecht University, P.O. Box 80.089, 3508 TB Utrecht, the Netherlands. Email: markov@cs.uu.nl.

More information

Exploiting collision information in probabilistic roadmap planning

Exploiting collision information in probabilistic roadmap planning Exploiting collision information in probabilistic roadmap planning Serene W. H. Wong and Michael Jenkin Department of Computer Science and Engineering York University, 4700 Keele Street Toronto, Ontario,

More information

II. RELATED WORK. A. Probabilistic roadmap path planner

II. RELATED WORK. A. Probabilistic roadmap path planner Gaussian PRM Samplers for Dynamic Configuration Spaces Yu-Te Lin and Shih-Chia Cheng Computer Science Department Stanford University Stanford, CA 94305, USA {yutelin, sccheng}@cs.stanford.edu SUID: 05371954,

More information

Mobile Robot Path Planning in Static Environments using Particle Swarm Optimization

Mobile Robot Path Planning in Static Environments using Particle Swarm Optimization Mobile Robot Path Planning in Static Environments using Particle Swarm Optimization M. Shahab Alam, M. Usman Rafique, and M. Umer Khan Abstract Motion planning is a key element of robotics since it empowers

More information

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

Collided Path Replanning in Dynamic Environments Using RRT and Cell Decomposition Algorithms Collided Path Replanning in Dynamic Environments Using RRT and Cell Decomposition Algorithms Ahmad Abbadi ( ) and Vaclav Prenosil Department of Information Technologies, Faculty of Informatics, Masaryk

More information

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

The Corridor Map Method: Real-Time High-Quality Path Planning 27 IEEE International Conference on Robotics and Automation Roma, Italy, 1-14 April 27 WeC11.3 The Corridor Map Method: Real-Time High-Quality Path Planning Roland Geraerts and Mark H. Overmars Abstract

More information

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

Workspace-Guided Rapidly-Exploring Random Tree Method for a Robot Arm WorkspaceGuided RapidlyExploring Random Tree Method for a Robot Arm Jaesik Choi choi31@cs.uiuc.edu August 12, 2007 Abstract Motion planning for robotic arms is important for real, physical world applications.

More information

Iteratively Locating Voronoi Vertices for Dispersion Estimation

Iteratively Locating Voronoi Vertices for Dispersion Estimation Iteratively Locating Voronoi Vertices for Dispersion Estimation Stephen R. Lindemann and Peng Cheng Department of Computer Science University of Illinois Urbana, IL 61801 USA {slindema, pcheng1}@uiuc.edu

More information

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

6.141: Robotics systems and science Lecture 9: Configuration Space and Motion Planning 6.141: Robotics systems and science Lecture 9: Configuration Space and Motion Planning Lecture Notes Prepared by Daniela Rus EECS/MIT Spring 2011 Figures by Nancy Amato, Rodney Brooks, Vijay Kumar Reading:

More information

Probabilistic Roadmap Planner with Adaptive Sampling Based on Clustering

Probabilistic Roadmap Planner with Adaptive Sampling Based on Clustering Proceedings of the 2nd International Conference of Control, Dynamic Systems, and Robotics Ottawa, Ontario, Canada, May 7-8 2015 Paper No. 173 Probabilistic Roadmap Planner with Adaptive Sampling Based

More information

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

Introduction to State-of-the-art Motion Planning Algorithms. Presented by Konstantinos Tsianos Introduction to State-of-the-art Motion Planning Algorithms Presented by Konstantinos Tsianos Robots need to move! Motion Robot motion must be continuous Geometric constraints Dynamic constraints Safety

More information

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

Variable-resolution Velocity Roadmap Generation Considering Safety Constraints for Mobile Robots Variable-resolution Velocity Roadmap Generation Considering Safety Constraints for Mobile Robots Jingyu Xiang, Yuichi Tazaki, Tatsuya Suzuki and B. Levedahl Abstract This research develops a new roadmap

More information

Learning to Guide Random Tree Planners in High Dimensional Spaces

Learning to Guide Random Tree Planners in High Dimensional Spaces Learning to Guide Random Tree Planners in High Dimensional Spaces Jörg Röwekämper Gian Diego Tipaldi Wolfram Burgard Fig. 1. Example paths for a mobile manipulation platform computed with RRT-Connect [13]

More information

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

CHAPTER SIX. the RRM creates small covering roadmaps for all tested environments. CHAPTER SIX CREATING SMALL ROADMAPS Many algorithms have been proposed that create a roadmap from which a path for a moving object can be extracted. These algorithms generally do not give guarantees on

More information

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

biasing the sampling based on the geometric characteristics of configurations known to be reachable from the assembled configuration (the start). In p Disassembly Sequencing Using a Motion Planning Approach Λ Sujay Sundaram Department of Mechanical Engineering Texas A&M University College Station, TX 77843 sps7711@cs.tamu.edu Ian Remmler Nancy M. Amato

More information

for Motion Planning RSS Lecture 10 Prof. Seth Teller

for Motion Planning RSS Lecture 10 Prof. Seth Teller Configuration Space for Motion Planning RSS Lecture 10 Monday, 8 March 2010 Prof. Seth Teller Siegwart & Nourbahksh S 6.2 (Thanks to Nancy Amato, Rod Brooks, Vijay Kumar, and Daniela Rus for some of the

More information

Probabilistic Roadmaps of Trees for Parallel Computation of Multiple Query Roadmaps

Probabilistic Roadmaps of Trees for Parallel Computation of Multiple Query Roadmaps Probabilistic Roadmaps of Trees for Parallel Computation of Multiple Query Roadmaps Mert Akinc, Kostas E. Bekris, Brian Y. Chen, Andrew M. Ladd, Erion Plaku, and Lydia E. Kavraki Rice University Department

More information

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

Efficient Motion Planning for Humanoid Robots using Lazy Collision Checking and Enlarged Robot Models Efficient Motion Planning for Humanoid Robots using Lazy Collision Checking and Enlarged Robot Models Nikolaus Vahrenkamp, Tamim Asfour and Rüdiger Dillmann Institute of Computer Science and Engineering

More information

Incrementally Reducing Dispersion by Increasing Voronoi Bias in RRTs

Incrementally Reducing Dispersion by Increasing Voronoi Bias in RRTs Incrementally Reducing Dispersion by Increasing Voronoi Bias in RRTs Stephen R. Lindemann Steven M. LaValle Dept. of Computer Science University of Illinois Urbana, IL 61801 USA {slindema, lavalle}@uiuc.edu

More information

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

ECE276B: Planning & Learning in Robotics Lecture 5: Configuration Space ECE276B: Planning & Learning in Robotics Lecture 5: Configuration Space Lecturer: Nikolay Atanasov: natanasov@ucsd.edu Teaching Assistants: Tianyu Wang: tiw161@eng.ucsd.edu Yongxi Lu: yol070@eng.ucsd.edu

More information

Configuration Space of a Robot

Configuration Space of a Robot Robot Path Planning Overview: 1. Visibility Graphs 2. Voronoi Graphs 3. Potential Fields 4. Sampling-Based Planners PRM: Probabilistic Roadmap Methods RRTs: Rapidly-exploring Random Trees Configuration

More information

Providing Haptic Hints to Automatic Motion Planners

Providing Haptic Hints to Automatic Motion Planners Providing Haptic Hints to Automatic Motion Planners O. Burchan Bayazit Guang Song Nancy M. Amato fburchanb,gsong,amatog@cs.tamu.edu Department of Computer Science, Texas A&M University College Station,

More information

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

Motion Planning with Dynamics, Physics based Simulations, and Linear Temporal Objectives. Erion Plaku Motion Planning with Dynamics, Physics based Simulations, and Linear Temporal Objectives Erion Plaku Laboratory for Computational Sensing and Robotics Johns Hopkins University Frontiers of Planning The

More information

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

COMPLETE AND SCALABLE MULTI-ROBOT PLANNING IN TUNNEL ENVIRONMENTS. Mike Peasgood John McPhee Christopher Clark COMPLETE AND SCALABLE MULTI-ROBOT PLANNING IN TUNNEL ENVIRONMENTS Mike Peasgood John McPhee Christopher Clark Lab for Intelligent and Autonomous Robotics, Department of Mechanical Engineering, University

More information

Balancing Exploration and Exploitation in Motion Planning

Balancing Exploration and Exploitation in Motion Planning 2008 IEEE International Conference on Robotics and Automation Pasadena, CA, USA, May 19-23, 2008 Balancing Exploration and Exploitation in Motion Planning Markus Rickert Oliver Brock Alois Knoll Robotics

More information

Mobile Robots Path Planning using Genetic Algorithms

Mobile Robots Path Planning using Genetic Algorithms Mobile Robots Path Planning using Genetic Algorithms Nouara Achour LRPE Laboratory, Department of Automation University of USTHB Algiers, Algeria nachour@usthb.dz Mohamed Chaalal LRPE Laboratory, Department

More information

Probabilistic Methods for Kinodynamic Path Planning

Probabilistic Methods for Kinodynamic Path Planning 16.412/6.834J Cognitive Robotics February 7 th, 2005 Probabilistic Methods for Kinodynamic Path Planning Based on Past Student Lectures by: Paul Elliott, Aisha Walcott, Nathan Ickes and Stanislav Funiak

More information

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

Algorithms for Sensor-Based Robotics: Sampling-Based Motion Planning Algorithms for Sensor-Based Robotics: Sampling-Based Motion Planning Computer Science 336 http://www.cs.jhu.edu/~hager/teaching/cs336 Professor Hager http://www.cs.jhu.edu/~hager Recall Earlier Methods

More information

1 Proximity via Graph Spanners

1 Proximity via Graph Spanners CS273: Algorithms for Structure Handout # 11 and Motion in Biology Stanford University Tuesday, 4 May 2003 Lecture #11: 4 May 2004 Topics: Proximity via Graph Spanners Geometric Models of Molecules, I

More information

Advanced Robotics Path Planning & Navigation

Advanced Robotics Path Planning & Navigation Advanced Robotics Path Planning & Navigation 1 Agenda Motivation Basic Definitions Configuration Space Global Planning Local Planning Obstacle Avoidance ROS Navigation Stack 2 Literature Choset, Lynch,

More information

Nonholonomic motion planning for car-like robots

Nonholonomic motion planning for car-like robots Nonholonomic motion planning for car-like robots A. Sánchez L. 2, J. Abraham Arenas B. 1, and René Zapata. 2 1 Computer Science Dept., BUAP Puebla, Pue., México {aarenas}@cs.buap.mx 2 LIRMM, UMR5506 CNRS,

More information

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

Path Planning for a Robot Manipulator based on Probabilistic Roadmap and Reinforcement Learning 674 International Journal Jung-Jun of Control, Park, Automation, Ji-Hun Kim, and and Systems, Jae-Bok vol. Song 5, no. 6, pp. 674-680, December 2007 Path Planning for a Robot Manipulator based on Probabilistic

More information

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

RRT-Connect: An Efficient Approach to Single-Query Path Planning In Proc. 2000 IEEE Int l Conf. on Robotics and Automation (ICRA 2000) RRT-Connect: An Efficient Approach to Single-Query Path Planning James J. Kuffner, Jr. Computer Science Dept. Stanford University Stanford,

More information

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

Algorithms for Sensor-Based Robotics: Sampling-Based Motion Planning Algorithms for Sensor-Based Robotics: Sampling-Based Motion Planning Computer Science 336 http://www.cs.jhu.edu/~hager/teaching/cs336 Professor Hager http://www.cs.jhu.edu/~hager Recall Earlier Methods

More information

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

T S. Configuration Space S1 LP S0 ITM. S3 Start cfg An Adaptive Framework for `Single Shot' Motion Planning Λ Daniel R. Vallejo Christopher Jones Nancy M. Amato Texas A&M University Sandia National Laboratories Texas A&M University dvallejo@cs.tamu.edu

More information

A Hybrid Approach for Complete Motion Planning

A Hybrid Approach for Complete Motion Planning A Hybrid Approach for Complete Motion Planning Liangjun Zhang 1 Young J. Kim 2 Dinesh Manocha 1 1 Dept. of Computer Science, University of North Carolina at Chapel Hill, USA, {zlj,dm}@cs.unc.edu 2 Dept.

More information

SPATIAL GUIDANCE TO RRT PLANNER USING CELL-DECOMPOSITION ALGORITHM

SPATIAL GUIDANCE TO RRT PLANNER USING CELL-DECOMPOSITION ALGORITHM SPATIAL GUIDANCE TO RRT PLANNER USING CELL-DECOMPOSITION ALGORITHM Ahmad Abbadi, Radomil Matousek, Pavel Osmera, Lukas Knispel Brno University of Technology Institute of Automation and Computer Science

More information

Geometric Path Planning for General Robot Manipulators

Geometric Path Planning for General Robot Manipulators Proceedings of the World Congress on Engineering and Computer Science 29 Vol II WCECS 29, October 2-22, 29, San Francisco, USA Geometric Path Planning for General Robot Manipulators Ziyad Aljarboua Abstract

More information

An Eternal Domination Problem in Grids

An Eternal Domination Problem in Grids Theory and Applications of Graphs Volume Issue 1 Article 2 2017 An Eternal Domination Problem in Grids William Klostermeyer University of North Florida, klostermeyer@hotmail.com Margaret-Ellen Messinger

More information

Useful Cycles in Probabilistic Roadmap Graphs

Useful Cycles in Probabilistic Roadmap Graphs Useful Cycles in Probabilistic Roadmap Graphs Dennis Nieuwenhuisen Mark H. Overmars institute of information and computing sciences, utrecht university technical report UU-CS-24-64 www.cs.uu.nl Useful

More information

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

Path Planning. Jacky Baltes Dept. of Computer Science University of Manitoba   11/21/10 Path Planning Jacky Baltes Autonomous Agents Lab Department of Computer Science University of Manitoba Email: jacky@cs.umanitoba.ca http://www.cs.umanitoba.ca/~jacky Path Planning Jacky Baltes Dept. of

More information

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

Motion Planning 2D. Corso di Robotica Prof. Davide Brugali Università degli Studi di Bergamo Motion Planning 2D Corso di Robotica Prof. Davide Brugali Università degli Studi di Bergamo Tratto dai corsi: CS 326A: Motion Planning ai.stanford.edu/~latombe/cs326/2007/index.htm Prof. J.C. Latombe Stanford

More information

UOBPRM: A Uniformly Distributed Obstacle-Based PRM

UOBPRM: A Uniformly Distributed Obstacle-Based PRM UOBPRM: A Uniformly Distributed Obstacle-Based PRM Hsin-Yi (Cindy) Yeh 1, Shawna Thomas 1, David Eppstein 2 and Nancy M. Amato 1 Abstract This paper presents a new sampling method for motion planning that

More information

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

D-Plan: Efficient Collision-Free Path Computation for Part Removal and Disassembly 774 Computer-Aided Design and Applications 2008 CAD Solutions, LLC http://www.cadanda.com D-Plan: Efficient Collision-Free Path Computation for Part Removal and Disassembly Liangjun Zhang 1, Xin Huang

More information

crrt : Planning loosely-coupled motions for multiple mobile robots

crrt : Planning loosely-coupled motions for multiple mobile robots crrt : Planning loosely-coupled motions for multiple mobile robots Jan Rosell and Raúl Suárez Institute of Industrial and Control Engineering (IOC) Universitat Politècnica de Catalunya (UPC) Barcelona

More information

Incremental Map Generation (IMG)

Incremental Map Generation (IMG) Incremental Map Generation (IMG) Dawen Xie, Marco Morales, Roger Pearce, Shawna Thomas, Jyh-Ming Lien, and Nancy M. Amato Parasol Lab, Department of Computer Science, Texas A&M University, College Station,

More information

Geometric Path Planning McGill COMP 765 Oct 12 th, 2017

Geometric Path Planning McGill COMP 765 Oct 12 th, 2017 Geometric Path Planning McGill COMP 765 Oct 12 th, 2017 The Motion Planning Problem Intuition: Find a safe path/trajectory from start to goal More precisely: A path is a series of robot configurations

More information

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

Dynamic-Domain RRTs: Efficient Exploration by Controlling the Sampling Domain Dynamic-Domain RRTs: Efficient Exploration by Controlling the Sampling Domain Anna Yershova Léonard Jaillet Department of Computer Science University of Illinois Urbana, IL 61801 USA {yershova, lavalle}@uiuc.edu

More information

Specialized PRM Trajectory Planning For Hyper-Redundant Robot Manipulators

Specialized PRM Trajectory Planning For Hyper-Redundant Robot Manipulators Specialized PRM Trajectory Planning For Hyper-Redundant Robot Manipulators MAHDI F. GHAJARI and RENE V. MAYORGA Department of Industrial Systems Engineering University of Regina 3737 Wascana Parkway, Regina,

More information

Adaptive Tuning of the Sampling Domain for Dynamic-Domain RRTs

Adaptive Tuning of the Sampling Domain for Dynamic-Domain RRTs Adaptive Tuning of the Sampling Domain for Dynamic-Domain RRTs Léonard Jaillet Anna Yershova LAAS-CNRS 7, Avenue du Colonel Roche 31077 Toulouse Cedex 04,France {ljaillet, nic}@laas.fr Steven M. LaValle

More information

RESAMPL: A Region-Sensitive Adaptive Motion Planner

RESAMPL: A Region-Sensitive Adaptive Motion Planner REAMPL: A Region-ensitive Adaptive Motion Planner amuel Rodriguez, hawna Thomas, Roger Pearce, and Nancy M. Amato Parasol Lab, Department of Computer cience, Texas A&M University, College tation, TX UA

More information

Robot Motion Planning

Robot Motion Planning Robot Motion Planning James Bruce Computer Science Department Carnegie Mellon University April 7, 2004 Agent Planning An agent is a situated entity which can choose and execute actions within in an environment.

More information

Customizing PRM Roadmaps at Query Time Λ

Customizing PRM Roadmaps at Query Time Λ Customizing PRM Roadmaps at Query Time Λ Guang Song Shawna Miller Nancy M. Amato Department of Computer Science Texas A&M University College Station, TX 77843-3112 fgsong,slm5563,amatog@cs.tamu.edu Abstract

More information

Steps Toward Derandomizing RRTs

Steps Toward Derandomizing RRTs Steps Toward Derandomizing RRTs Stephen R. Lindemann Steven M. LaValle Dept. of Computer Science University of Illinois Urbana, IL 61801 USA {slindema, lavalle}@uiuc.edu Abstract We present two motion

More information

Stable Trajectory Design for Highly Constrained Environments using Receding Horizon Control

Stable Trajectory Design for Highly Constrained Environments using Receding Horizon Control Stable Trajectory Design for Highly Constrained Environments using Receding Horizon Control Yoshiaki Kuwata and Jonathan P. How Space Systems Laboratory Massachusetts Institute of Technology {kuwata,jhow}@mit.edu

More information

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

G 6i try. On the Number of Minimal 1-Steiner Trees* Discrete Comput Geom 12:29-34 (1994) Discrete Comput Geom 12:29-34 (1994) G 6i try 9 1994 Springer-Verlag New York Inc. On the Number of Minimal 1-Steiner Trees* B. Aronov, 1 M. Bern, 2 and D. Eppstein 3 Computer Science Department, Polytechnic

More information

CS Path Planning

CS Path Planning Why Path Planning? CS 603 - Path Planning Roderic A. Grupen 4/13/15 Robotics 1 4/13/15 Robotics 2 Why Motion Planning? Origins of Motion Planning Virtual Prototyping! Character Animation! Structural Molecular

More information

Visibility: Finding the Staircase Kernel in Orthogonal Polygons

Visibility: Finding the Staircase Kernel in Orthogonal Polygons Visibility: Finding the Staircase Kernel in Orthogonal Polygons 8 Visibility: Finding the Staircase Kernel in Orthogonal Polygons Tzvetalin S. Vassilev, Nipissing University, Canada Stefan Pape, Nipissing

More information

Configuration Space. Ioannis Rekleitis

Configuration Space. Ioannis Rekleitis Configuration Space Ioannis Rekleitis Configuration Space Configuration Space Definition A robot configuration is a specification of the positions of all robot points relative to a fixed coordinate system

More information

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

A Slicing Connection Strategy for Constructing PRMs in High-Dimensional Cspaces A Slicing Connection Strategy for Constructing PRMs in High-Dimensional Cspaces Abstract - This paper presents a connection strategy for PRM-based motion planning in high-dimensional configuration spaces.

More information

Connected Components of Underlying Graphs of Halving Lines

Connected Components of Underlying Graphs of Halving Lines arxiv:1304.5658v1 [math.co] 20 Apr 2013 Connected Components of Underlying Graphs of Halving Lines Tanya Khovanova MIT November 5, 2018 Abstract Dai Yang MIT In this paper we discuss the connected components

More information

Spring 2010: Lecture 9. Ashutosh Saxena. Ashutosh Saxena

Spring 2010: Lecture 9. Ashutosh Saxena. Ashutosh Saxena CS 4758/6758: Robot Learning Spring 2010: Lecture 9 Why planning and control? Video Typical Architecture Planning 0.1 Hz Control 50 Hz Does it apply to all robots and all scenarios? Previous Lecture: Potential

More information

Incremental Map Generation (IMG)

Incremental Map Generation (IMG) Incremental Map Generation (IMG) Dawen Xie, Marco A. Morales A., Roger Pearce, Shawna Thomas, Jyh-Ming Lien, Nancy M. Amato {dawenx,marcom,rap2317,sthomas,neilien,amato}@cs.tamu.edu Technical Report TR06-005

More information

Optimizing Schedules for Prioritized Path Planning of Multi-Robot Systems

Optimizing Schedules for Prioritized Path Planning of Multi-Robot Systems Proceedings of the 20 IEEE International Conference on Robotics & Automation Seoul, Korea May 21-26, 20 Optimizing Schedules for Prioritized Path Planning of Multi-Robot Systems Maren Bennewitz y Wolfram

More information

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

f-v v-f f-e e-f f-f e-e-cross e-v v-e degenerate PCs e-e-touch v-v Planning Motion Compliant to Complex Contact States Λ uerong Ji, Jing iao Computer Science Department University of North Carolina - Charlotte Charlotte, NC 28223, US xji@uncc.edu, xiao@uncc.edu bstract

More information

A Hybrid Approach for Complete Motion Planning

A Hybrid Approach for Complete Motion Planning A Hybrid Approach for Complete Motion Planning Liangjun Zhang 1 Young J. Kim 2 Dinesh Manocha 1 1 Dept. of Computer Science, University of North Carolina at Chapel Hill, USA, {zlj,dm}@cs.unc.edu 2 Dept.

More information

Part I Part 1 Sampling-based Motion Planning

Part I Part 1 Sampling-based Motion Planning Overview of the Lecture Randomized Sampling-based Motion Planning Methods Jan Faigl Department of Computer Science Faculty of Electrical Engineering Czech Technical University in Prague Lecture 05 B4M36UIR

More information

Path Planning in Repetitive Environments

Path Planning in Repetitive Environments MMAR 2006 12th IEEE International Conference on Methods and Models in Automation and Robotics 28-31 August 2006 Międzyzdroje, Poland Path Planning in Repetitive Environments Jur van den Berg Mark Overmars

More information

Introduction to Robotics

Introduction to Robotics Jianwei Zhang zhang@informatik.uni-hamburg.de Universität Hamburg Fakultät für Mathematik, Informatik und Naturwissenschaften Technische Aspekte Multimodaler Systeme 05. July 2013 J. Zhang 1 Task-level

More information

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

Star-shaped Roadmaps - A Deterministic Sampling Approach for Complete Motion Planning Star-shaped Roadmaps - A Deterministic Sampling Approach for Complete Motion Planning Gokul Varadhan Dinesh Manocha University of North Carolina at Chapel Hill http://gamma.cs.unc.edu/motion/ Email: {varadhan,dm}@cs.unc.edu

More information

Part I Part 1 Sampling-based Motion Planning

Part I Part 1 Sampling-based Motion Planning Overview of the Lecture Randomized Sampling-based Motion Planning Methods Jan Faigl Department of Computer Science Faculty of Electrical Engineering Czech Technical University in Prague Lecture 06 B4M36UIR

More information

1 The range query problem

1 The range query problem CS268: Geometric Algorithms Handout #12 Design and Analysis Original Handout #12 Stanford University Thursday, 19 May 1994 Original Lecture #12: Thursday, May 19, 1994 Topics: Range Searching with Partition

More information

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

OOPS for Motion Planning: An Online, Open-source, Programming System IEEE Inter Conf on Robotics and Automation (ICRA), Rome, Italy, 2007, pp. 3711 3716 OOPS for Motion Planning: An Online, Open-source, Programming System Erion Plaku Kostas E. Bekris Lydia E. Kavraki Abstract

More information

Workspace Skeleton Tools for Motion Planning

Workspace Skeleton Tools for Motion Planning Workspace Skeleton Tools for Motion Planning Kiffany Lyons, Diego Ruvalcaba, Mukulika Ghosh, Shawna Thomas, and Nancy Amato Abstract Motion planning is the ability to find a valid path from a start to

More information

(Refer Slide Time: 00:02:00)

(Refer Slide Time: 00:02:00) Computer Graphics Prof. Sukhendu Das Dept. of Computer Science and Engineering Indian Institute of Technology, Madras Lecture - 18 Polyfill - Scan Conversion of a Polygon Today we will discuss the concepts

More information

Planning with Reachable Distances: Fast Enforcement of Closure Constraints

Planning with Reachable Distances: Fast Enforcement of Closure Constraints Planning with Reachable Distances: Fast Enforcement of Closure Constraints Xinyu Tang Shawna Thomas Nancy M. Amato xinyut@cs.tamu.edu sthomas@cs.tamu.edu amato@cs.tamu.edu Technical Report TR6-8 Parasol

More information

PRM path planning optimization algorithm research

PRM path planning optimization algorithm research PRM path planning optimization algorithm research School of Information Science & Engineering Hunan International Economics University Changsha, China, postcode:41005 matlab_bysj@16.com http:// www.hunaneu.com

More information

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

Last update: May 6, Robotics. CMSC 421: Chapter 25. CMSC 421: Chapter 25 1 Last update: May 6, 2010 Robotics CMSC 421: Chapter 25 CMSC 421: Chapter 25 1 A machine to perform tasks What is a robot? Some level of autonomy and flexibility, in some type of environment Sensory-motor

More information

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

6.141: Robotics systems and science Lecture 10: Implementing Motion Planning 6.141: Robotics systems and science Lecture 10: Implementing Motion Planning Lecture Notes Prepared by N. Roy and D. Rus EECS/MIT Spring 2011 Reading: Chapter 3, and Craig: Robotics http://courses.csail.mit.edu/6.141/!

More information

Kinodynamic Motion Planning on Roadmaps in Dynamic Environments

Kinodynamic Motion Planning on Roadmaps in Dynamic Environments Proceedings of the 2007 IEEE/RSJ International Conference on Intelligent Robots and Systems San Diego, CA, USA, Oct 29 - Nov 2, 2007 ThD11.1 Kinodynamic Motion Planning on Roadmaps in Dynamic Environments

More information

Lecture 3: Art Gallery Problems and Polygon Triangulation

Lecture 3: Art Gallery Problems and Polygon Triangulation EECS 396/496: Computational Geometry Fall 2017 Lecture 3: Art Gallery Problems and Polygon Triangulation Lecturer: Huck Bennett In this lecture, we study the problem of guarding an art gallery (specified

More information

Sampling Techniques for Probabilistic Roadmap Planners

Sampling Techniques for Probabilistic Roadmap Planners Sampling Techniques for Probabilistic Roadmap Planners Roland Geraerts Mark H. Overmars Institute of Information and Computing Sciences Utrecht University, the Netherlands Email: {roland,markov}@cs.uu.nl.

More information

This chapter explains two techniques which are frequently used throughout

This chapter explains two techniques which are frequently used throughout Chapter 2 Basic Techniques This chapter explains two techniques which are frequently used throughout this thesis. First, we will introduce the concept of particle filters. A particle filter is a recursive

More information

Clearance Based Path Optimization for Motion Planning

Clearance Based Path Optimization for Motion Planning Clearance Based Path Optimization for Motion Planning Roland Geraerts Mark Overmars institute of information and computing sciences, utrecht university technical report UU-CS-2003-039 www.cs.uu.nl Clearance

More information

Geometric Computations for Simulation

Geometric Computations for Simulation 1 Geometric Computations for Simulation David E. Johnson I. INTRODUCTION A static virtual world would be boring and unlikely to draw in a user enough to create a sense of immersion. Simulation allows things

More information

Algorithms for Grid Graphs in the MapReduce Model

Algorithms for Grid Graphs in the MapReduce Model University of Nebraska - Lincoln DigitalCommons@University of Nebraska - Lincoln Computer Science and Engineering: Theses, Dissertations, and Student Research Computer Science and Engineering, Department

More information

Robot Motion Planning in Eight Directions

Robot Motion Planning in Eight Directions Robot Motion Planning in Eight Directions Miloš Šeda and Tomáš Březina Abstract In this paper, we investigate the problem of 8-directional robot motion planning where the goal is to find a collision-free

More information

Planning in Mobile Robotics

Planning in Mobile Robotics Planning in Mobile Robotics Part I. Miroslav Kulich Intelligent and Mobile Robotics Group Gerstner Laboratory for Intelligent Decision Making and Control Czech Technical University in Prague Tuesday 26/07/2011

More information

Motion Planning. Howie CHoset

Motion Planning. Howie CHoset Motion Planning Howie CHoset Questions Where are we? Where do we go? Which is more important? Encoders Encoders Incremental Photodetector Encoder disk LED Photoemitter Encoders - Incremental Encoders -

More information