Int. Conf. on Intelligent Autonomous Systems July 2527, Venezia (IT). pp Planning Safe Paths for Nonholonomic Car-Like Robots Navigating

Size: px
Start display at page:

Download "Int. Conf. on Intelligent Autonomous Systems July 2527, Venezia (IT). pp Planning Safe Paths for Nonholonomic Car-Like Robots Navigating"

Transcription

1 Int. Conf. on Intelligent Autonomous Systems July 2527, Venezia (IT). pp Planning Safe Paths for Nonholonomic Car-Like Robots Navigating Through Computed Landmarks Th. Fraichard and A. Lambert Inria a Rh ne-alpes & Gravir b 655 av. de l'europe, Montbonnot, France July 2000 Abstract This paper addresses path planning with uncertainty for a car-like robot subject to conguration uncertainty. The robot estimates its conguration with odometry and an absolute localization device based on environmental feature matching. The issue is to compute safe paths that guarantee that the goal will be reached in spite of the uncertainty. The solution proposed relies upon the automatic construction of a set of landmarks characterized by (1) a region of the conguration space, (2) the `best' features for localization in this region, and (3) a perception uncertainty eld that measures how well a feature is perceived at each conguration in the region. The landmarks are used within an ecient roadmap-based path planning algorithm that returns a safe motion plan that alternates motion along safe paths and localization operations. Keywords mobile-robot, nonholonomic-system, path-planning, uncertainty, landmark. Acknowledgements This work was partially supported by the French programme La Route Automatis e: < a Institut National de Recherche en Informatique et en Automatique. b Lab. Graphisme, Vision et Robotique.

2

3 Planning Safe Paths for Nonholonomic Car-Like Robots Navigating Through Computed Landmarks Th. Fraichard and A. Lambert Inria Rh ne-alpes & Gravir y 655 av. de l'europe Montbonnot, France 1 Introduction Abstract This paper addresses path planning with uncertainty for a car-like robot subject to conguration uncertainty. The robot estimates its conguration with odometry and an absolute localization device based on environmental feature matching. The issue is to compute safe paths that guarantee that the goal will be reached in spite of the uncertainty. The solution proposed relies upon the automatic construction of a set of landmarks characterized by (1) a region of the conguration space, (2) the `best' features for localization in this region, and (3) a perception uncertainty eld that measures how well a feature is perceived at each conguration in the region. The landmarks are used within an ecient roadmap-based path planning algorithm that returns a safe motion plan that alternates motion along safe paths and localization operations. Navigating a mobile robot usually implies (a) planning a path, i.e. a continuous sequence of congurations, that takes the robot to its goal, and then (b) following this path. Path planning is thus a fundamental issue in Robotics and, as such, it has received a large attention in the past twenty years (cf. [11]). The primary concern of path planning is to compute collision-free paths and the underlying assumption of most path planners is that the robot should be able to follow the planned paths accurately enough. A challenging problem is that this assumption hardly holds for a mobile robot operating in the real world. To begin with, mobile robots usually rely on odometric techniques to estimate their conguration. As these techniques yield increasing and unbounded conguration uncertainty, failure to follow a planned path is bound to occur. To overcome this problem, mobile robots are often equipped with absolute localization devices. These devices usually rely on sensors identifying environmental features that are then matched against a priori models of the environment in order to estimate the robot's conguration 1 (cf. [1]). Combining the estimates provided by both odometric and feature matching techniques permits to reduce conguration uncertainty. However if a planned path does not allow the detection of the appropriate environmental features, the mobile robot may once again fail to reach its goal. A solution to these two problems (drift, feature detection), both related to the various sources of uncertainty aecting the robot, is to design a path planner that explicitly takes into account uncertainty so as to compute safe paths, i.e. paths that guarantee that the goal will be reached in spite of these uncertainties. Path planning with uncertainty for mobile robots has motivated a number of research works (cf. [8] and [11, chapter 10] for reviews on this topic). In most cases however, simplifying assumptions are made (point robots performing straight motions, perfect sensing, perfect control, etc. e.g. [2, 5, 13, 18]) that restrict their applicability to real robots. For instance, nonholonomy, which is a key issue in path planning for wheeled mobile robots (cf. [12]), has seldom been considered before in path planning with uncertainty. It is the purpose of this paper to address these challenging issues in a realistic context. The case of a nonholonomic car-like robot moving in a stationary workspace and subject to con- guration uncertainty is considered here. Odometry is the primary tool used to estimate the robot's conguration. The robot is also equipped with an absolute localization device based on feature matching. It is assumed that feature matching localization is costly and that its use should be minimized. Inst. Nat. de Recherche en Informatique et en Automatique. y Lab. Graphisme, Vision et Robotique. 1 Henceforth feature matching localization will denote the whole procedure: identication, matching, etc. 1

