Rigid Body Transformations

Similar documents
F1/10 th Autonomous Racing. Localization. Nischal K N

CS 309: Autonomous Intelligent Robotics FRI I. Lecture 18: Coordinate Frames TF2 Alvar. Instructor: Justin Hart

Robot Programming with Lisp

EECS 4330/7330 Introduction to Mechatronics and Robotic Vision, Fall Lab 5. Controlling Puma Using Leap Motion Device

MTRX4700 Experimental Robotics

Development of intelligent systems

Exam in DD2426 Robotics and Autonomous Systems

Localization, Where am I?

ROS navigation stack Costmaps Localization Sending goal commands (from rviz) (C)2016 Roi Yehoshua

ROBOT NAVIGATION ROBOTICS

RoboCup Rescue Summer School Navigation Tutorial

Localization and Map Building

Humanoid Robotics. Monte Carlo Localization. Maren Bennewitz

Investigating Simultaneous Localization and Mapping for AGV systems

CALCULATING TRANSFORMATIONS OF KINEMATIC CHAINS USING HOMOGENEOUS COORDINATES

ME 597/747 Autonomous Mobile Robots. Mid Term Exam. Duration: 2 hour Total Marks: 100

Coordinate Frames and Transforms

LOAM: LiDAR Odometry and Mapping in Real Time

EEE 187: Robotics Summary 2

TF (transform) in ROS

ROS-Industrial Basic Developer s Training Class. Southwest Research Institute

Introduction to Mobile Robotics

EE-565-Lab2. Dr. Ahmad Kamal Nasir

ICRA 2016 Tutorial on SLAM. Graph-Based SLAM and Sparsity. Cyrill Stachniss

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

Practical Course WS12/13 Introduction to Monte Carlo Localization

Least Squares and SLAM Pose-SLAM

CS283: Robotics Fall 2016: Sensors

Localization, Mapping and Exploration with Multiple Robots. Dr. Daisy Tang

Basics of Localization, Mapping and SLAM. Jari Saarinen Aalto University Department of Automation and systems Technology

tf: On the PR2 ROS + PR2 Training Workshop

Mapping and Navigation

Individual Lab Report #6. Pratik Chatrath. Team A / Team Avengers. Teammates: Tushar Agrawal, Sean Bryan. January 28, 2016

Nonlinear State Estimation for Robotics and Computer Vision Applications: An Overview

Robotics. Lecture 5: Monte Carlo Localisation. See course website for up to date information.

Teaching Assistant: Roi Yehoshua

Robot Mapping. Least Squares Approach to SLAM. Cyrill Stachniss

Graphbased. Kalman filter. Particle filter. Three Main SLAM Paradigms. Robot Mapping. Least Squares Approach to SLAM. Least Squares in General

MTRX4700: Experimental Robotics

Advanced Techniques for Mobile Robotics Graph-based SLAM using Least Squares. Wolfram Burgard, Cyrill Stachniss, Kai Arras, Maren Bennewitz

COMP30019 Graphics and Interaction Three-dimensional transformation geometry and perspective

Humanoid Robotics. Least Squares. Maren Bennewitz

Laser, Kinect, Gmapping, Localization, PathPlanning

METR 4202: Advanced Control & Robotics

MCE/EEC 647/747: Robot Dynamics and Control. Lecture 3: Forward and Inverse Kinematics

Simultaneous Localization and Mapping (SLAM)

The Kinematic Chain or Tree can be represented by a graph of links connected though joints between each Link and other links.

Simultaneous local and global state estimation for robotic navigation

Kinematics, Kinematics Chains CS 685

Vision-based Mobile Robot Localization and Mapping using Scale-Invariant Features

Programming for Robotics Introduction to ROS

Lecture 14: Basic Multi-View Geometry

Graphics and Interaction Transformation geometry and homogeneous coordinates

COMP30019 Graphics and Interaction Transformation geometry and homogeneous coordinates

Overview. EECS 124, UC Berkeley, Spring 2008 Lecture 23: Localization and Mapping. Statistical Models

3 Problems You Need to Tackle when Developing Robot Software

Robot Mapping. SLAM Front-Ends. Cyrill Stachniss. Partial image courtesy: Edwin Olson 1

ECE276A: Sensing & Estimation in Robotics Lecture 11: Simultaneous Localization and Mapping using a Particle Filter

Data Association for SLAM

Autonomous Navigation for Flying Robots

ROS tf System February, Janyl Jumadinova

5. Tests and results Scan Matching Optimization Parameters Influence

Simultaneous Localization

CSE 490R P1 - Localization using Particle Filters Due date: Sun, Jan 28-11:59 PM

Lecture «Robot Dynamics»: Kinematics 3

Preface...vii. Printed vs PDF Versions of the Book...ix. 1. Scope of this Volume Installing the ros-by-example Code...3

Using the ikart mobile platform

DD2429 Computational Photography :00-19:00

