Introduction to Robotics

Similar documents
Advanced Robotics Path Planning & Navigation

Master s Thesis: Real-Time Object Shape Perception via Force/Torque Sensor

Geometric Path Planning McGill COMP 765 Oct 12 th, 2017

Robot Motion Planning

MEV 442: Introduction to Robotics - Module 3 INTRODUCTION TO ROBOT PATH PLANNING

Comparative Study of Potential Field and Sampling Algorithms for Manipulator Obstacle Avoidance

Sung-Eui Yoon ( 윤성의 )

Spring 2010: Lecture 9. Ashutosh Saxena. Ashutosh Saxena

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

Path Planning for Point Robots. NUS CS 5247 David Hsu

Advanced Robotics Path Planning & Navigation

Probabilistic Methods for Kinodynamic Path Planning

3D Collision Avoidance for Navigation in Unstructured Environments

A Reduced-Order Analytical Solution to Mobile Robot Trajectory Generation in the Presence of Moving Obstacles

Robot Motion Planning

Motion Planning of Multiple Mobile Robots for Cooperative Manipulation and Transportation

Planning: Part 1 Classical Planning

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

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

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

Mobile robots control architectures

Advanced path planning. ROS RoboCup Rescue Summer School 2012

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

Planning in Mobile Robotics

Probabilistic Motion Planning: Algorithms and Applications

Unit 5: Part 1 Planning

Sampling-Based Motion Planning

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

CS 4649/7649 Robot Intelligence: Planning

Configuration Space of a Robot

Introduction to Mobile Robotics Path Planning and Collision Avoidance. Wolfram Burgard, Maren Bennewitz, Diego Tipaldi, Luciano Spinello

Shorter, Smaller, Tighter Old and New Challenges

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

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

Performance study of single-query motion planning for grasp execution using various manipulators

Introduction to Robotics

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

Visual Navigation for Flying Robots. Motion Planning

Dependency Tracking for Fast Marching. Dynamic Replanning for Ground Vehicles

CS Path Planning

Instant Prediction for Reactive Motions with Planning

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

Robot Motion Control Matteo Matteucci

Specialized PRM Trajectory Planning For Hyper-Redundant Robot Manipulators

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

Trajectory Optimization

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

Humanoid Robotics. Path Planning and Walking. Maren Bennewitz

Introduction to Mobile Robotics Path Planning and Collision Avoidance

Balancing Exploration and Exploitation in Motion Planning

Elastic Bands: Connecting Path Planning and Control

Collision-Aware Assembly Planning

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

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

Can work in a group of at most 3 students.! Can work individually! If you work in a group of 2 or 3 students,!

Decomposition-based Motion Planning: Towards Real-time Planning for Robots with Many Degrees of Freedom. Abstract

Safe Prediction-Based Local Path Planning using Obstacle Probability Sections

Local Search Methods. CS 188: Artificial Intelligence Fall Announcements. Hill Climbing. Hill Climbing Diagram. Today

Super Assembling Arms

MOBILE ROBOTS NAVIGATION, MAPPING & LOCALIZATION: PART I

Autonomous and Mobile Robotics. Whole-body motion planning for humanoid robots (Slides prepared by Marco Cognetti) Prof.

Announcements. CS 188: Artificial Intelligence Fall Robot motion planning! Today. Robotics Tasks. Mobile Robots

CS 188: Artificial Intelligence Fall Announcements

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

PRM path planning optimization algorithm research

Providing Haptic Hints to Automatic Motion Planners

Motion Planning for Robot Manipulators

PATH PLANNING IMPLEMENTATION USING MATLAB

Basic Motion Planning Algorithms

Motion planning is a branch of computer science concentrating upon the computation of

To Do. History of Computer Animation. These Lectures. 2D and 3D Animation. Computer Animation. Foundations of Computer Graphics (Spring 2010)

Spring 2016 :: :: Robot Autonomy :: Team 7 Motion Planning for Autonomous All-Terrain Vehicle

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

Robot Motion Planning and (a little) Computational Geometry

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

Introduction to Autonomous Mobile Robots

Autonomous Mobile Robots, Chapter 6 Planning and Navigation Where am I going? How do I get there? Localization. Cognition. Real World Environment

Probabilistic roadmaps for efficient path planning

Path Planning. Marcello Restelli. Dipartimento di Elettronica e Informazione Politecnico di Milano tel:

Manipulator trajectory planning

A 2-Stages Locomotion Planner for Digital Actors

Inverse Kinematics. Given a desired position (p) & orientation (R) of the end-effector

Path-Planning for Multiple Generic-Shaped Mobile Robots with MCA

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

Improving Robot Path Planning Efficiency with Probabilistic Virtual Environment Models

Lecture VI: Constraints and Controllers. Parts Based on Erin Catto s Box2D Tutorial

SPATIAL GUIDANCE TO RRT PLANNER USING CELL-DECOMPOSITION ALGORITHM

Roadmaps. Vertex Visibility Graph. Reduced visibility graph, i.e., not including segments that extend into obstacles on either side.

Sampling-based Planning 2

Predicting Protein Folding Paths. S.Will, , Fall 2011