4 The solution proposed in this paper relies upon: (a) simulations of the robot's odometry and localization procedure in order to estimate in a conservative way how the conguration uncertainty evolves when the robot moves or localizes itself, and (b) a novel type of landmarks, i.e. environmental features (natural or articial) that the robot can perceive and use to localize itself. Landmarks have already been used in path planning with uncertainty. In most cases however, they tended to be binary (their associated features are visible or they are not) and to yield a constant localization uncertainty, e.g. [2, 6, 13]. This is far from being satisfactory because, if feature matching localization clearly requires the environmental features to be visible, it is also clear that the localization uncertainty is sensitive to the position of the environmental features with respect to the robot's sensors (e.g. the closer the feature, the better the localization). The landmarks introduced herein are characterized by: (1) a region of the conguration space, (2) a set of `best' features for localization in the region, and (3) a perception uncertainty eld that measures how well a given feature is perceived at each conguration in the region. They are actually derived from the local map concept developed by the second author. A local map associates to a conguration the set of environmental features that are most appropriate for localization. Local map validity regions are connected subsets of the conguration space with similar local maps [9]. Local maps were originally introduced to drive the feature matching procedure during navigation: by reducing the number of features to be matched and by selecting the best features, local maps simplify and improve localization. Ref. [18] introduced the concept of sensory uncertainty eld, that associates to each conguration of a robot its localization uncertainty, to address path planning with uncertainty. This concept is interesting. However, the conguration uncertainty of the robot is not taken into account when the eld is computed. The perception uncertainty eld is derived from this concept. It associates to each conguration of a landmark region the perception uncertainty of the dierent environmental features of the landmark. This eld is used, at a later stage, along with the current conguration uncertainty of the robot, to compute a conservative localization uncertainty which is better suited for safe path planning purposes. To begin with, the paper presents how the landmarks can be built automatically from a model of the localization sensor and a description of the environment, and then, how they can be used within an ecient safe path planning algorithm similar to the one developed by the rst author in [6]. The algorithm relies upon a roadmap, i.e. a graph in the conguration space whose edges are collisionfree paths that respects the nonholonomic constraints of a car-like vehicle. It searches the roadmap for the shortest path to the goal. Safeness along each edge-path is checked thanks to an odometry simulation. Whenever a node included in a landmark region is reached, feature matching localization takes place and conguration uncertainty is reduced accordingly. The algorithm returns a motion plan that alternates motions along safe paths and localization operations. Outline of the paper. First, the problem at hand is stated in 2 and the solution algorithm is outlined in 3. Details about odometry and feature matching localization are given in 4 while the method to build the landmarks is described in 5. Finally the planning scheme is presented ( 6) along with experimental results ( 7). 2 Problem Statement 2.1 Model of the Robot The robot considered is a car-like robot denoted by A. It moves on the IR 2 plane and its conguration is dened as q = (x; y; ) 2 IR 2 S 1 where (x; y) are the coordinates of the rear axle midpoint, and the orientation of A. It is subject to two nonholonomic kinematic constraints [12]: (1) it can only move forward and backward in a direction tangent to its main axis, and (2) its turning radius is lower bounded. Let C be the conguration space of A, a path for A is a continuous sequence of congurations, i.e. a continuous mapping : [0; 1]?! C. A path is feasible if it respects the nonholonomic constraints above. 2.2 Model of the Workspace Let W IR 2 denote the workspace of A. It is cluttered up with a set of stationary obstacles B = fb i ; i = 1 : : : bg dened as forbidden regions of W. A set of stationary features F = ff j ; j = 1 : : : fg is also dened. A feature is an element of the environment that can be detected by the localization sensor of A. A feature may be part of an obstacle. A typical indoor environment is depicted in Fig. 1. The obstacles are modeled as polygons. The bold lines represent features, i.e. part of the obstacles 2

5 that can be detected while the thin lines represent the part of the obstacles that cannot or are dicult to detect (windows, etc.). 2.3 Conguration Uncertainty The knowledge that A has of its current conguration is always uncertain, i.e. with a limited accuracy. A probabilistic representation was chosen to model the uncertainty [16]. Accordingly an uncertain conguration is represented by its estimate ^q and its covariance matrix C. For collision checking purposes, it is necessary to know (^q; C), i.e. the set of congurations that are potentially occupied by A with a given condence threshold. This set is dened by the equiprobable contour of the probability distribution represented by (^q; C), it is a conguration space ellipsoid: (q? ^q) T C?1 (q? ^q) 2 (1) where is the condence threshold. For eciency reasons, it was further decided to decouple the position and orientation uncertainties and to approximate (^q; C) by an elliptical cylinder dened by the xy-projection of the ellipsoid (1), and by its -projection [9]. Accordingly an uncertain conguration (^q; C) is safe i: 8i 2 f1; : : : ; bg; 8q p 2 (^q; C); A(q p ) \ B i = ; where A(q) is the region of W occupied by A when in the conguration q. 2.4 Uncertainty Evolution, Safe Path The conguration uncertainty of A changes over time: it increases when A moves around (odometry) and it decreases when feature matching localization takes place. Hence the denition of the two following functions: The rst one, Od, models the evolution of the conguration uncertainty when A moves along a given path : Od(; C; s) returns C O, i.e. the conguration uncertainty at position (s) along the path assuming that A starts at conguration (0) with uncertainty C. The second one, Lo, computes the localization uncertainty, i.e. the conguration uncertainty resulting from feature matching localization. Lo takes as input the current uncertain conguration and the set of environmental features, it returns a covariance matrix: Lo(^q; C; F) = C L. Using Od, it is possible to dene a safe path as a path such that: 2.5 Safe Path Planning 8s 2 [0; 1]; ((s); Od(; C; s)) is safe. Safe path planning can now be stated as follows: let (^q s ; C s ) and (^q g ; C g ) be two uncertain congurations. ^q s is the start conguration and C s the corresponding uncertainty, whereas ^q g is the goal con- guration and C g the maximum nal uncertainty allowed. The sequence f 1 ; Lo; 2 ; Lo; : : : ; Lo; n g constitutes a safe path from (^q s ; C s ) to (^q g ; C g ) i (the Lo indicate when feature matching localization occurs): 1 starts at ^q s with uncertainty C s. n ends at ^q g with a nal uncertainty C n such that: (^q g ; C n ) (^q g ; C g ) 8i 2 f1; : : : ; ng; i is feasible and safe. 3 The Approach The solution scheme proposed relies upon a roadmap, i.e. a graph in the conguration space whose edges are feasible and collision-free paths for the robot A. The origin of the roadmap is not relevant. It may be automatically generated or manually built, but it must capture the connectivity of the collision-free conguration space. The Probabilistic Path Planner [17] is a general planning scheme that constitutes an automatic and ecient way to build roadmaps. In a previous work, the rst author has shown how to use the Probabilistic Path Planner in order to compute roadmaps that satisfy the requirements above in the case of a car-like robot [7]. 3

6 Given such a roadmap and assuming that the start and goal congurations are roadmap nodes 2, safe path planning can be turned into graph search. The graph is explored until the goal node is reached. In the course of the exploration, two important tasks are carried out: When an edge path is visited: the algorithm checks whether the path is safe (it cannot be checked a priori since it depends on the robot conguration uncertainty at the beginning of the path). When a node is visited: the algorithm checks whether feature matching localization can take place. If so, it estimates the output of the localization. In theory, feature matching localization can take place anywhere. However, the resulting localization uncertainty (which is a direct measure of the quality of the localization) depends heavily on two factors: what features are visible and how well can the robot's sensors perceive them? To answer these questions and improve the performance of the feature matching localization, the solution proposed relies upon a novel type of landmarks that are characterized by: (1) a region of the conguration space, (2) a set of `best' features for localization in the region, and (3) a perception uncertainty eld that measures how well a given feature is perceived at each conguration in the region. The region associated with a landmark is used to determine whether the robot has reached a landmark (it takes into account the robot's uncertainty). If so, then the best features are then used to simulate the feature matching localization. Once again, the robot's uncertainty is taken into account; this is achieved thanks to the perception uncertainty eld. The next three sections respectively describes how odometry and feature matching localization are simulated for the purpose of safe path planning ( 4), how the landmarks are built ( 5) and how safe path planning is achieved ( 6). 4 Odometry, Localization 4.1 Odometry (Od) To decide whether a given path is safe, it is necessary to know how the conguration uncertainty changes along the path, i.e. to dene the Od function (cf. 2.4). A relies on odometric techniques to estimate its current conguration and it was decided to use an uncertainty evolution model derived from the classical odometric models used in navigation [3]. Let (^q(t); C(t)) be the uncertain conguration of A at time t. At time t + t, odometry returns (s; ), i.e. the estimates of the translational and rotational motion performed by A. Then, using the prediction part of an Extended Kalman Filter, it is possible to compute the new uncertain conguration (^q(t + t); C(t + t)) at time t + t (cf. [9] for more details). Od is dened by discretizing, estimating (s; ) at each step and by iteratively feeding the values obtained to the Extended Kalman Filter. 4.2 Localization (Lo) To determine the conguration uncertainty after a localization, it is necessary to simulate the feature matching localization procedure, i.e. to dene the Lo function (cf. 2.4). To do so, a model of the sensor is required rst. It is assumed that A is equipped with a rotating range scanner that returns the distance to the nearest obstacle in a given direction. As per [4], the sensor uncertainty is modeled by a circular covariance. Using the set of environmental features F and the sensor model, it is possible to estimate the sensor measurements and their uncertainty at a given conguration (cf. [9]). Finally, the simulated sensor measurements are fed into a classical feature matching localization procedure based upon Extended Kalman Filtering technique [14]. 5 Landmarks Recall that a feature is an environmental object that can be detected by the robot's sensors and used in feature matching localization. As soon as a feature is detectable, feature matching localization can take place. However, the resulting localization uncertainty depends on what features are visible and how well can the robot's sensors perceive them. To simplify and improve localization, a novel type of landmark is introduced. Such a landmark is characterized by: (1) R, a region of the conguration space, (2) F, a set of `best' features for localization in R, and (3) puf, a perception uncertainty eld that measures how well each feature of F is perceived at each conguration in R. 2 This assumption can be lifted easily. 4

