Sub-Optimal Heuristic Search ARA* and Experience Graphs

Size: px
Start display at page:

Download "Sub-Optimal Heuristic Search ARA* and Experience Graphs"

Transcription

1 Robot Autonomy (16-662, S13) Lecture#09 (Wednesday Feb 13, 2013) Lecture by: Micheal Phillips Sub-Optimal Heuristic Search ARA* and Experience Graphs Scribes: S.Selvam Raju and Adam Lebovitz Contents 1 Introduction 2 2 Typical approaches to motion planning 3 3 ARA* Heuristic Search Why the sub-optimal A* ARA* - Re-use of search results ARA* Algorithm Applications: Planning for manipulation ARA*-based motion planning for a single 7DOF arm ARA*-based motion planning for dual-arm motion Discussion Experience Graphs Planning with E-Graphs Applications in Mobile Manipulation Conclusion 12 1

2 1 Introduction These notes are an introduction to Planning for mobile manipulation and a detailed description of the sub-optimal heuristic search algorithms. The disadvantages of the heuristic algorithms are also discussed hence describing the need for sub-optimal heuristics. Planning for Mobile Manipulation There are several tasks in robotics that involve planning. A few such planning tasks that a bar tender robot for example has would be: Task planning (order of getting items) Planning for navigation Planning motions for an arm Planning coordinated full body motions (base + arms) Planning how to grasp an object These notes chiefly deal with the planning algorithms that are used in planning motions for an arm and the co-ordinated full body motion. Figure 1: A bartender robot after pouring a drink into a glass. 2

3 2 Typical approaches to motion planning Consider a 20 DoF arm for which each state is defined by 20 discretized joint angles {q1, q2,..., q20}. Each action for this arm represented in 2D is achieved by changing one angle (or a set of angles) at a time. For the purpose of planning the motion of this arm, we would be required to search a very high dimensional state-space that these angles represent. For the 20D arm under consideration we might have to store m 20 states in the memory, where m is # the of values. Instead usually the states are computed on the fly as search expands states. Figure 2: A 20D arm represented on 2D to illustrate the number of states available for planning A few methods in which this planning could be done are: 1. Planning with optimized heuristic search-based approaches Eg: A* and D* These approaches have an advantage that: they are complete and guarantee optimality they have excellent cost minimization they have consistent solutions to similar motion queries However they are slow and memory intensive and hence are used only for 2D {x, y} path planning applications. 2. Planning with sampling-based approaches Eg: RRT, PRM etc. 3

4 These approaches are typically very fast and work with low memory and hence are used for high-d path/motion planning applications. However, they have the following disadvantages: they are complete only in the defined limit they often have a poor cost minimization hard to provide solution consistency 3. Planning with sub-optimal heuristic based approaches These approaches can be fast enough for high-d motion planning and return consistently good quality solutions. We have two such searches: ARA* (Anytime version of A*) graph search This search makes effective use of solutions (previously computed) to arrive at easier motion planning problems within a preset span of time. Experience graphs This is a heuristic search that learns from its planning experiences. 3 ARA* Heuristic Search In real world planning problems, time for deliberation is often limited. Anytime planners are well suited in addressing such problems: they 64257;nd a feasible solution quickly and then continually work on improving it until time (predetermined) runs out. ARA*, is an anytime heuristic search, which tunes its performance bound based on the available search time. It starts by 64257;nding a sub-optimal solution quickly using a loose bound, then tightens the bound progressively as time allows. Given enough time it 64257;nds a provably optimal solution. While improving its bound, ARA* reuses previous search efforts and, as a result, is signi64257;cantly more ef64257;cient than other anytime search methods. 3.1 Why the sub-optimal A* Dijkstra s: expands states in the order of f = g values. This leads to huge memory usage and is not applicable for high D problems. A* Search: expands states in the order of f(s) = g(s) + h(s) values. Though this expands to much lesser states it tends to become slow for high D applications. 4

5 Weighted A*: expands states in the order of f = g + εh values, ε1 = bias towards states that are closer to goal. This approach however makes the solution less optimal as ε increases. It trades off optimality for speed. The cost of the optimal solution is usually ε times the suboptimal solution provided by the weighted A*. A more detailed description of the above algorithms is available in the previous class notes. [4] In the above searches particularly the weighted A* several previous search results are similar to future search results as the path is being optimised. Hence we should be able to reuse these results. ARA* is an efficient version of the weighter A* that reuses state values within any search iteration. 3.2 ARA* - Re-use of search results ARA* works by executing A* multiple times, starting with a large ε and decreasing ε prior to each execution until ε = 1. As a result, after each search a solution is guaranteed to be within a factor ε of optimal. Running A* search from scratch every time we decrease ε, however, would be very expensive. ARA* reuses the results of the previous searches to save computation. Figure 3 show the operation of the A* algorithm with a heuristic inflated by ε = 2.5, ε = 1.5, and ε = 1 (no inflation) on a simple grid world. In this example an eight-connected grid is used with black cells being obstacles. S denotes a start state, while G denotes a goal state. The cost of moving from one cell to its neighbor is one. The heuristic is the larger of the x and y distances from the cell to the goal. The cells which were expanded are shown in grey. (A* can stop search as soon as it is about to expand a goal state without actually expanding it. Thus, the goal state is not shown in grey.) The paths found by these searches are shown with grey arrows. The A* searches with inflated heuristics expand substantially fewer cells than A* with ε = 1, but their solution is sub-optimal. Figure 3: Weighted A* searches with decreasing ε [3]. Figure 4 shows how the ARA* search reduces the number of states expanded to in the sub-sequent iterations as it improves the optimality. It uses an ImprovePath function that 5