Towards an Integrated System Model for Testing and Verification

for Motion Planning RSS Lecture 10 Prof. Seth Teller

Final Exam Practice Fall Semester, 2012

Path Planning using Probabilistic Cell Decomposition FRANK LINGELBACH

Navigation and Metric Path Planning

Computer Game Programming Basic Path Finding

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

Agent Based Intersection Traffic Simulation

Real-time Reach Planning for Animated Characters Using Hardware Acceleration

Part I Part 1 Sampling-based Motion Planning

Transcription:

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

Task-level Programming and Path Planning Outline Task-level Programming and Path Planning Potential Field Method Probabilistic Approaches Application fields Extension of Basic Problem Summary Practical Example: Path Planning with MoveIt J. Zhang 2

Task-level Programming and Path Planning - Potential Field Method Potential field method: Definition The manipulator moves in a field of forces. The position to be reached is an attracting pole for the end effector and obstacles are repulsive surfaces for the manipulator parts.(khatib 86) J. Zhang 3

Task-level Programming and Path Planning - Potential Field Method Potential field method: basic ideas The potential field method was initially developed for real-time collision avoidance. A potential field associates a scalar value to every point in a space. An ideal field used for navigation should.. be smooth, have only one global minimum, and the values should approach infinite near obstacles. The force applied to the robot is the negative gradient of the potential field. The robot moves along this force. A function is defined for the free space, that has a global minimum at the goal configuration. The motion happens according to the direction of the gradient. J. Zhang 4

Task-level Programming and Path Planning - Potential Field Method Potential field method: basic idea J. Zhang 5