7 F and R derive from the concepts of local map and local map validity regions developed by the second author in [9]. A local map is dened as the minimum set of features that can be used for a good localization in a region of C (called the local map validity region). Whenever A enters a region R, i.e. when (^q; C) R, localization based upon the features of F takes place. By reducing the number of features to be matched and by selecting the best features, local maps and local map validity regions simplify and improve localization. They were originally introduced to drive the feature matching procedure at navigation time. To be used at planning time, they are complemented with the perception uncertainty eld puf that takes as input a conguration q and a feature F i and returns the best sensor uncertainty (determined thanks to the simulated sensor measurements) associated with F i when observed from q. puf is computed globally over the conguration space C. As it will be seen further down, puf permits to compute a conservative localization uncertainty that does take into account the conguration uncertainty of A (cf. 6.4). In the meantime, the next two sections describe how the landmarks are automatically built from the model of the environment. 5.1 From Features to Local Maps In order to select the best features, A is placed at a given conguration q and a sensor simulation is done. Localization is then performed on each feature F j separately. The result is a set of covariance matrices C j representing the localization uncertainty when using feature F j. Each matrix C j determines an ellipsoid (q; C j ), the analysis of the intersection between the (q; C j ) permits to determine the `best' features for localization at q or rather to eliminate the features that are useless in the sense that, taking them into account into the localization process, does not improve signicantly the quality of the localization. The features F k to be eliminated are those for which (q; C k ) is strictly greater than the volume dened by \ j (q; C j ) (cf. [9]). This process is repeated over the discretized conguration space C. Its output denes the local maps for each discrete conguration q, i.e. the set of best features to be used for localization at q. 5.2 From Local Maps to Landmarks Using a clustering algorithm such as the one presented in [10], the connected congurations sharing the same local maps are grouped together to dene the local map validity regions. Along with the perception uncertainty eld puf, a local map validity region R and its local map F dene a landmark. 6 Safe Path Planning The roadmap, which is a graph, is explored using the classical Dijkstra algorithm [15]. This algorithm is guaranteed to return the path that optimizes a given cost function. Path length is a straightforward optimality criterion. Like [18], it proved interesting though to dene a cost function combining path length and path reliability. The cost function is detailed in 6.1. In the course of the graph search, each path connecting two nodes must be checked for safeness. This point is presented in 6.2. In addition, when a node is visited, the algorithm has to check whether feature matching localization can take place and if so, it must compute the corresponding localization uncertainty. These two points are respectively addressed in 6.3 and Cost Function Let be a path in the roadmap; it is a sequence of congurations (nodes of the graph) connected by feasible paths (edges of the graph). In the course of the roadmap exploration, the conguration uncertainty of A is computed and propagated. Accordingly an uncertain conguration (^q i ; C i ) is associated with each conguration-node of. The cost function J combines path length and path reliability. It is dened as: J =X 1 L(q i ; q i+1 ) + 2 R(q i ; q i+1 ) (2) i where 1 and 2 are two weighing coecients. L(q i ; q i+1 ) denotes the length of the edge-path connecting q i to q i+1. R(q i ; q i+1 ) is a measure of the reliability of the edge-path connecting q i to q i+1, it is dened as the product of the average uncertainty along the edge-path with the length of the edge-path: R(q i ; q i+1 ) = L(q i ; q i+1 ) V (q i) + V (q i+1 ) 2 where V (q i ) denotes the volume of (^q i ; C i ). 5

8 6.2 Edge-Path Safeness Potential collisions between the robot and the environment are detected by computing A((^q; C)) and by comparing it with the location of the obstacles. The odometry function Od is used to determine the conguration uncertainty along a path. For the sake of eciency, collision checking is not performed in the three dimensional conguration space C, but in the two dimensional workspace W by computing the intersection between the obstacles B i ; i 2 f1; : : : ; bg, and the region swept by A (integrating its uncertainty) when it moves along a given path. The recursive and resolution-dependent collision checker developed in [6] is used to that purpose. 6.3 Landmark Perceptibility When a node of the roadmap is visited, the algorithm must determine whether feature matching localization can take place. Recall that the landmarks have been introduced to guide feature matching localization. The landmark regions dene a partition of the conguration space C and each node of the roadmap belong to a given landmark region. Accordingly, when the node q of the roadmap is visited, the algorithm rst checks whether, the landmark associated with q, can be used for localization. In other words, it checks that A((q; C)) R where C is the current conguration uncertainty of A (to do so, R is discretized). 6.4 Localization Uncertainty Once it has been determined that feature matching localization can take place at a given node q with a given landmark, the algorithm must compute an estimate of the localization uncertainty and use it to update the conguration uncertainty of A. Recall that a set of best features F is associated to. The features of F are used for localization purposes. Let C be the current conguration uncertainty of A, a straightforward manner to estimate the localization uncertainty C l would be to use Lo(q; C; F ). However, since the quality of the localization with respect to a given feature F j clearly depends on the conguration of A at localization time, it was decided to use the following function instead: Loc-Unc (q; C; F ) C l = C forall F j 2 F q max = max qp 2(^q;C) puf(q p; F j ) C l = Lo(q max ; C l ; ff j g) endforall return C l By processing one feature at a time in the worst possible situation, a more conservative estimate of the localization uncertainty is obtained. 7 Experimental Results The left-hand side of Fig. 1 depicts the landmark regions that have been automatically determined in a m. indoor environment that contains 10 obstacles and 17 features. 23 landmark regions have been computed (dierent regions may have similar grey shades). Two examples of landmarks are depicted on the right-hand side of Fig. 1. For each example are represented (1) the validity region of the local map, and (2) the set of best features that have been retained for localization purposes. Two results of the safe path planning algorithm are depicted in Fig. 2. The rectangles represent the robot at dierent congurations (corresponding to nodes of the roadmap). The curves between the nodes are edges of the roadmap, i.e. paths verifying the nonholonomic constraints of A. The ellipses inside the rectangles represent the conguration uncertainties (before and after localization when localization can take place). In the situation depicted on the left hand side of Fig. 2, A starts from q s with an initial conguration uncertainty C s. Its goal is to reach q g with a conguration uncertainty less than C g. Since A((q s ; C s )) R A, localization can take place there and the initial conguration uncertainty ellipse is reduced. Later, the planning process has returned the sequence fq s ; q a ; q b ; q g g as being a safe path to q g with localization taking place in q s, q a and q g. The situation depicted on the right hand side of Fig. 2 is similar. The safe path is now fq s ; q a ; q b ; q c ; q d ; q g g with localization taking place in q s, q b and q d. 6

9 PSfrag replacements PSfrag replacements R A R B A Region Features R E R B C R D C R C R D R D E R E Region Features PSfrag replacements PSfrag replacements R A R B R C Region Features R B R A R D R E Region Features Figure 1: landmark regions in an indoor environment (left); two regions (R A associated features (right). and R D ) and their q g q a q b PSfrag replacements q d q g q s q a q b q g q c rag replacements q s q b q a q s Figure 2: two examples of safe paths. 8 Discussion and Conclusion This paper has presented a safe path planner for a car-like robot that estimates its conguration with odometry and an absolute localization device based on environmental feature matching. The nonholonomic kinematics of such a robot is taken into account thanks to a roadmap-based path planner. Respective simulations of the robot's odometry and localization procedure permit to estimate in a conservative way how the conguration uncertainty evolves when the robot moves or localizes itself. These simulation are used to explore the roadmap and compute a safe motion plan that alternates motion along safe paths and localization operations. The safeness issue is mainly addressed through landmarks that are characterized by: (1) a region of the conguration space, (2) a set of `best' features for localization in the region, and (3) a perception uncertainty eld that measures how well a given 7