6 Figure 4: ARA* search iterations for the searches shown in Figure 3 [3]. recomputes a path for a given ε. Then the Main function of ARA* repetitively calls the ImprovePath function with a series of decreasing εs and uses the results of previous searches in all the sub-sequent searches to save computation. 3.3 ARA* Algorithm The algorithm for the ARA* search is divided into two functions. The ImprovePath() function [Algorithm 1] and the Main() function [Algorithm 2]. A detailed explanation for these algorithms is available in the class website [3]. while (f(sgoal) > minimum f-value in OPEN ) do remove s with the smallest [g(s)+ εh(s)] from OPEN; insert s into CLOSED; for every successor s of s do if g(s ) > g(s) + c(s,s ) then g(s ) = g(s) + c(s,s ); if s not in CLOSED then insert s into OPEN; else insert s into INCONS end end end end Algorithm 1: ImprovePath() function 6

7 set ε to large value; g(sstart) = 0; OPEN = {sstart}; while ε 1 do CLOSED = {}; INCONS = {}; ImprovePath(); publish current ε suboptimal solution; decrease ε; initialize OPEN = OPEN U INCONS; end Algorithm 2: Main() function 3.4 Applications: Planning for manipulation ARA*-based motion planning for a single 7DOF arm [Cohen et al., ICRA 10, ICRA 11] The ARA* search can be used to find the optimal path for a 7DOF arm to move from its current state to reach an object in the 3D space [Figure 5]. For this purpose: goal is given as 6D (x,y,z,r,p,y) pose of the end-effector each state is: 4 non-wrist joint angles {q1,... q4} when far away from the goal, all 7 joint angles {q1,... q7} when close to the goal actions are: {moving one joint at a time by fixed ; IK-based motion to snap to the goal when close to it} heuristics are: 3D BFS distances for the object Figure 5: ARA* Search used in planning for a single 7DOF arm for picking a ball. 7

8 3.4.2 ARA*-based motion planning for dual-arm motion [Cohen et al., ICRA 12] The ARA* search is used for co-ordinated motion of two arms on the PR2 to pick a goal object. The following data are used as parameters [Figure 6]: goal is given as 4D (x,y,z,y) pose for the object each state is 6D: 4D (x,y,z,y) pose of the object, {q1,q2} of the elbow angles actions are: changing the 4D pose of the object or q1, q2 heuristics are: 3D BFS distances for the object Figure 6: ARA* Search used in planning dual arm motion. 3.5 Discussion The pros and cons associated with the ARA* search are as listed below: Pros: There is Explicit cost minimization The planning is consistent (similar input generates similar output) Can handle arbitrary goal sets (such as set of grasps from a grasp planner) Many path constraints are easy to implement (eg: upright orientation of gripper) Cons: Requires good graph and heuristic design to plan fast The number of motions from a state affects speed and path quality 8

9 4 Experience Graphs Experience Graphs is a sub-optimal heuristic search with the distinct advantage of learning from it s history planning experiences. Since many tasks in robotics are repetitive, but not exactly the same each time (example: loading dishes into a dishwasher), it is advantageous to re-use prior experiences to speed up planning for subsequent motions. This method is extremely useful in high-dimensional problems like those found in mobile manipulation. 4.1 Planning with E-Graphs The Experience Graph (E-Graph or G E ) plans with specially designed algorithm with a bias toward searching G E as much as possible, rather than searching the entire graph G. This method avoids exploring large portions of the original graph G. Given a problem with an explicitly defined start and goal state (s start, s goal ), the desired path is a path that connects s start to s goal [2]. Shown in Figure 7 is a graph G with obstacles colored in black. Figure 7: This figure shows three images of a graph G overlaid with previous paths (experiences) shown in red, green, and blue. These paths can be combined to create an Experience Graph G E [1]. Previous paths are shown as colored segments which can be put together to create an Experience Graph G E. The compilation of these paths can be seen in Figure 8. This collection of paths becomes a sub-graph of the original graph G. When given a search query, the e uses the previously computed paths to speed up the process of planning the task. The heuristic is stated in equation 1. h E (s 0 ) = min π i=0 N=1 min{ε E h G (s i, s i+1 ), C E (s i, s i+1 )} (1) 9