+ i a y )( cosφ + isinφ) ( ) + i( a x. cosφ a y. = a x

θ x Week Date Lecture (M: 2:05p-3:50, 50-N202) 1 23-Jul Introduction + Representing Position & Orientation & State 2 30-Jul

CS283: Robotics Fall 2016: Software

ME5286 Robotics Spring 2014 Quiz 1 Solution. Total Points: 30

2D/3D Geometric Transformations and Scene Graphs

RIGID IMAGE REGISTRATION

ME 597: AUTONOMOUS MOBILE ROBOTICS SECTION 2 COORDINATE TRANSFORMS. Prof. Steven Waslander

Hello, welcome to the video lecture series on Digital Image Processing. So in today's lecture

Robot Mapping. Graph-Based SLAM with Landmarks. Cyrill Stachniss

Introduction to Mobile Robotics

Visual Recognition: Image Formation

INDOOR AND OUTDOOR LOCALIZATION OF A MOBILE ROBOT FUSING SENSOR DATA. A Thesis Presented. Md Maruf Ibne Hasan

Introducing MoveIt! First, start the Baxter simulator in Gazebo:

CS 445 / 645 Introduction to Computer Graphics. Lecture 21 Representing Rotations

Mobile Robots: An Introduction.

Computer Graphics 7: Viewing in 3-D

COMP3431 Robot Software Architectures

Lecture 18: Voronoi Graphs and Distinctive States. Problem with Metrical Maps

Today. Parity. General Polygons? Non-Zero Winding Rule. Winding Numbers. CS559 Lecture 11 Polygons, Transformations

Lecture «Robot Dynamics»: Multi-body Kinematics

Lecture «Robot Dynamics»: Kinematics 3

W4. Perception & Situation Awareness & Decision making

CSE 490R P3 - Model Learning and MPPI Due date: Sunday, Feb 28-11:59 PM

CSE 527: Introduction to Computer Vision

Forward kinematics and Denavit Hartenburg convention

GEOMETRIC TRANSFORMATIONS AND VIEWING

Vector Calculus: Understanding the Cross Product

Robotics (Kinematics) Winter 1393 Bonab University

Teaching Assistant: Roi Yehoshua

IntroductionToRobotics-Lecture02

Introduction to Robotics

Spring 2010: Lecture 9. Ashutosh Saxena. Ashutosh Saxena

Transcription:

F1/10 th Racing Rigid Body Transformations (Or How Different sensors see the same world) By, Paritosh Kelkar

Mapping the surroundings Specify destination and generate path to goal The colored cells represent a potential that is used to plan paths Rviz is used to specify different goals to the robot

Why should you watch these lectures Following the wall here blindly is going to be really hard You will need a very complicated Route definition file

Why should you watch these lectures Simultaneous Localization and Planning Planning

Lets begin

Scope of the Lecture PART 1 The concept of frames and transforms (different views of the same world) Why is this important to us The Homogenous Transformation Matrix PART 2 How ROS deals with these frames, conventions in ROS

Frames of Reference

Part 1

Transformations and Frames: Heads up 1. w.r.t = with respect to 2. Map frame where are you w.r.t the map co-oridnates from origin

Transformations and Frames: Heads up The Sensor frame how does the world look w.r.t the sensor Does this tell you anything about where obstacles are in the map? Does this tell you anything about where we are in the map? We must link frames together Transformations

Transformations and Frames The frame of reference in which the measurement is taken Z Δz X Distance measurements returned by LIDAR

Transformations and Frames The frame of reference in which the measurement is taken Δz X Z Y The scan Values from the LIDAR will not tell us how far away are the obstacles. We must take care of the offsets Δx

Transformations and Frames Δz X Z Y Note: Axes X,Y,Z of Frames of Reference are orthogonal(90 o ) to each other. X,Y,Z represent the axes along the 3 dimensions.

Transformations and Frames Car frame X Z Y Y Map frame Y laser frame Between frames there will exist transformations that convert measurements from one frame to another Important Point: Note what the transformation means w.r.t frames

Transformations and Frames Between frames there will exist transformations that convert measurements from one frame to another Z Y laser frame Y There should exist a relationship Between these frames Car frame X Y Y Map frame Y Transform from car to laser Y Transform from map to car

A world without frames and transformations

The actual motion of the car

Rigid Body Transforms: An Aside What s with it being Rigid? The distance between any two given points of a rigid body remains constant in time regardless of external forces exerted on it. Play-Doh: Obviously not a rigid body

Rigid Body Transforms Y A Z A X A

Rigid Body Transforms Y A Z A X A

Rigid Body Transforms θ Y A Z A X A

Rigid Body Transforms θ Y A A d B Z A X A

Rigid Body Transforms B p θ Y A A d B Z A X A

Rigid Body Transforms B p A p θ Y A A d B Z A X A

Rigid Body Transforms What we need is Point p with respect to Frame A, given its pose in Frame B B p A p θ Y A A d B Z A X A

Rigid Body Transforms Special type of matrices called Rotation matrices X B = R 11 X A + R 21 Y A + R 31 Z A Y A Y B = R 12 X A + R 22 Y A + R 32 Z A Z B = R 13 X A + R 23 Y A + R 33 Z A Z A X A θ

Rigid Body Transforms Special type of matrices called Rotation matrices X B = R 11 X A + R 21 Y A + R 31 Z A Y B = R 12 X A + R 22 Y A + R 32 Z A Z B = R 13 X A + R 23 Y A + R 33 Z A Y A Z A A R B = R 11 R 12 R 13 R 21 R 22 R 23 R 31 R 32 R 33 Takes points in frame B and represents their orientation in frame A θ X A

Rigid Body Transforms: Rotation Matrices X B = R 11 X A + R 21 Y A + R 31 Z A (0,5,0) A p =? Y B = R 12 X A + R 22 Y A + R 32 Z A Y A B p Sine component Z B = R 13 X A + R 23 Y A + R 33 Z A Z A θ Cosine component XA X B = cos(θ) X A +sin(θ) Y A +0 Z A R 11 R 21 R 31

Rigid Body Transforms: Rotation Matrices A R B = Cos(θ) R 12 R 13 Sin(θ) R 22 R 23 0 R 32 R 33 X A Y A Z A A C S 0 RB S C 0 0 0 1 X B Y B Z B ) C θ = Cos(θ ) S θ = Sin(θ

We have the Rotation Matrix, so now what? p R p A A B B R = 0.86 0.5 0 0.5 0.86 0 0 0 1 For example θ We now have the point P as referenced in frame A Τ = π 6 Known Known A p = (-2.5,4.3,0) (-2.5,4.3,0) Y A A p Z A X A

Important point to remember The rotation matrix will take care of perspectives of orientation, what about displacement? Y A Y A Z A Z A X A X A Origins of both the frames are at the same location A d B

Rigid Body Transforms: And We are back to the Future A A B A B p R p d B Y B Y A Z B X B Z A X A

Rigid Body Transforms What we need is Point p with respect to Frame A, given its pose in Frame B p H p B p A A B B p A p θ Y A Z A X A A d B A H = Homogenous transformations that transforms B measurements in Frame B to those in Frame A A C S 0 RB S C 0 0 0 1 R d A A A B B H B 0 1

Part 2

Map frame Map Frame

Map frame: Importance Position with respect to map MAP FRAME

Map Frame: Properties Used as a long term reference Dependence on localization engine (Adaptive Monte Carlo Localization AMCL used in our system more about this in later lectures) Localization engine - responsible for providing pose w.r.t map Frame Authority

Map Frame: ROS The tf package tracks multiple 3D coordinate frames - maintains a tree structure b/w frames access relationship b/w any 2 frames at any point of time ROS REP(ROS Enhancement Proposals) 105 describes the various frames involved Normal hierarchy world_frame Has no parent A tf tree is a structure that maintains relations between the linked frames. Note: Tf = transformer class map Child of world frame

Odom Frame

Odom frame: Calculation Frame in which odometry is measured Odometry is used by some robots, whether they be legged or wheeled, to estimate (not determine) their position relative to a starting location -Wikipedia Source: eg: Wheel encoders. Count wheel ticks

Odom Frame: Calculation Difference in count of ticks of wheels orientation Integrating the commanded velocities/accelarations Integrating values from IMU

Odom Frame: Uncertainty Initial Position Error can accumulate leading to a drift in values Incorrect diameter used? Slippage? Dead Reckoning Notice how the uncertainty increases

Odom Frame: Properties Continuous actual data from actuators/motors Evolves in a smooth manner, without discrete jumps Short term ; accurate local reference

Odom Frame: ROS General ROS frame hierarchy world_frame map Note that if the frame is connected in the tf tree, we can obtain a representation of that frame with any other frame in the tree odom Tf tree

Base_link and fixed frames attached to the robot

Base link: What is it Attached to the robot itself base_footprint; base_link; base_stabilized

Base link: Properties Odom -> base link transform provided by Odometry source Map -> base_link transform provided by localization component

Fixed Frames: Source Where do we get the relationships between the fixed frame on the car Frame for various hardware components(sensors) Robot description provides the transformations Urdf file Look up the tutorial related to this lecture

Base_link Frame: ROS General ROS frame hierarchy world_frame map odom base_link Tf tree

ROS.W.T.F Its actually a tool just very cleverly named Host of tf debugging tools provided by ROS Look at tutorial for further details $ rosrun tf view_frames $ rosrun tf view_monitor $ roswtf

In Conclusion Rigid Body Transformations the concept and the importance in robotic systems We now know how to correlate measurements from different sensors The upcoming lecture SLAM Simultaneous Localization and Mapping

Why do you have to remember all of this stuff Again, you are developing the platform in this framework Don t you want to know how you could get maps of your surroundings? what we just covered are building blocks of the upcoming topics

Upcoming Lectures We will go into detail about the packages that we use for mapping and localizing

Map frame: Properties Discontinuity Y Z Map frame (0,0,0) X

Map frame: Properties New sensor reading gives us new information Discontinuity Y Z Map frame (0,0,0) X Jump in position, i.e, not continuous (2,0,0)

Map Frame: Properties

Map Frame: Why Discontinuity is a Problem What pose coordinates will the controller act on?

Transformations and Frames The frame of reference in which the measurement is taken Z Δz X Y Δx

Odom Frame: Uncertainty Initial placement of odom and map frames Final placement of odom and map frames after robot has moved some distance