10 feature is perceived at each conguration in the region. Their main purpose is to simplify and improve localization by reducing the number of features to be matched and by selecting only the best features. Future developments will include experiments with a real car-like robot in order to validate the soundness of our uncertainty evolution models. Acknowledgements. This work was partially supported by the French programme La Route Automatis e: References [1] J. Borenstein, H. R. Everett, and L. Feng. Where am I? Sensors and methods for autonomous mobile robot positioning 1995 edition. Technical Report, University of Michigan, [2] B. Bouilly, T. Sim on, and R. Alami. A numerical technique for planning motion strategies of a mobile robot in presence of uncertainty. In Proc. of the IEEE Int. Conf. on Robotics and Automation, volume 2, pages , Nagoya (JP), May [3] F. Chenavier and J. L. Crowley. Position estimation for a mobile robot using vision and odometry. In Proc. of the IEEE Int. Conf. on Robotics and Automation, pages , Nice (FR), May [4] J. L. Crowley. World modeling and position estimation for a mobile robot using ultrasonic ranging. In Proc. of the IEEE Int. Conf. on Robotics and Automation, pages , Scottsdale, AZ (US), May [5] F. De la Rosa, C. Laugier, and J. N jera. Robust path planning in the plane. IEEE Trans. Robotics and Automation, 12(2):347352, April [6] Th. Fraichard and R. Mermond. Path planning with uncertainty for car-like robots. In Proc. of the IEEE Int. Conf. on Robotics and Automation, volume 1, pages 2732, Leuven (BE), May [7] Th. Fraichard, A. Scheuer, and R. Desvigne. From Reeds and Shepp's to continuous-curvature paths. In Proc. of the IEEE Int. Conf. on Advanced Robotics, pages , Tokyo (JP), October [8] K. Y. Goldberg, M. T. Mason, and A. Requicha. Geometric uncertainty in motion planning: summary report and bibliography. Technical Report IRIS-297, University of Southern California, [9] A. Lambert and N. Le Fort-Piat. Safe task planning integrating uncertainties and local maps federations. Int. Journal of Robotics Research, To appear. [10] A. Lambert, M. Van Dang, and G. Govaert. Generating validity regions using Markovian spatial clustering. In Proc. of the IEEE Int. Conf. on Advanced Robotics, pages , Tokyo (JP), October [11] J.-C. Latombe. Robot motion planning. Kluwer Academic Press, [12] J.-P. Laumond, editor. Robot motion planning and control, volume 229 of Lecture Notes in Control and Information Science. Springer, [13] A. Lazanas and J.-C. Latombe. Motion planning with uncertainty: a landmark approach. In Articial Intelligence, volume 76, pages , [14] J. J. Leonard and H.F. Durant-Whyte. Mobile robot localization by tracking geometric beacons. IEEE Trans. Robotics and Automation, 7(3):376382, [15] N. J. Nilsson. Principles of articial intelligence. Morgan Kaufmann, Los Altos, CA (USA), [16] R. C. Smith and P. Cheeseman. On the representation and estimation of spatial uncertainty. Int. Journal of Robotics Research, 5(4):5668, Winter [17] P. Svestka and M. H. Overmars. Probabilistic path planning. In J.-P. Laumond, editor, Robot motion planning and control, volume 229 of Lecture Notes in Control and Information Science, pages Springer, [18] H. Takeda, C. Facchinetti, and J.-C. Latombe. Planning the motions of a mobile robot in a sensory uncertainty eld. IEEE Trans. on Pattern Analysis and Machine Intelligence, 16(10): , October

IEEE-RSJ Int. Conf. on Intelligent Robots and Systems October 2-6, 998. Victoria BC (CA). Planning Sub-Optimal and Continuous-Curvature Paths for Car-Like Robots A. Scheuer and Ch. Laugier Inria a Rh^one-Alpes

More information

Localization, Where am I?

Localization, Where am I? 5.1 Localization, Where am I?? position Position Update (Estimation?) Encoder Prediction of Position (e.g. odometry) YES matched observations Map data base predicted position Matching Odometry, Dead Reckoning

More information

Robust Motion Planning using Markov Decision Processes and Quadtree Decomposition

Robust Motion Planning using Markov Decision Processes and Quadtree Decomposition Robust Motion Planning using Markov Decision Processes and Quadtree Decomposition Julien Burlet, Olivier Aycard, Thierry Fraichard To cite this version: Julien Burlet, Olivier Aycard, Thierry Fraichard.

More information