10 Figure 8: Shown in this figure is the compilation of previously computed path experiences pieced together from those seen in Figure 7 [1]. From equation 1, π is a path s 0...s N 1, and s N 1 = s goal and ε E is a scalar 1. The heuristic in equation 1 guides the search toward expanding states on the E-Graph within sub- optimally bound ε. In the heuristic computation finds a minimum cost path using two kinds of path edges, where ε E h G (s i, s i+1 ) describes traveling off the E-Graph with an inflated heuristic, and C E (s i, s i+1 ) describes traveling of the E-Graph using actual costs. For finding paths for repetitive tasks, this heuristic makes the planning much faster. The planner based on equation 1 guarantees the following theorems [1] : 1. Completeness with respect to the original graph G: For a finite graph G, the planner terminates and finds a path in G that connects s start to s goal if one exists. 2. Bounds on sub-optimality: For a finite graph G, the planner terminates and the solution it returns is guaranteed to be no worse than ε ε E times the optimal solution cost in graph G. It is important to note that these properties hold true even if the quality or placement of the experiences is arbitrarily bad. 4.2 Applications in Mobile Manipulation Experiments using planning with E-Graphs has been shown to decrease planning times dramatically when compared against weighted A*. In the experiments discussed by M. Phillips et. al. [2], a PR2 was used to move objects around a kitchen. The PR2 has 10 degrees of freedom: 3 DOFs for base navigation, 1 DOF for spine, 6s DOF for arms. The 10

11 Figure 9: This figure shows the heuristic search using the E-Graph. C E represents the path solution using actual costs of the previously generated experiences, h G represents the path traveling off the E-Graph using inflated costs [1]. experiment was conducted on 40 goals within the kitchen. The results compared to Weighted A* are shown in table 1. Table 1: This table compares the success rate and planning times for mobile manipulation using Weighted A* and E-Graph. Method Success (of 40) Mean Time (s) Std. Dev. (s) Max (s) E-Graphs Weighted A* The following is a list of Pros and Cons of using E-Graph planning. is Pros Can lead search around local minima (obstacles) Provided paths can have arbitrary quality Can reuse many parts of multiple experiences User can control bound on solution quality Cons Local minima can be created going on to the E-Graph The E-Graph can gro arbitrarily large 11

12 5 Conclusion Heuristic search within sub-optimal bounds can be more suitable for high-dimensional manipulation planning as compared to optimal heuristic planning. Using a sub-optimal approach still provides good cost minimization, consistent behavior and rigorous theoretical success. Because sub-optimal planning dramatically speeds up search planning with more experience, the performance can get better over time with learning. References [1] Mike Phillips (adapted from Maxim Likhachev). Sub-optimal heuristic search and its application to planning for manipulation. courses/16662/notes/discrete-search/heuristic_search.pdf, [2] M. Phillips, B.J. Cohen, S. Chitta, M. Likhachev. E-graphs: Bootstrapping planning with experience graphs. [3] Maxim Likhachev, Geoff Gordon, Sebastian Thrun. ARA*: Anytime A* with Provable Bounds on Sub-Optimality. ara_nips03.pdf, [4] Kavya Suresh Siddhartha Srinivasa and David Matten. Lecture on discrete search algorithms, lecture08 - monday feb-11, courses/16662/notes/discrete-search/16662_lecture08.pdf,

Sub-optimal Heuristic Search and its Application to Planning for Manipulation

Sub-optimal Heuristic Search and its Application to Planning for Manipulation Sub-optimal Heuristic Search and its Application to Planning for Manipulation Mike Phillips Slides adapted from Planning for Mobile Manipulation What planning tasks are there? robotic bartender demo at

More information

Search-based Planning with Motion Primitives. Maxim Likhachev Carnegie Mellon University

Search-based Planning with Motion Primitives. Maxim Likhachev Carnegie Mellon University Search-based Planning with Motion Primitives Maxim Likhachev Carnegie Mellon University generate a graph representation of the planning problem search the graph for a solution What is Search-based Planning

More information

Planning, Execution and Learning Application: Examples of Planning for Mobile Manipulation and Articulated Robots

Planning, Execution and Learning Application: Examples of Planning for Mobile Manipulation and Articulated Robots 15-887 Planning, Execution and Learning Application: Examples of Planning for Mobile Manipulation and Articulated Robots Maxim Likhachev Robotics Institute Carnegie Mellon University Two Examples Planning

More information

Anytime Incremental Planning with E-Graphs

Anytime Incremental Planning with E-Graphs Anytime Incremental Planning with E-Graphs Mike Phillips 1 and Andrew Dornbush 1 and Sachin Chitta 2 and Maxim Likhachev 1 Abstract Robots operating in real world environments need to find motion plans

More information

Computer Game Programming Basic Path Finding