Task-level Programming and Path Planning - Potential Field Method Potential field method: basic idea The attracting force (of the goal): F Goal (x) = κ ρ (x x goal ) where κ ρ is a gain factor, and (x x goal ) is the distance between the current position and the goal position. The potential field (of obstacles): { 1 2 U(x) = η( 1 ρ(x) 1 ρ 0 ) 2 if ρ(x) ρ 0 0 else where ρ is the shortest distance to the obstacle O and ρ 0 is a threshold defining the region of influence of an obstacle. J. Zhang 6

Task-level Programming and Path Planning - Potential Field Method Potential field method: basic idea The repulsive force: η( F Obstacle (x) = 1 ρ(x) 1 ρ 0 ) 1 dρ(x) ρ(x) if ρ(x) ρ 2 0 dx 0 ifρ(x) > ρ 0 where dρ(x) is the partial derivative vector of the distance from the point dx to the obstacle. This way, the direction of the force vector is expressed. (Khatib 86) J. Zhang 7

Task-level Programming and Path Planning - Potential Field Method Potential field method: Advantages and Disadvantages Advantages: Usage of heuristics real-time capable Two basic disadvantages: It can not be guaranteed, that an existing solution can be found or that calculation terminates if no solution exists no further constraints can be considered J. Zhang 8

Task-level Programming and Path Planning - Potential Field Method Potential field method: local minima J. Zhang 9

Task-level Programming and Path Planning - Probabilistic Approaches Probabilistic Approaches There is demand for an efficient, i.e. fast, robust, easy to implement framework to plan robot motion supporting a high number of degrees of freedom. Ideas: 1. random samples in the region of interest 2. test the samples for collisions 3. connect samples using simple trajectories 4. search in the resulting graph Motivation: Collision Detection and distance estimation are faster than the generation of an explicit representation of free space. : Probabilistic Roadmaps (Barraquand, Kavraki & Latombe) J. Zhang 10

Task-level Programming and Path Planning - Probabilistic Approaches Milestones and Roadmaps - I J. Zhang 11

Task-level Programming and Path Planning - Probabilistic Approaches Milestones and Roadmaps - II J. Zhang 12

Task-level Programming and Path Planning - Probabilistic Approaches Milestones and Roadmaps - III J. Zhang 13

Task-level Programming and Path Planning - Probabilistic Approaches Milestones and Roadmaps - IV J. Zhang 14

Task-level Programming and Path Planning - Probabilistic Approaches Milestones and Roadmaps - V J. Zhang 15

Task-level Programming and Path Planning - Probabilistic Approaches Milestones and Roadmaps - VI J. Zhang 16

Task-level Programming and Path Planning - Probabilistic Approaches Parallels to the Art-Gallery-Problem J. Zhang 17

In an expansive free space: Prob[miss] exp( N) where N: the number of milestones J. Zhang 18 Universität Hamburg Task-level Programming and Path Planning - Probabilistic Approaches Process of taking Samples

Task-level Programming and Path Planning - Probabilistic Approaches Strategies of Taking Samples 99% of the time of a probabilistic Roadmap planner is used for collision checks. Can an intelligent strategy reduce the size of the map and accordingly the time for collision checks? uniform multi-level (coarse to fine) obstacle-aware (shift colliding sample to free space) lazy collision checks probabilistic default values J. Zhang 19

Task-level Programming and Path Planning - Probabilistic Approaches Successful 6D plan for narrow passages J. Zhang 20

Task-level Programming and Path Planning - Probabilistic Approaches Planing Results for a multi-joint artifact J. Zhang 21

Task-level Programming and Path Planning - Probabilistic Approaches Conclusion for Probabilistic Approaches Disadvantages: not complete no strict termination criteria, if no solution can be found completeness only in a probabilistical way (an existing solution will be found sometime...) no insight in the planning process Advantages easy to implement fast, scalable for problems with multiple degrees of freedom J. Zhang 22

Task-level Programming and Path Planning - Application fields Application fields Production: Robot Programming, Assembly, Layout Planning Sequence generation for maintenance tasks autonomous mobile robots graphical animations motion planning for medical appliances simulation of realistic paths of cells and molecules... J. Zhang 23

Task-level Programming and Path Planning - Application fields Application: Assembly Planning Using a path planner, the complexity of a product can be assessed. The assembly-process can be planned. J. Zhang 24

Task-level Programming and Path Planning - Application fields Application: Assembly Planning J. Zhang 25

Task-level Programming and Path Planning - Application fields Application: Layout Planning Path planning combined with optimization methods generate optimal positioning of robots and other equipment in a work cell. J. Zhang 26

Task-level Programming and Path Planning - Application fields Application: Humanoid J. Zhang 27

Task-level Programming and Path Planning - Application fields Application: Engine Maintenance A path planner can be used to automatically check the disassembly methods of parts. This way the products can be easier maintained and repaired. J. Zhang 28

Task-level Programming and Path Planning - Application fields Animation for Task Oriented Programming J. Zhang 29

Task-level Programming and Path Planning - Application fields Application: Animation for Manipulation Scripts J. Zhang 30

Task-level Programming and Path Planning - Application fields Application: Animation for Simulation J. Zhang 31

Task-level Programming and Path Planning - Application fields Application: Planning of Radiotherapy J. Zhang 32

Task-level Programming and Path Planning - Application fields Application: Generation of Docking Motion of Molecules J. Zhang 33

Task-level Programming and Path Planning - Extension of Basic Problem Application: Generation of Docking Motion of Molecules moving obstacles multiple moving objects objects with deformable shape unspecified goals non holonomic constraints dynamical constraints planning for optimal time fuzzy sensing and plan execution highly complex artifacts J. Zhang 34

Task-level Programming and Path Planning - Extension of Basic Problem New Application: Protein Folding Handling of over 1000 degrees of freedom: J. Zhang 35

Task-level Programming and Path Planning - Extension of Basic Problem Planning of Minimal Invasive Surgery for soft objects J. Zhang 36

Task-level Programming and Path Planning - Extension of Basic Problem Autonomous Virtual Actors J. Zhang 37

Task-level Programming and Path Planning - Summary Summary The explicit representation of configuration space yields a complete solution if the resolution is high enough, but the applicability is limited. The distributed probabilistic approach is useful for a large number of degrees of freedom. Path planning comes from the field of robotics, but it is widely used in many different applications: manufacturing, virtual reality, animation, video-games, biology, chemistry, ect. Simulated environments fulfill the preferences of geometrical path planning: known models of the environment, specified start- and goal-configurations and ideal execution. The increasing computation power allows realtime-applications. J. Zhang 38

Task-level Programming and Path Planning - Summary Summary Real robots have to face many uncertainties in the environment. The extension of the base problem requires additional research. Embedded Systems (of the robots) will get more and more powerful. Modeling and calculation of motion of intelligent devices will open up new fields of research. J. Zhang 39

Task-level Programming and Path Planning - Practical Example: Path Planning with MoveIt The Kinova Jaco Arm Path planning is shown for the Kinova Jaco Arm: 6 degrees of freedom carbon fiber structure total weight: 5Kg reach : 90cm J. Zhang 40

Task-level Programming and Path Planning - Practical Example: Path Planning with MoveIt The Kinova Jaco Arm Maximum Load : 1.5kg at mid-range/1.0kg at end-range Maximum linear arm speed : 15cm/sec 3 fingers or 2 fingers utilization Finger force limited to 7N J. Zhang 41

Task-level Programming and Path Planning - Practical Example: Path Planning with MoveIt The Open Motion Planning Library (OMPL) library of sampling-based motion planning algorithms integrated in ROS arm navigation stack (used on the PR2) integrated in (new) MoveIt! project includes state-of-the-art motion planning algorithms no collision checking demo videos at http://ompl.kavrakilab.org/gallery.html tutorials on how to integrate OMPL at http: //www.ros.org/wiki/ompl_ros_interface/tutorials J. Zhang 42

Task-level Programming and Path Planning - Practical Example: Path Planning with MoveIt MoveIt! - A Planning Framework includes kinematics, dynamics, collision checking, constraints evaluation, visualization.. centered around planning and execution motion plans for different robots Tools include: specification of motion plans, configuration and debugging tools, visualization, benchmarking Overview at http://moveit.ros.org J. Zhang 43

Task-level Programming and Path Planning - Practical Example: Path Planning with MoveIt MoveIt! - A Planning Framework J. Zhang 44

Task-level Programming and Path Planning - Practical Example: Path Planning with MoveIt MoveIt! - A Planning Framework More in the video. J. Zhang 45