Advanced Robotics, 13(1):75{94, 1999 Trajectory Planning in a Dynamic Workspace: a `State-Time Space' Approach Th. Fraichard Inria a Rh^one-Alpes Zirs

Advanced Robotics, 13(1):75{94, 1999 Trajectory Planning in a Dynamic Workspace: a `State-Time Space' Approach Th. Fraichard Inria a Rh^one-Alpes Zirs Advanced Robotics, 13(1):75{94, 1999 Trajectory Planning in a Dynamic Workspace: a `State-Time Space' Approach Th. Fraichard Inria a Rh^one-Alpes Zirst. 655 av. de l'europe, 38330 Montbonnot Saint Martin,

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

IEEE TRANSACTIONS ON ROBOTICS AND AUTOMATION, VOL. XX, NO. Y, MONTH Smooth motion planning for car-like vehicles

IEEE TRANSACTIONS ON ROBOTICS AND AUTOMATION, VOL. XX, NO. Y, MONTH Smooth motion planning for car-like vehicles IEEE TRANSATIONS ON ROBOTIS AND AUTOMATION, VOL. XX, NO. Y, MONTH 2 Smooth motion planning for car-like vehicles F. Lamiraux and J.-P. Laumond Abstract This paper presents a steering method for a carlike

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

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

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

Localization and Map Building

Localization and Map Building Localization and Map Building Noise and aliasing; odometric position estimation To localize or not to localize Belief representation Map representation Probabilistic map-based localization Other examples

More information

An Architecture for Automated Driving in Urban Environments

An Architecture for Automated Driving in Urban Environments An Architecture for Automated Driving in Urban Environments Gang Chen and Thierry Fraichard Inria Rhône-Alpes & LIG-CNRS Lab., Grenoble (FR) firstname.lastname@inrialpes.fr Summary. This paper presents

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

Keeping features in the camera s field of view: a visual servoing strategy

Keeping features in the camera s field of view: a visual servoing strategy Keeping features in the camera s field of view: a visual servoing strategy G. Chesi, K. Hashimoto,D.Prattichizzo,A.Vicino Department of Information Engineering, University of Siena Via Roma 6, 3 Siena,

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

Techniques. IDSIA, Istituto Dalle Molle di Studi sull'intelligenza Articiale. Phone: Fax:

Techniques. IDSIA, Istituto Dalle Molle di Studi sull'intelligenza Articiale. Phone: Fax: Incorporating Learning in Motion Planning Techniques Luca Maria Gambardella and Marc Haex IDSIA, Istituto Dalle Molle di Studi sull'intelligenza Articiale Corso Elvezia 36 - CH - 6900 Lugano Phone: +41

More information

A Stochastic Environment Modeling Method for Mobile Robot by using 2-D Laser scanner Young D. Kwon,Jin.S Lee Department of Electrical Engineering, Poh

A Stochastic Environment Modeling Method for Mobile Robot by using 2-D Laser scanner Young D. Kwon,Jin.S Lee Department of Electrical Engineering, Poh A Stochastic Environment Modeling Method for Mobile Robot by using -D Laser scanner Young D. Kwon,Jin.S Lee Department of Electrical Engineering, Pohang University of Science and Technology, e-mail: jsoo@vision.postech.ac.kr

More information

From Reeds and Shepp s to continuous-curvature paths

From Reeds and Shepp s to continuous-curvature paths From Reeds and Shepp s to continuous-curvature paths Thierry Fraichard, Alexis Scheuer To cite this version: Thierry Fraichard, Alexis Scheuer. From Reeds and Shepp s to continuous-curvature paths. IEEE

More information

Path Coordination for Multiple Mobile Robots: A Resolution-Complete Algorithm

Path Coordination for Multiple Mobile Robots: A Resolution-Complete Algorithm 42 IEEE TRANSACTIONS ON ROBOTICS AND AUTOMATION, VOL. 18, NO. 1, FEBRUARY 2002 Path Coordination for Multiple Mobile Robots: A Resolution-Complete Algorithm Thierry Siméon, Stéphane Leroy, and Jean-Paul

More information

APCS. Start. Is a Flat Wall Found? No. Position Correction. Corrected Positon. Yes. Yes. Locomotion Module. Ultrasonic Sensor Measured Range Data

APCS. Start. Is a Flat Wall Found? No. Position Correction. Corrected Positon. Yes. Yes. Locomotion Module. Ultrasonic Sensor Measured Range Data n Implementation of Landmark-based Position Estimation Function as an utonomous and Distributed System for a Mobile Robot Takashi YMMOTO 3 Shoichi MEYM kihisa OHY Shin'ichi YUT Intelligent Robot Laboratory,

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

Obstacles Avoidance for Car-Like Robots Integration And Experimentation on Two Robots

Obstacles Avoidance for Car-Like Robots Integration And Experimentation on Two Robots Obstacles Avoidance for Car-Like Robots Integration And Experimentation on Two Robots Olivier Lefebvre Florent Lamiraux Cédric Pradalier Thierry Fraichard firstname.lastname@laas.fr firstname.lastname@inrialpes.fr

More information

(1) LAAS/CNRS, Toulouse, France. and. (2) Department of Computer Science, Utrecht University, the Netherlands

(1) LAAS/CNRS, Toulouse, France. and. (2) Department of Computer Science, Utrecht University, the Netherlands Multi-Level Path Planning for Nonholonomic Robots using Semi-Holonomic Subsystems Sepanta Sekhavat 1,Petr Svestka 2, J.-P. Laumond 1, Mark H. Overmars 2 (1) LAAS/CNRS, Toulouse, France and (2) Department

More information

DYNAMIC POSITIONING OF A MOBILE ROBOT USING A LASER-BASED GONIOMETER. Joaquim A. Batlle*, Josep Maria Font*, Josep Escoda**

DYNAMIC POSITIONING OF A MOBILE ROBOT USING A LASER-BASED GONIOMETER. Joaquim A. Batlle*, Josep Maria Font*, Josep Escoda** DYNAMIC POSITIONING OF A MOBILE ROBOT USING A LASER-BASED GONIOMETER Joaquim A. Batlle*, Josep Maria Font*, Josep Escoda** * Department of Mechanical Engineering Technical University of Catalonia (UPC)

More information

Automatic Generation of Smooth Paths Bounded by Polygonal Chains

Automatic Generation of Smooth Paths Bounded by Polygonal Chains Automatic Generation of Smooth Paths Bounded by Polygonal Chains T. Berglund 1, U. Erikson 1, H. Jonsson 1, K. Mrozek 2, and I. Söderkvist 3 1 Department of Computer Science and Electrical Engineering,

More information

Jane Li. Assistant Professor Mechanical Engineering Department, Robotic Engineering Program Worcester Polytechnic Institute

Jane Li. Assistant Professor Mechanical Engineering Department, Robotic Engineering Program Worcester Polytechnic Institute Jane Li Assistant Professor Mechanical Engineering Department, Robotic Engineering Program Worcester Polytechnic Institute (3 pts) How to generate Delaunay Triangulation? (3 pts) Explain the difference

More information

Algorithmic Robotics and Motion Planning

Algorithmic Robotics and Motion Planning Algorithmic Robotics and Motion Planning Spring 2018 Introduction Dan Halperin School of Computer Science Tel Aviv University Dolce & Gabbana 2018 handbag collection Today s lesson basic terminology fundamental

More information

Dynamic Modeling of Free-Space for a Mobile Robot

Dynamic Modeling of Free-Space for a Mobile Robot Dynamic Modeling of Free-Space for a Mobile Robot 1. Introduction James L. Crowley, Patrick Reignier and Philippe Bobet LIFIA (IMAG) Institut National Polytechnique de Grenoble Grenoble, France Free-space

More information

Navigation and Metric Path Planning

Navigation and Metric Path Planning Navigation and Metric Path Planning October 4, 2011 Minerva tour guide robot (CMU): Gave tours in Smithsonian s National Museum of History Example of Minerva s occupancy map used for navigation Objectives

More information

VISION-BASED MOBILE ROBOT LOCALIZATION WITH SIMPLE ARTIFICIAL LANDMARKS. Robert B aczyk, Andrzej Kasiński, Piotr Skrzypczyński

VISION-BASED MOBILE ROBOT LOCALIZATION WITH SIMPLE ARTIFICIAL LANDMARKS. Robert B aczyk, Andrzej Kasiński, Piotr Skrzypczyński VISION-BASED MOBILE ROBOT LOCALIZATION WITH SIMPLE ARTIFICIAL LANDMARKS Robert B aczyk, Andrzej Kasiński, Piotr Skrzypczyński Poznań University of Technology, Institute of Control and Information Engineering,

More information

A Divide-and-Merge Approach to Automatic Generation of Contact. States and Planning of Contact Motion

A Divide-and-Merge Approach to Automatic Generation of Contact. States and Planning of Contact Motion A Divide-and-Merge Approach to Automatic Generation of Contact States and Planning of Contact Motion Jing Xiao and Xuerong Ji Computer Science Department University of North Carolina - Charlotte Charlotte,

More information

Aerial Robotic Autonomous Exploration & Mapping in Degraded Visual Environments. Kostas Alexis Autonomous Robots Lab, University of Nevada, Reno

Aerial Robotic Autonomous Exploration & Mapping in Degraded Visual Environments. Kostas Alexis Autonomous Robots Lab, University of Nevada, Reno Aerial Robotic Autonomous Exploration & Mapping in Degraded Visual Environments Kostas Alexis Autonomous Robots Lab, University of Nevada, Reno Motivation Aerial robotic operation in GPS-denied Degraded

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

the robot attains the goal configuration. Before each iteration, a localization will be performed to precisely determine the robot's current configura

the robot attains the goal configuration. Before each iteration, a localization will be performed to precisely determine the robot's current configura An Integrated Mobile Robot Path (Re)Planner and Localizer for Personal Robots Λ Jinsuck Kim Nancy M. Amato Department ofcomputer Science Texas A&M University College Station, TX 77843 fjinsuckk,amatog@cs.tamu.edu

More information

PROJECTION MODELING SIMPLIFICATION MARKER EXTRACTION DECISION. Image #k Partition #k

PROJECTION MODELING SIMPLIFICATION MARKER EXTRACTION DECISION. Image #k Partition #k TEMPORAL STABILITY IN SEQUENCE SEGMENTATION USING THE WATERSHED ALGORITHM FERRAN MARQU ES Dept. of Signal Theory and Communications Universitat Politecnica de Catalunya Campus Nord - Modulo D5 C/ Gran

More information

MOTION. Feature Matching/Tracking. Control Signal Generation REFERENCE IMAGE

MOTION. Feature Matching/Tracking. Control Signal Generation REFERENCE IMAGE Head-Eye Coordination: A Closed-Form Solution M. Xie School of Mechanical & Production Engineering Nanyang Technological University, Singapore 639798 Email: mmxie@ntuix.ntu.ac.sg ABSTRACT In this paper,

More information

Lecture 3: Motion Planning 2

Lecture 3: Motion Planning 2 CS 294-115 Algorithmic Human-Robot Interaction Fall 2017 Lecture 3: Motion Planning 2 Scribes: David Chan and Liting Sun - Adapted from F2016 Notes by Molly Nicholas and Chelsea Zhang 3.1 Previously Recall

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

A Fuzzy Local Path Planning and Obstacle Avoidance for Mobile Robots

A Fuzzy Local Path Planning and Obstacle Avoidance for Mobile Robots A Fuzzy Local Path Planning and Obstacle Avoidance for Mobile Robots H.Aminaiee Department of Electrical and Computer Engineering, University of Tehran, Tehran, Iran Abstract This paper presents a local

More information

MOBILE ROBOT LOCALIZATION. REVISITING THE TRIANGULATION METHODS. Josep Maria Font, Joaquim A. Batlle

MOBILE ROBOT LOCALIZATION. REVISITING THE TRIANGULATION METHODS. Josep Maria Font, Joaquim A. Batlle MOBILE ROBOT LOCALIZATION. REVISITING THE TRIANGULATION METHODS Josep Maria Font, Joaquim A. Batlle Department of Mechanical Engineering Technical University of Catalonia (UC) Avda. Diagonal 647, 08028

More information

Final Exam Practice Fall Semester, 2012

Final Exam Practice Fall Semester, 2012 COS 495 - Autonomous Robot Navigation Final Exam Practice Fall Semester, 2012 Duration: Total Marks: 70 Closed Book 2 hours Start Time: End Time: By signing this exam, I agree to the honor code Name: Signature:

More information

A MOBILE ROBOT MAPPING SYSTEM WITH AN INFORMATION-BASED EXPLORATION STRATEGY

A MOBILE ROBOT MAPPING SYSTEM WITH AN INFORMATION-BASED EXPLORATION STRATEGY A MOBILE ROBOT MAPPING SYSTEM WITH AN INFORMATION-BASED EXPLORATION STRATEGY Francesco Amigoni, Vincenzo Caglioti, Umberto Galtarossa Dipartimento di Elettronica e Informazione, Politecnico di Milano Piazza

More information

Non-holonomic Planning

Non-holonomic Planning Non-holonomic Planning Jane Li Assistant Professor Mechanical Engineering & Robotics Engineering http://users.wpi.edu/~zli11 Recap We have learned about RRTs. q new q init q near q rand But the standard

More information

Environment Identification by Comparing Maps of Landmarks

Environment Identification by Comparing Maps of Landmarks Environment Identification by Comparing Maps of Landmarks Jens-Steffen Gutmann Masaki Fukuchi Kohtaro Sabe Digital Creatures Laboratory Sony Corporation -- Kitashinagawa, Shinagawa-ku Tokyo, 4- Japan Email:

More information

DEALING WITH SENSOR ERRORS IN SCAN MATCHING FOR SIMULTANEOUS LOCALIZATION AND MAPPING

DEALING WITH SENSOR ERRORS IN SCAN MATCHING FOR SIMULTANEOUS LOCALIZATION AND MAPPING Inženýrská MECHANIKA, roč. 15, 2008, č. 5, s. 337 344 337 DEALING WITH SENSOR ERRORS IN SCAN MATCHING FOR SIMULTANEOUS LOCALIZATION AND MAPPING Jiří Krejsa, Stanislav Věchet* The paper presents Potential-Based

More information

Landmark-Based Robot Motion Planning

Landmark-Based Robot Motion Planning Landmark-Based Robot Motion Planning Anthony Lazanas and Jean-Claude Latombe lazanas@cs.st anford.edu latombe@cs.st anford.edu Robotics Laboratory Department of Computer Science, Stanford University Stanford,

More information

Smooth Motion Planning for Car-Like Vehicles

Smooth Motion Planning for Car-Like Vehicles 498 IEEE TRANSACTIONS ON ROBOTICS AND AUTOMATION, VOL. 17, NO. 4, AUGUST 21 Smooth Motion Planning for Car-Like Vehicles F. Lamiraux and J.-P. Laumond Abstract This paper presents a steering method for

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

Lecture 3: Motion Planning (cont.)

Lecture 3: Motion Planning (cont.) CS 294-115 Algorithmic Human-Robot Interaction Fall 2016 Lecture 3: Motion Planning (cont.) Scribes: Molly Nicholas, Chelsea Zhang 3.1 Previously in class... Recall that we defined configuration spaces.

More information

Elastic Bands: Connecting Path Planning and Control

Elastic Bands: Connecting Path Planning and Control Elastic Bands: Connecting Path Planning and Control Sean Quinlan and Oussama Khatib Robotics Laboratory Computer Science Department Stanford University Abstract Elastic bands are proposed as the basis

More information

THREE VISION-BASED BEHAVIORS FOR SELF- Claudio Facchinetti, Francois Tieche and Heinz Hugli

THREE VISION-BASED BEHAVIORS FOR SELF- Claudio Facchinetti, Francois Tieche and Heinz Hugli THREE VISION-BASED BEHAVIORS FOR SELF- POSITIONING A MOBILE ROBOT Claudio Facchinetti, Francois Tieche and Heinz Hugli (claudio.facchinetti@imt.unine.ch) Institute of Microtechnology University of Neuch^atel,

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

Optimal Trajectory Generation for Nonholonomic Robots in Dynamic Environments

Optimal Trajectory Generation for Nonholonomic Robots in Dynamic Environments 28 IEEE International Conference on Robotics and Automation Pasadena, CA, USA, May 19-23, 28 Optimal Trajectory Generation for Nonholonomic Robots in Dynamic Environments Yi Guo and Tang Tang Abstract

More information

Optimization of the Simultaneous Localization and Map-Building Algorithm for Real-Time Implementation

Optimization of the Simultaneous Localization and Map-Building Algorithm for Real-Time Implementation 242 IEEE TRANSACTIONS ON ROBOTICS AND AUTOMATION, VOL. 17, NO. 3, JUNE 2001 Optimization of the Simultaneous Localization and Map-Building Algorithm for Real-Time Implementation José E. Guivant and Eduardo

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

Time Optimal Trajectories for Bounded Velocity Differential Drive Robots

Time Optimal Trajectories for Bounded Velocity Differential Drive Robots Time Optimal Trajectories for Bounded Velocity Differential Drive Robots Devin J. Balkcom Matthew T. Mason Robotics Institute and Computer Science Department Carnegie Mellon University Pittsburgh PA 53

More information

A set theoretic approach to path planning for mobile robots

A set theoretic approach to path planning for mobile robots A set theoretic approach to path planning for mobile robots Nicola Ceccarelli, Mauro Di Marco, Andrea Garulli, Antonio Giannitrapani Dipartimento di Ingegneria dell Informazione Università di Siena Via

More information

Autonomous Mobile Robot Design

Autonomous Mobile Robot Design Autonomous Mobile Robot Design Topic: EKF-based SLAM Dr. Kostas Alexis (CSE) These slides have partially relied on the course of C. Stachniss, Robot Mapping - WS 2013/14 Autonomous Robot Challenges Where

More information

S-SHAPED ONE TRAIL PARALLEL PARKING OF A CAR-LIKE MOBILE ROBOT

S-SHAPED ONE TRAIL PARALLEL PARKING OF A CAR-LIKE MOBILE ROBOT S-SHAPED ONE TRAIL PARALLEL PARKING OF A CAR-LIKE MOBILE ROBOT 1 SOE YU MAUNG MAUNG, 2 NU NU WIN, 3 MYINT HTAY 1,2,3 Mechatronic Engineering Department, Mandalay Technological University, The Republic

More information

Sensor Calibration. Sensor Data. Processing. Local Map LM k. SPmap Prediction SPmap Estimation. Global Map GM k

Sensor Calibration. Sensor Data. Processing. Local Map LM k. SPmap Prediction SPmap Estimation. Global Map GM k Sensor Inuence in the Performance of Simultaneous Mobile Robot Localization and Map Building J.A. Castellanos J.M.M. Montiel J. Neira J.D. Tardos Departamento de Informatica e Ingeniera de Sistemas Universidad

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

Online Simultaneous Localization and Mapping in Dynamic Environments

Online Simultaneous Localization and Mapping in Dynamic Environments To appear in Proceedings of the Intl. Conf. on Robotics and Automation ICRA New Orleans, Louisiana, Apr, 2004 Online Simultaneous Localization and Mapping in Dynamic Environments Denis Wolf and Gaurav

More information

A Path Tracking Method For Autonomous Mobile Robots Based On Grid Decomposition

A Path Tracking Method For Autonomous Mobile Robots Based On Grid Decomposition A Path Tracking Method For Autonomous Mobile Robots Based On Grid Decomposition A. Pozo-Ruz*, C. Urdiales, A. Bandera, E. J. Pérez and F. Sandoval Dpto. Tecnología Electrónica. E.T.S.I. Telecomunicación,

More information

Elastic Correction of Dead-Reckoning Errors in Map Building

Elastic Correction of Dead-Reckoning Errors in Map Building Elastic Correction of Dead-Reckoning Errors in Map Building Matteo Golfarelli Dario Maio Stefano Rizzi DEIS, Università di Bologna Bologna, Italy Abstract A major problem in map building is due to the

More information

Mobile Robots: An Introduction.

Mobile Robots: An Introduction. Mobile Robots: An Introduction Amirkabir University of Technology Computer Engineering & Information Technology Department http://ce.aut.ac.ir/~shiry/lecture/robotics-2004/robotics04.html Introduction

More information

World Modeling and Position Estimation for a Mobile Robot Using Ultrasonic Ranging

World Modeling and Position Estimation for a Mobile Robot Using Ultrasonic Ranging World Modeling and Position Estimation for a Mobile Robot Using Ultrasonic Ranging James L. Crowley Institut National Polytechnique de Grenoble Grenoble, France 1989 IEEE Conference on Robotics and Automation,

More information

Uncertainties: Representation and Propagation & Line Extraction from Range data

Uncertainties: Representation and Propagation & Line Extraction from Range data 41 Uncertainties: Representation and Propagation & Line Extraction from Range data 42 Uncertainty Representation Section 4.1.3 of the book Sensing in the real world is always uncertain How can uncertainty

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

Proceedings of the 6th Int. Conf. on Computer Analysis of Images and Patterns. Direct Obstacle Detection and Motion. from Spatio-Temporal Derivatives

Proceedings of the 6th Int. Conf. on Computer Analysis of Images and Patterns. Direct Obstacle Detection and Motion. from Spatio-Temporal Derivatives Proceedings of the 6th Int. Conf. on Computer Analysis of Images and Patterns CAIP'95, pp. 874-879, Prague, Czech Republic, Sep 1995 Direct Obstacle Detection and Motion from Spatio-Temporal Derivatives

More information

Vision-Motion Planning with Uncertainty

Vision-Motion Planning with Uncertainty Vision-Motion Planning with Uncertainty Jun MIURA Yoshiaki SHIRAI Dept. of Mech. Eng. for Computer-Controlled Machinery, Osaka University, Suita, Osaka 565, Japan jun@ccm.osaka-u.ac.jp Abstract This paper

More information

Agent Based Intersection Traffic Simulation

Agent Based Intersection Traffic Simulation Agent Based Intersection Traffic Simulation David Wilkie May 7, 2009 Abstract This project focuses on simulating the traffic at an intersection using agent-based planning and behavioral methods. The motivation

More information

DYNAMIC TRIANGULATION FOR MOBILE ROBOT LOCALIZATION USING AN ANGULAR STATE KALMAN FILTER. Josep Maria Font, Joaquim A. Batlle

DYNAMIC TRIANGULATION FOR MOBILE ROBOT LOCALIZATION USING AN ANGULAR STATE KALMAN FILTER. Josep Maria Font, Joaquim A. Batlle DYNAMIC TRIANGULATION FOR MOBILE ROBOT LOCALIZATION USING AN ANGULAR STATE KALMAN FILTER Josep Maria Font, Joaquim A. Batlle Department of Mechanical Engineering Technical University of Catalonia (UPC)

More information

Jean-Claude Eatornbe

Jean-Claude Eatornbe From: AAAI-91 Proceedings. Copyright 1991, AAAI (www.aaai.org). All rights reserved. Jean-Claude Eatornbe Robotics Laboratory Department of Computer Science, Stanford University Stanford, CA 94305 latombe@cs.stanford.edu

More information

P ^ 2π 3 2π 3. 2π 3 P 2 P 1. a. b. c.

P ^ 2π 3 2π 3. 2π 3 P 2 P 1. a. b. c. Workshop on Fundamental Structural Properties in Image and Pattern Analysis - FSPIPA-99, Budapest, Hungary, Sept 1999. Quantitative Analysis of Continuous Symmetry in Shapes and Objects Hagit Hel-Or and

More information

Neuro-adaptive Formation Maintenance and Control of Nonholonomic Mobile Robots

Neuro-adaptive Formation Maintenance and Control of Nonholonomic Mobile Robots Proceedings of the International Conference of Control, Dynamic Systems, and Robotics Ottawa, Ontario, Canada, May 15-16 2014 Paper No. 50 Neuro-adaptive Formation Maintenance and Control of Nonholonomic

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

COS Lecture 13 Autonomous Robot Navigation

COS Lecture 13 Autonomous Robot Navigation COS 495 - Lecture 13 Autonomous Robot Navigation Instructor: Chris Clark Semester: Fall 2011 1 Figures courtesy of Siegwart & Nourbakhsh Control Structure Prior Knowledge Operator Commands Localization

More information

Mirror C 6 C 2. b. c. d. e.

Mirror C 6 C 2. b. c. d. e. To appear in Symmetry Culture and Science 1999, 4th Int. Conf. of the Interdisciplinary Study of Symmetry ISIS98 Computational Aspects in Image Analysis of Symmetry and of its Perception Hagit Hel-Or Dept

More information

Spring Localization II. Roland Siegwart, Margarita Chli, Martin Rufli. ASL Autonomous Systems Lab. Autonomous Mobile Robots

Spring Localization II. Roland Siegwart, Margarita Chli, Martin Rufli. ASL Autonomous Systems Lab. Autonomous Mobile Robots Spring 2016 Localization II Localization I 25.04.2016 1 knowledge, data base mission commands Localization Map Building environment model local map position global map Cognition Path Planning path Perception

More information

A Real-Time Navigation Architecture for Automated Vehicles in Urban Environments

A Real-Time Navigation Architecture for Automated Vehicles in Urban Environments A Real-Time Navigation Architecture for Automated Vehicles in Urban Environments Gang Chen and Thierry Fraichard Inria Rhône-Alpes & LIG-CNRS Laboratory, Grenoble (FR) Submitted to the Int. Conf. on Field

More information

Navigating Dynamic Environments with Trajectory Deformation

Navigating Dynamic Environments with Trajectory Deformation Navigating Dynamic Environments with Trajectory Deformation Thierry Fraichard, Vivien Delsart To cite this version: Thierry Fraichard, Vivien Delsart. Navigating Dynamic Environments with Trajectory Deformation.

More information

Navigation methods and systems

Navigation methods and systems Navigation methods and systems Navigare necesse est Content: Navigation of mobile robots a short overview Maps Motion Planning SLAM (Simultaneous Localization and Mapping) Navigation of mobile robots a

More information

Introduction to Mobile Robotics

Introduction to Mobile Robotics Introduction to Mobile Robotics Olivier Aycard Associate Professor University of Grenoble Laboratoire d Informatique de Grenoble http://membres-liglab.imag.fr/aycard 1/29 Some examples of mobile robots

More information

Geometrical Feature Extraction Using 2D Range Scanner

Geometrical Feature Extraction Using 2D Range Scanner Geometrical Feature Extraction Using 2D Range Scanner Sen Zhang Lihua Xie Martin Adams Fan Tang BLK S2, School of Electrical and Electronic Engineering Nanyang Technological University, Singapore 639798

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

VISION-BASED HANDLING WITH A MOBILE ROBOT

VISION-BASED HANDLING WITH A MOBILE ROBOT VISION-BASED HANDLING WITH A MOBILE ROBOT STEFAN BLESSING TU München, Institut für Werkzeugmaschinen und Betriebswissenschaften (iwb), 80290 München, Germany, e-mail: bl@iwb.mw.tu-muenchen.de STEFAN LANSER,

More information

Exploration of Unknown or Partially Known. Prof. Dr. -Ing. G. Farber. the current step. It can be derived from a third camera

Exploration of Unknown or Partially Known. Prof. Dr. -Ing. G. Farber. the current step. It can be derived from a third camera Exploration of Unknown or Partially Known Environments? Darius Burschka, Christof Eberst Institute of Process Control Computers Prof. Dr. -Ing. G. Farber Technische Universitat Munchen 80280 Munich, Germany

More information

Three-Dimensional Off-Line Path Planning for Unmanned Aerial Vehicle Using Modified Particle Swarm Optimization

Three-Dimensional Off-Line Path Planning for Unmanned Aerial Vehicle Using Modified Particle Swarm Optimization Three-Dimensional Off-Line Path Planning for Unmanned Aerial Vehicle Using Modified Particle Swarm Optimization Lana Dalawr Jalal Abstract This paper addresses the problem of offline path planning for

More information

A Comparison of Position Estimation Techniques Using Occupancy Grids

A Comparison of Position Estimation Techniques Using Occupancy Grids A Comparison of Position Estimation Techniques Using Occupancy Grids Bernt Schiele and James L. Crowley LIFIA (IMAG) - I.N.P. Grenoble 46 Avenue Félix Viallet 38031 Grenoble Cedex FRANCE Abstract A mobile

More information

Mobile Robotics. Mathematics, Models, and Methods. HI Cambridge. Alonzo Kelly. Carnegie Mellon University UNIVERSITY PRESS

Mobile Robotics. Mathematics, Models, and Methods. HI Cambridge. Alonzo Kelly. Carnegie Mellon University UNIVERSITY PRESS Mobile Robotics Mathematics, Models, and Methods Alonzo Kelly Carnegie Mellon University HI Cambridge UNIVERSITY PRESS Contents Preface page xiii 1 Introduction 1 1.1 Applications of Mobile Robots 2 1.2

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

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

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

ON THE DUALITY OF ROBOT AND SENSOR PATH PLANNING. Ashleigh Swingler and Silvia Ferrari Mechanical Engineering and Materials Science Duke University

ON THE DUALITY OF ROBOT AND SENSOR PATH PLANNING. Ashleigh Swingler and Silvia Ferrari Mechanical Engineering and Materials Science Duke University ON THE DUALITY OF ROBOT AND SENSOR PATH PLANNING Ashleigh Swingler and Silvia Ferrari Mechanical Engineering and Materials Science Duke University Conference on Decision and Control - December 10, 2013

More information

1 Trajectories. Class Notes, Trajectory Planning, COMS4733. Figure 1: Robot control system.

1 Trajectories. Class Notes, Trajectory Planning, COMS4733. Figure 1: Robot control system. Class Notes, Trajectory Planning, COMS4733 Figure 1: Robot control system. 1 Trajectories Trajectories are characterized by a path which is a space curve of the end effector. We can parameterize this curve

More information

Localization and Map Building

Localization and Map Building Localization and Map Building Noise and aliasing; odometric position estimation To localize or not to localize Belief representation Map representation Probabilistic map-based localization Other examples

More information

Sung-Eui Yoon ( 윤성의 )

Sung-Eui Yoon ( 윤성의 ) Path Planning for Point Robots Sung-Eui Yoon ( 윤성의 ) Course URL: http://sglab.kaist.ac.kr/~sungeui/mpa Class Objectives Motion planning framework Classic motion planning approaches 2 3 Configuration Space:

More information

User Interface. Global planner. Local planner. sensors. actuators

User Interface. Global planner. Local planner. sensors. actuators Combined Map-Based and Case-Based Path Planning for Mobile Robot Navigation Maarja Kruusmaa and Bertil Svensson Chalmers University of Technology, Department of Computer Engineering, S-412 96 Gothenburg,

More information

Scaling the Dynamic Approach to Autonomous Path Planning: 3401 Walnut Street, Room 301C Kungliga Tekniska H gskolan

Scaling the Dynamic Approach to Autonomous Path Planning: 3401 Walnut Street, Room 301C Kungliga Tekniska H gskolan Scaling the Dynamic Approach to Autonomous Path Planning: Planning Horizon Dynamics Edward W. Large, Henrik I. Christensen y & Ruzena Bajcsy ** GRASP Laboratory y Centre for Autonomous Systems University

More information

Department of Electrical Engineering, Keio University Hiyoshi Kouhoku-ku Yokohama 223, Japan

Department of Electrical Engineering, Keio University Hiyoshi Kouhoku-ku Yokohama 223, Japan Shape Modeling from Multiple View Images Using GAs Satoshi KIRIHARA and Hideo SAITO Department of Electrical Engineering, Keio University 3-14-1 Hiyoshi Kouhoku-ku Yokohama 223, Japan TEL +81-45-563-1141

More information

Homework #2 Posted: February 8 Due: February 15

Homework #2 Posted: February 8 Due: February 15 CS26N Motion Planning for Robots, Digital Actors and Other Moving Objects (Winter 2012) Homework #2 Posted: February 8 Due: February 15 How to complete this HW: First copy this file; then type your answers

More information