Computer Game Programming Basic Path Finding 15-466 Computer Game Programming Basic Path Finding Robotics Institute Path Planning Sven Path Planning needs to be very fast (especially for games with many characters) needs to generate believable paths

More information

Search-based Planning Library SBPL. Maxim Likhachev Robotics Institute Carnegie Mellon University

Search-based Planning Library SBPL. Maxim Likhachev Robotics Institute Carnegie Mellon University Search-based Planning Library SBPL Maxim Likhachev Robotics Institute Carnegie Mellon University Outline Overview Few SBPL-based planners in details - 3D (x,y,θ) lattice-based planning for navigation (available

More information

Cognitive Robotics Robot Motion Planning Matteo Matteucci

Cognitive Robotics Robot Motion Planning Matteo Matteucci Cognitive Robotics Robot Motion Planning Robot Motion Planning eminently necessary since, by definition, a robot accomplishes tasks by moving in the real world. J.-C. Latombe (1991) Robot Motion Planning

More information

E-Graphs: Bootstrapping Planning with Experience Graphs

E-Graphs: Bootstrapping Planning with Experience Graphs Robotics: Science and Systems 2012 Sydney, NSW, Australia, July 09-13, 2012 E-Graphs: Bootstrapping Planning with Experience Graphs Mike Phillips, Benjamin Cohen, Sachin Chitta, Maxim Likhachev Abstract

More information

Robot Motion Control Matteo Matteucci

Robot Motion Control Matteo Matteucci Robot Motion Control Open loop control A mobile robot is meant to move from one place to another Pre-compute a smooth trajectory based on motion segments (e.g., line and circle segments) from start to

More information

CSE-571. Deterministic Path Planning in Robotics. Maxim Likhachev 1. Motion/Path Planning. Courtesy of Maxim Likhachev University of Pennsylvania

CSE-571. Deterministic Path Planning in Robotics. Maxim Likhachev 1. Motion/Path Planning. Courtesy of Maxim Likhachev University of Pennsylvania Motion/Path Planning CSE-57 Deterministic Path Planning in Robotics Courtesy of Maxim Likhachev University of Pennsylvania Tas k : find a feasible (and cost-minimal) path/motion from the current configuration

More information

Planning with Experience Graphs

Planning with Experience Graphs Planning with Experience Graphs Mike Phillips Carnegie Mellon University Collaborators Benjamin Cohen, Andrew Dornbush, Victor Hwang, Sachin ChiFa, Maxim Likhachev MoHvaHon Many tasks are repehhve. They

More information

Planning, Execution and Learning Heuristics and Multi-Heuristic A*

Planning, Execution and Learning Heuristics and Multi-Heuristic A* 15-887 Planning, Execution and Learning Heuristics and Multi-Heuristic A* Maxim Likhachev Robotics Institute Carnegie Mellon University Design of Informative Heuristics Example problem: move picture frame

More information

Anytime Search in Dynamic Graphs

Anytime Search in Dynamic Graphs Anytime Search in Dynamic Graphs Maxim Likhachev a, Dave Ferguson b,c, Geoff Gordon c, Anthony Stentz c, and Sebastian Thrun d a Computer and Information Science, University of Pennsylvania, Philadelphia,

More information

Anytime search in dynamic graphs

Anytime search in dynamic graphs University of Pennsylvania ScholarlyCommons Lab Papers (GRASP) General Robotics, Automation, Sensing and Perception Laboratory 9-2008 Anytime search in dynamic graphs Maxim Likhachev University of Pennsylvania,

More information

Search-Based Planning with Provable Suboptimality Bounds for Continuous State Spaces

Search-Based Planning with Provable Suboptimality Bounds for Continuous State Spaces Search-Based Planning with Provable Suboptimality Bounds Juan Pablo Gonzalez for Continuous State Spaces Maxim Likhachev Autonomous Perception Research Robotics Institute General Dynamics Robotic Systems

More information

Discrete search algorithms

Discrete search algorithms Robot Autonomy (16-662, S13) Lecture#08 (Monday February 11) Discrete search algorithms Lecturer: Siddhartha Srinivasa Scribes: Kavya Suresh & David Matten I. INTRODUCTION These notes contain a detailed

More information

Humanoid Robotics. Path Planning and Walking. Maren Bennewitz

Humanoid Robotics. Path Planning and Walking. Maren Bennewitz Humanoid Robotics Path Planning and Walking Maren Bennewitz 1 Introduction Given the robot s pose in a model of the environment Compute a path to a target location First: 2D path in a 2D grid map representation

More information

ANA*: Anytime Nonparametric A*

ANA*: Anytime Nonparametric A* ANA*: Anytime Nonparametric A* Jur van den Berg 1 and Rajat Shah 2 and Arthur Huang 2 and Ken Goldberg 2 1 University of North Carolina at Chapel Hill. E-mail: berg@cs.unc.edu. 2 University of California,

More information

Motion Planning for Robotic Manipulators with Independent Wrist Joints

Motion Planning for Robotic Manipulators with Independent Wrist Joints Motion Planning for Robotic Manipulators with Independent Wrist Joints Kalin Gochev Venkatraman Narayanan Benjamin Cohen Alla Safonova Maxim Likhachev Abstract Advanced modern humanoid robots often have

More information

Speeding up heuristic computation in planning with Experience Graphs

Speeding up heuristic computation in planning with Experience Graphs Speeding up heuristic computation in planning with Experience Graphs Mike Phillips 1 and Maxim Likhachev 1 Abstract Experience Graphs have been shown to accelerate motion planning using parts of previous

More information

R* Search. Anthony Stentz The Robotics Institute Carnegie Mellon University Pittsburgh, PA

R* Search. Anthony Stentz The Robotics Institute Carnegie Mellon University Pittsburgh, PA R* Search Maxim Likhachev Computer and Information Science University of Pennsylvania Philadelphia, PA 19104 maximl@seas.upenn.edu Anthony Stentz The Robotics Institute Carnegie Mellon University Pittsburgh,

More information

Trajectory Optimization

Trajectory Optimization Trajectory Optimization Jane Li Assistant Professor Mechanical Engineering & Robotics Engineering http://users.wpi.edu/~zli11 Recap We heard about RRT*, a sampling-based planning in high-dimensional cost

More information

Learning to Plan for Constrained Manipulation from Demonstrations

Learning to Plan for Constrained Manipulation from Demonstrations Learning to Plan for Constrained Manipulation from Demonstrations Mike Phillips mlphilli@andrew.cmu.edu Carnegie Mellon University Victor Hwang vchwang@andrew.cmu.edu Carnegie Mellon University Sachin

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

Planning Techniques for Robotics Search Algorithms: Multi-goal A*, IDA*

Planning Techniques for Robotics Search Algorithms: Multi-goal A*, IDA* 6-350 Planning Techniques for Robotics Search Algorithms: Multi-goal A*, IDA* Maxim Likhachev Robotics Institute Agenda A* with multiple goals Iterative Deepening A* (IDA*) 2 Support for Multiple Goal

More information

Visual Navigation for Flying Robots. Motion Planning

Visual Navigation for Flying Robots. Motion Planning Computer Vision Group Prof. Daniel Cremers Visual Navigation for Flying Robots Motion Planning Dr. Jürgen Sturm Motivation: Flying Through Forests 3 1 2 Visual Navigation for Flying Robots 2 Motion Planning

More information

Planning & Decision-making in Robotics Case Study: Planning for Autonomous Driving

Planning & Decision-making in Robotics Case Study: Planning for Autonomous Driving 16-782 Planning & Decision-making in Robotics Case Study: Planning for Autonomous Driving Maxim Likhachev Robotics Institute Carnegie Mellon University Typical Planning Architecture for Autonomous Vehicle

More information

Discrete Motion Planning

Discrete Motion Planning RBE MOTION PLANNING Discrete Motion Planning Jane Li Assistant Professor Mechanical Engineering & Robotics Engineering http://users.wpi.edu/~zli11 Announcement Homework 1 is out Due Date - Feb 1 Updated

More information

ANA*: Anytime Nonparametric A*

ANA*: Anytime Nonparametric A* ANA*: Anytime Nonparametric A* Jur van den Berg 1 and Rajat Shah 2 and Arthur Huang 2 and Ken Goldberg 2 1 University of North Carolina at Chapel Hill. E-mail: berg@cs.unc.edu. 2 University of California,

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

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

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

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 A search-algorithm prioritizes and expands the nodes in its open list items by

More information

Approximate path planning. Computational Geometry csci3250 Laura Toma Bowdoin College

Approximate path planning. Computational Geometry csci3250 Laura Toma Bowdoin College Approximate path planning Computational Geometry csci3250 Laura Toma Bowdoin College Outline Path planning Combinatorial Approximate Combinatorial path planning Idea: Compute free C-space combinatorially

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

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) Compare the testing methods for testing path segment and finding first

More information

Path Planning With Adaptive Dimensionality

Path Planning With Adaptive Dimensionality University of Pennsylvania ScholarlyCommons Center for Human Modeling and Simulation Department of Computer & Information Science 2011 Path Planning With Adaptive Dimensionality Kalin Gochev University

More information

Humanoid Robotics. Inverse Kinematics and Whole-Body Motion Planning. Maren Bennewitz

Humanoid Robotics. Inverse Kinematics and Whole-Body Motion Planning. Maren Bennewitz Humanoid Robotics Inverse Kinematics and Whole-Body Motion Planning Maren Bennewitz 1 Motivation Plan a sequence of configurations (vector of joint angle values) that let the robot move from its current

More information

Humanoid Robotics. Inverse Kinematics and Whole-Body Motion Planning. Maren Bennewitz

Humanoid Robotics. Inverse Kinematics and Whole-Body Motion Planning. Maren Bennewitz Humanoid Robotics Inverse Kinematics and Whole-Body Motion Planning Maren Bennewitz 1 Motivation Planning for object manipulation Whole-body motion to reach a desired goal configuration Generate a sequence

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

Introduction to Information Science and Technology (IST) Part IV: Intelligent Machines and Robotics Planning

Introduction to Information Science and Technology (IST) Part IV: Intelligent Machines and Robotics Planning Introduction to Information Science and Technology (IST) Part IV: Intelligent Machines and Robotics Planning Sören Schwertfeger / 师泽仁 ShanghaiTech University ShanghaiTech University - SIST - 10.05.2017

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

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

15-494/694: Cognitive Robotics

15-494/694: Cognitive Robotics 15-494/694: Cognitive Robotics Dave Touretzky Lecture 9: Path Planning with Rapidly-exploring Random Trees Navigating with the Pilot Image from http://www.futuristgerd.com/2015/09/10 Outline How is path

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

Planning & Decision-making in Robotics Planning Representations/Search Algorithms: RRT, RRT-Connect, RRT*

Planning & Decision-making in Robotics Planning Representations/Search Algorithms: RRT, RRT-Connect, RRT* 16-782 Planning & Decision-making in Robotics Planning Representations/Search Algorithms: RRT, RRT-Connect, RRT* Maxim Likhachev Robotics Institute Carnegie Mellon University Probabilistic Roadmaps (PRMs)

More information

Experience Graphs: Leveraging Experience in Planning

Experience Graphs: Leveraging Experience in Planning Carnegie Mellon University Research Showcase @ CMU Dissertations Theses and Dissertations Spring 5-2015 Experience Graphs: Leveraging Experience in Planning Michael Phillips Carnegie Mellon University

More information

Anytime Path Planning and Replanning in Dynamic Environments

Anytime Path Planning and Replanning in Dynamic Environments Anytime Path Planning and Replanning in Dynamic Environments Jur van den Berg Department of Information and Computing Sciences Universiteit Utrecht The Netherlands berg@cs.uu.nl Dave Ferguson and James

More information

Planning in Domains with Cost Function Dependent Actions

Planning in Domains with Cost Function Dependent Actions Planning in Domains with Cost Function Dependent Actions Mike Phillips and Maxim Likhachev mlphilli@andrew.cmu.edu, maxim@cs.cmu.edu Carnegie Mellon University Content Area Constraints, Satisfiability,

More information

Anytime Tree-Restoring Weighted A* Graph Search

Anytime Tree-Restoring Weighted A* Graph Search Proceedings of the Seventh Annual Symposium on Combinatorial Search (SoCS 2014) Anytime Tree-Restoring Weighted A* Graph Search Kalin Gochev University of Pennsylvania Alla Safonova University of Pennsylvania

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

Graph-based Planning Using Local Information for Unknown Outdoor Environments

Graph-based Planning Using Local Information for Unknown Outdoor Environments Graph-based Planning Using Local Information for Unknown Outdoor Environments Jinhan Lee, Roozbeh Mottaghi, Charles Pippin and Tucker Balch {jinhlee, roozbehm, cepippin, tucker}@cc.gatech.edu Center for

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

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

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

More information

Navigation in Three-Dimensional Cluttered Environments for Mobile Manipulation

Navigation in Three-Dimensional Cluttered Environments for Mobile Manipulation Navigation in Three-Dimensional Cluttered Environments for Mobile Manipulation Armin Hornung Mike Phillips E. Gil Jones Maren Bennewitz Maxim Likhachev Sachin Chitta Abstract Collision-free navigation

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

Dynamic Multi-Heuristic A*

Dynamic Multi-Heuristic A* Dynamic Multi-Heuristic A* Fahad Islam, Venkatraman Narayanan and Maxim Likhachev Abstract Many motion planning problems in robotics are high dimensional planning problems. While sampling-based motion

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

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

Planning for Markov Decision Processes with Sparse Stochasticity

Planning for Markov Decision Processes with Sparse Stochasticity Planning for Markov Decision Processes with Sparse Stochasticity Maxim Likhachev Geoff Gordon Sebastian Thrun School of Computer Science School of Computer Science Dept. of Computer Science Carnegie Mellon

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

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

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

Experience Guided Mobile Manipulation Planning

Experience Guided Mobile Manipulation Planning Experience Guided Mobile Manipulation Planning Tekin Meriçli 1 and Manuela Veloso 2 and H. Levent Akın 1 {tekin.mericli,akin}@boun.edu.tr,veloso@cmu.edu 1 Department of Computer Engineering, Boğaziçi University,

More information

Space Robot Path Planning for Collision Avoidance

Space Robot Path Planning for Collision Avoidance Space Robot Path Planning for ollision voidance Yuya Yanoshita and Shinichi Tsuda bstract This paper deals with a path planning of space robot which includes a collision avoidance algorithm. For the future

More information

Reinforcement Learning for Appearance Based Visual Servoing in Robotic Manipulation

Reinforcement Learning for Appearance Based Visual Servoing in Robotic Manipulation Reinforcement Learning for Appearance Based Visual Servoing in Robotic Manipulation UMAR KHAN, LIAQUAT ALI KHAN, S. ZAHID HUSSAIN Department of Mechatronics Engineering AIR University E-9, Islamabad PAKISTAN

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

Lecture 18 Kinematic Chains

Lecture 18 Kinematic Chains CS 598: Topics in AI - Adv. Computational Foundations of Robotics Spring 2017, Rutgers University Lecture 18 Kinematic Chains Instructor: Jingjin Yu Outline What are kinematic chains? C-space for kinematic

More information

Inverse Kinematics Analysis for Manipulator Robot With Wrist Offset Based On the Closed-Form Algorithm

Inverse Kinematics Analysis for Manipulator Robot With Wrist Offset Based On the Closed-Form Algorithm Inverse Kinematics Analysis for Manipulator Robot With Wrist Offset Based On the Closed-Form Algorithm Mohammed Z. Al-Faiz,MIEEE Computer Engineering Dept. Nahrain University Baghdad, Iraq Mohammed S.Saleh

More information

Factor-Guided Motion Planning for a Robot Arm

Factor-Guided Motion Planning for a Robot Arm Factor-Guided Motion Planning for a Robot Arm Jaesik Choi and Eyal Amir Computer Science Department University of Illinois at Urbana-Champaign Urbana, IL 61801 {choi31,eyal}@cs.uiuc.edu Abstract Motion

More information

Humanoid Robots Exercise Sheet 9 - Inverse reachability maps (IRM) and statistical testing

Humanoid Robots Exercise Sheet 9 - Inverse reachability maps (IRM) and statistical testing Prof. Dr. Maren Bennewitz M.Sc. Stefan Oßwald M.Sc. AbdElMoniem Bayoumi Bonn, 2 July 2015 Humanoid Robots Exercise Sheet 9 - Inverse reachability maps (IRM) and statistical testing Exercise 17 In this

More information

Planning Techniques for Robotics Planning Representations: Skeletonization- and Grid-based Graphs

Planning Techniques for Robotics Planning Representations: Skeletonization- and Grid-based Graphs 16-350 Planning Techniques for Robotics Planning Representations: Skeletonization- and Grid-based Graphs Maxim Likhachev Robotics Institute 2D Planning for Omnidirectional Point Robot Planning for omnidirectional

More information

Robotics Tasks. CS 188: Artificial Intelligence Spring Manipulator Robots. Mobile Robots. Degrees of Freedom. Sensors and Effectors

Robotics Tasks. CS 188: Artificial Intelligence Spring Manipulator Robots. Mobile Robots. Degrees of Freedom. Sensors and Effectors CS 188: Artificial Intelligence Spring 2006 Lecture 5: Robot Motion Planning 1/31/2006 Dan Klein UC Berkeley Many slides from either Stuart Russell or Andrew Moore Motion planning (today) How to move from

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

Optimization of a two-link Robotic Manipulator

Optimization of a two-link Robotic Manipulator Optimization of a two-link Robotic Manipulator Zachary Renwick, Yalım Yıldırım April 22, 2016 Abstract Although robots are used in many processes in research and industry, they are generally not customized

More information

Integer Programming Theory

Integer Programming Theory Integer Programming Theory Laura Galli October 24, 2016 In the following we assume all functions are linear, hence we often drop the term linear. In discrete optimization, we seek to find a solution x

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

Anytime, Dynamic Planning in High-dimensional Search Spaces

Anytime, Dynamic Planning in High-dimensional Search Spaces 2007 IEEE International Conference on Robotics and Automation Roma, Italy, 10-14 April 2007 WeD11.2 Anytime, Dynamic Planning in High-dimensional Search Spaces Dave Ferguson Intel Research Pittsburgh 4720

More information

Path Planning in Dynamic Environments with Adaptive Dimensionality

Path Planning in Dynamic Environments with Adaptive Dimensionality Proceedings of the Ninth International Symposium on Combinatorial Search (SoCS 2016) Path Planning in Dynamic Environments with Adaptive Dimensionality Anirudh Vemula, Katharina Muelling, and Jean Oh Robotics

More information

Human Augmentation in Teleoperation of Arm Manipulators in an Environment with Obstacles

Human Augmentation in Teleoperation of Arm Manipulators in an Environment with Obstacles Human Augmentation in Teleoperation of Arm Manipulators in an Environment with Obstacles I. Ivanisevic and V. Lumelsky Robotics Lab, University of Wisconsin-Madison Madison, Wisconsin 53706, USA iigor@cs.wisc.edu

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

Motion Planning. Howie CHoset

Motion Planning. Howie CHoset Motion Planning Howie CHoset What is Motion Planning? What is Motion Planning? Determining where to go Overview The Basics Motion Planning Statement The World and Robot Configuration Space Metrics Algorithms

More information

Visualization and Analysis of Inverse Kinematics Algorithms Using Performance Metric Maps

Visualization and Analysis of Inverse Kinematics Algorithms Using Performance Metric Maps Visualization and Analysis of Inverse Kinematics Algorithms Using Performance Metric Maps Oliver Cardwell, Ramakrishnan Mukundan Department of Computer Science and Software Engineering University of Canterbury

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

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

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

Manipulator trajectory planning

Manipulator trajectory planning Manipulator trajectory planning Václav Hlaváč Czech Technical University in Prague Faculty of Electrical Engineering Department of Cybernetics Czech Republic http://cmp.felk.cvut.cz/~hlavac Courtesy to

More information

CS283: Robotics Fall 2016: Robot Arms

CS283: Robotics Fall 2016: Robot Arms CS83: Fall 016: Robot Arms Sören Schwertfeger / 师泽仁 ShanghaiTech University ShanghaiTech University - SIST - 0.11.016 REVIEW ShanghaiTech University - SIST - 0.11.016 3 General Control Scheme for Mobile

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

Planning, Execution and Learning Application: Examples of Planning in Perception

Planning, Execution and Learning Application: Examples of Planning in Perception 15-887 Planning, Execution and Learning Application: Examples of Planning in Perception Maxim Likhachev Robotics Institute Carnegie Mellon University Two Examples Graph search for perception Planning for

More information

Lecture Note 2: Configuration Space

Lecture Note 2: Configuration Space ECE5463: Introduction to Robotics Lecture Note 2: Configuration Space Prof. Wei Zhang Department of Electrical and Computer Engineering Ohio State University Columbus, Ohio, USA Spring 2018 Lecture 2 (ECE5463

More information

z θ 1 l 2 θ 2 l 1 l 3 θ 3 θ 4 θ 5 θ 6

z θ 1 l 2 θ 2 l 1 l 3 θ 3 θ 4 θ 5 θ 6 Human Augmentation in Teleoperation of Arm Manipulators in an Environment with Obstacles Λ I. Ivanisevic and V. Lumelsky Robotics Lab, University of Wisconsin-Madison Madison, Wisconsin 53706, USA iigor@cs.wisc.edu

More information

Anytime RRTs. Dave Ferguson and Anthony Stentz Robotics Institute Carnegie Mellon University Pittsburgh, Pennsylvania

Anytime RRTs. Dave Ferguson and Anthony Stentz Robotics Institute Carnegie Mellon University Pittsburgh, Pennsylvania Proceedings of the 2006 IEEE/RSJ International Conference on Intelligent Robots and Systems October 9-15, 2006, Beijing, China Anytime RRTs Dave Ferguson and Anthony Stentz Robotics Institute Carnegie

More information

Planning and Control: Markov Decision Processes

Planning and Control: Markov Decision Processes CSE-571 AI-based Mobile Robotics Planning and Control: Markov Decision Processes Planning Static vs. Dynamic Predictable vs. Unpredictable Fully vs. Partially Observable Perfect vs. Noisy Environment What

More information

NERC Gazebo simulation implementation

NERC Gazebo simulation implementation NERC 2015 - Gazebo simulation implementation Hannan Ejaz Keen, Adil Mumtaz Department of Electrical Engineering SBA School of Science & Engineering, LUMS, Pakistan {14060016, 14060037}@lums.edu.pk ABSTRACT

More information

Homework #3 (Search) Out: 1/24/11 Due: 2/1/11 (at noon)

Homework #3 (Search) Out: 1/24/11 Due: 2/1/11 (at noon) CS121 Introduction to Artificial Intelligence Winter 2011 Homework #3 (Search) Out: 1/24/11 Due: 2/1/11 (at noon) How to complete this HW: First copy this file; then type your answers in the file immediately

More information

Efficient Motion and Grasp Planning for Humanoid Robots

Efficient Motion and Grasp Planning for Humanoid Robots Efficient Motion and Grasp Planning for Humanoid Robots Nikolaus Vahrenkamp and Tamim Asfour and Rüdiger Dillmann Abstract The control system of a robot operating in a human-centered environments should

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

Ian Mitchell. Department of Computer Science The University of British Columbia

Ian Mitchell. Department of Computer Science The University of British Columbia CPSC 542D: Level Set Methods Dynamic Implicit Surfaces and the Hamilton-Jacobi Equation or What Water Simulation, Robot Path Planning and Aircraft Collision Avoidance Have in Common Ian Mitchell Department

More information

Search : Lecture 2. September 9, 2003

Search : Lecture 2. September 9, 2003 Search 6.825: Lecture 2 September 9, 2003 1 Problem-Solving Problems When your environment can be effectively modeled as having discrete states and actions deterministic, known world dynamics known initial

More information