Lecture Note 7: Velocity Kinematics and Jacobian

Size: px
Start display at page:

Download "Lecture Note 7: Velocity Kinematics and Jacobian"

Transcription

1 ECE5463: Introduction to Robotics Lecture Note 7: Velocity Kinematics and Jacobian Prof. Wei Zhang Department of Electrical and Computer Engineering Ohio State University Columbus, Ohio, USA Spring 2018 Lecture 7 (ECE5463 Sp18) Wei Zhang(OSU) 1 / 20

2 Outline Introduction Space and Body Jacobians Kinematic Singularity Outline Lecture 7 (ECE5463 Sp18) Wei Zhang(OSU) 2 / 20

3 Jacobian Given a multivariable function x = f(θ), where x R m and θ R n. Its Jacobian is defined as [ ] [ ] f J(θ) θ (θ) fi R m n θ j i m,j n If x and θ are both a function of time, then their velocities are related by the Jacobian: [ ] f dθ ẋ = θ (θ) = J(θ) θ dt Let J i (θ) be the ith column of J, then ẋ = J 1 (θ) θ J n (θ) - J i(θ) is the velocity of x due to θ i (while θ j = 0 for all j i) θ n Introduction Lecture 7 (ECE5463 Sp18) Wei Zhang(OSU) 3 / 20

4 Velocity Kinematics Problem In the previous lecture, we studied the forward kinematics problem, that obtains the mapping from joint angles to {b} frame configuration: θ = (θ 1,..., θ n ) T T sb (θ) In this lecture, we study the velocity kinematics problem, namely, deriving the relation that maps velocities of joint variables θ to the velocity of the end-effector frame - Note: we are interested in relating θ to the velocity of the entire body frame (not just a point on the body) - One may intend to write T (θ) = J(θ) θ. However, T SE(4) and its derivative is not a good way to represent velocity of the body. - Two approaches: (1) Analytical Jacobian: using a minimum set of coordinate x R 6 of the frame configuration and then take derivative; (2) Geometric Jacobian: directly relate θ to the spacial/body twist V Introduction Lecture 7 (ECE5463 Sp18) Wei Zhang(OSU) 4 / 20

5 Analytical vs. Geometric Jacobian A straightforward way to characterize the velocity kinematics is through the Analytical Jacobian Express the configuration of {b} using a minimum set of coordinates x. For example: - (x 1, x 2, x 3): Cartesian coordinates or spherical coordinate of the origin - (x 4, x 5, x 6): Euler angles or exponential coordinate of the orientation Write down the forward kinematics using the minimum set of coordinate x: x = f(θ) Analytical Jacobian can then be computed as J a (θ) = [ f θ (θ) ] The analytical Jacobian J a depends on the local coordinates system of SE(3) See Textbook for more details Introduction Lecture 7 (ECE5463 Sp18) Wei Zhang(OSU) 5 / 20

6 Analytical vs. Geometric Jacobian Geometric Jacobian directly finds relation between joint velocities and end-effector twist: [ ] ω V = = J(θ) v θ, where J(θ) R 6 n Note: V = (ω, v) is NOT a derivative of any position variable, i.e. V dx dt (regardless what representation x is used) because the angular velocity is not the derivative of any time varying quantity. Analytical Jacobian J a destroys the natural geometric structure of the rigid body motion; Geometric Jacobian can be used to derive analytical Jacobian. Introduction Lecture 7 (ECE5463 Sp18) Wei Zhang(OSU) 6 / 20

7 Outline Introduction Space and Body Jacobians Kinematic Singularity Geometric Jacobian Lecture 7 (ECE5463 Sp18) Wei Zhang(OSU) 7 / 20

8 Geometric Jacobian in Space Form Given the forward kinematics: T sb (θ 1,..., θ n ) = e [S1]θ1 e [Sn]θn M Let V s = (ω s, v s ) be the spacial twist, we aim to find J s (θ) such that V s = J s (θ) θ = J s1 (θ) θ J sn (θ) θ n The ith column J si is the velocity (twist) of the body frame due to only the ith joint motion θ i In other words, J si (θ) is the spatial twist when the robot is rotating about S i at unit speed θ i = 1 while all other joints do not move (i.e. θj = 0 for j i). Geometric Jacobian Lecture 7 (ECE5463 Sp18) Wei Zhang(OSU) 8 / 20

9 Derivation of Space Jacobian Given any screw axis S, we have d dθ i e [S]θ i = [S]e [S]θ i For simplicity, denote T s,i = e [S 1]θ1 e [S i 1]θ i 1, i = 2,..., n. Let T = T sb (θ) We have [V s] = T T 1 = ( T θ 1 θ1 + + T θ i θi + + T θ n θn ) T 1 Let θ i = 1 and θ j = 0 for j i [J si(θ)] = T θ i T 1 J si(θ) = [ Ad Ts,i ] Si Geometric Jacobian Lecture 7 (ECE5463 Sp18) Wei Zhang(OSU) 9 / 20

10 Summary of Space Jacobian Given the forward kinematics: T (θ) = e [S1]θ1 e [Sn]θn M Space Jacobian: J s (θ) R 6 n relates joint rate vector θ R n to the spatial twist V s via V s = J s (θ) θ. For i 2, the ith column of J s is J si (θ) = [ Ad Ts,i ] Si, where T s,i = e [S1]θ1 e [Si 1]θi 1 and the first column is J s1 = S 1. Procedure: Suppose the current joint position is θ = (θ 1,..., θ n ): - i = 1: find the screw axis S 1 = (ω s1, v s1) when robot is at home position J s1 = S 1 - i = 2: find the screw axis S 2(θ) = (ω s2, v s2) after moving joint 1 from zero position to θ 1. J s2(θ) = S 2(θ) - i = 3: find the screw axis S 3(θ) = (ω s3, v s3) after moving the first 2 joints from zero position to the θ 1 and θ 2. J s3(θ) = S 3(θ) -... Geometric Jacobian Lecture 7 (ECE5463 Sp18) Wei Zhang(OSU) 10 / 20

11 Geometric Jacobian Lecture 7 (ECE5463 Sp18) The first joint axis is in the direction Wei Zhang(OSU) ωs1 = (0, 0, 1). 11 / Choo 20 Space Jacobian Example Chapter 5. Velocity Kinematics and Statics θ1 L1 L2 θ3 θ2 θ4 ẑ ŷ ˆx ŷ q3 ẑ ˆx q1 q2 Figure 5.7: Space Jacobian for a spatial RRRP chain. Since the final joint is prismatic, ωs4 = (0, 0, 0), and the joint-axis is given by vs4 = (0, 0, 1). The space Jacobian is therefore Js(θ) = L1s1 L1s1 + L2s L1c1 L1c1 L2c Example 5.3 (Space Jacobian for a spatial RRPRRR chain). We n the space Jacobian for the spatial RRPRRR chain of Figure 5.8. The b is chosen as shown in the figure.

12 Space Jacobian Example (Continued) Geometric Jacobian Lecture 7 (ECE5463 Sp18) Wei Zhang(OSU) 12 / 20

13 Body Jacobian Recall that V b is the rigid body velocity expressed in body frame. By change of frame for twist, we know V b = [Ad Tbs ] V s or equivalently [V b ] = T bs [V s ]T 1 bs = T 1 sb T sb Body Jacobian J b relates joint rates θ to V b V b = J b (θ) θ = [ J b1 (θ) J bn (θ) ] θ 1. θ n Geometric Jacobian Lecture 7 (ECE5463 Sp18) Wei Zhang(OSU) 13 / 20

14 Derivation of Body Jacobian Use Body form PoE kinematics formula: T (θ) = Me [B1]θ1 e [Bn]θn For simplicity, denote T b,i+ = e [Bi+1]θi+1 e [Bn]θn, for i = 1,..., n 1 ( ) [V b ] = T 1 T = T 1 T θ θ1 1 + T θ θn n Let θ i = 1 and θ j = 0 for j i, 1 T [J b,i ] = T θ i ) ) = (e [Bn]θn e (e [B1]θ1 [B1]θ1 e [Bi 1]θi 1 [B i ]e [Bi]θi e [Bn]θn = ( T b i+) 1 [Bi ]T b i+ Therefore, J b,i = [ ] Ad T 1 B i b,i+ Geometric Jacobian Lecture 7 (ECE5463 Sp18) Wei Zhang(OSU) 14 / 20

15 Summary of Body Jacobian Given the forward kinematics: T (θ) = Me [B1]θ1 e [Bn]θn Body Jacobian: J b (θ) R 6 n relates joint rate vector θ R n to the body twist V b via V b = J b (θ) θ. For i = n 1,..., 1, the ith column of J b is [ ] J bi (θ) = Ad T 1 B i, where T b,i+ = e [Si+1]θi+1 e [Sn]θn b,i+ and the last column is J bn = B n. Geometric Jacobian Lecture 7 (ECE5463 Sp18) Wei Zhang(OSU) 15 / 20

16 Relation Between Space and Body Jacobian Recall that: V b = [Ad Tbs ] V s and V s = [Ad Tsb ] V b Body and spacial twists represent the velocity of the end-effector frame in fixed and body frame The velocity may be caused by one or multiple joint motions. We know the ith column J si (or J bi ) is the spacial twist (or body twist) when θ i = 1 and θ j = 0, j i Therefore, we have J si = [Ad Tsb ] J bi and J bi = [Ad Tbs ] J si. Putting all the columns together leads to J s (θ) = [Ad Tsb ] J b (θ), and J b (θ) = [Ad Tbs ] J s (θ) Detailed derivation can be found in the textbook. Geometric Jacobian Lecture 7 (ECE5463 Sp18) Wei Zhang(OSU) 16 / 20

17 Outline Introduction Space and Body Jacobians Kinematic Singularity Singularity Lecture 7 (ECE5463 Sp18) Wei Zhang(OSU) 17 / 20

18 Kinematic Singularity Roughly speaking, kinematic singularity (or simply singularity) refers to a posture at which the robot s end-effector loses the ability to move instantaneously in one or more directions. Mathematically, a singular posture is one in which the Jacobian (J s (θ) or J b (θ)) fails to be of maximal rank Singularity is independent of the choice of space or body Jacobian rankj s (θ) = rankj b (θ) Singularity Lecture 7 (ECE5463 Sp18) Wei Zhang(OSU) 18 / 20

19 T (θ) =PT Singularity Example Chapter 5. Velocity Kine T (θ) Two collinear revolute joint P (a) Figure 5.10: Kinematic Singularity Lecture 7 (ECE5463 Sp18) Wei Zhang(OSU) 19 / 20

20 More Discussions Singularity Lecture 7 (ECE5463 Sp18) Wei Zhang(OSU) 20 / 20

Lecture Note 7: Velocity Kinematics and Jacobian

Lecture Note 7: Velocity Kinematics and Jacobian ECE5463: Introduction to Robotics Lecture Note 7: Velocity Kinematics and Jacobian Prof. Wei Zhang Department of Electrical and Computer Engineering Ohio State University Columbus, Ohio, USA Spring 2018

More information

Lecture Note 8: Inverse Kinematics

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

More information

Lecture Note 8: Inverse Kinematics

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

More information

Lecture Note 4: General Rigid Body Motion

Lecture Note 4: General Rigid Body Motion ECE5463: Introduction to Robotics Lecture Note 4: General Rigid Body Motion Prof. Wei Zhang Department of Electrical and Computer Engineering Ohio State University Columbus, Ohio, USA Spring 2018 Lecture

More information

Lecture Note 12: Dynamics of Open Chains: Lagrangian Formulation

Lecture Note 12: Dynamics of Open Chains: Lagrangian Formulation ECE5463: Introduction to Robotics Lecture Note 12: Dynamics of Open Chains: Lagrangian Formulation Prof. Wei Zhang Department of Electrical and Computer Engineering Ohio State University Columbus, Ohio,

More information

Lecture Note 5: Velocity of a Rigid Body

Lecture Note 5: Velocity of a Rigid Body ECE5463: Introduction to Robotics Lecture Note 5: Velocity of a Rigid Body Prof. Wei Zhang Department of Electrical and Computer Engineering Ohio State University Columbus, Ohio, USA Spring 2018 Lecture

More information

Differential Kinematics

Differential Kinematics Differential Kinematics Relations between motion (velocity) in joint space and motion (linear/angular velocity) in task space (e.g., Cartesian space) Instantaneous velocity mappings can be obtained through

More information

In this section of notes, we look at the calculation of forces and torques for a manipulator in two settings:

In this section of notes, we look at the calculation of forces and torques for a manipulator in two settings: Introduction Up to this point we have considered only the kinematics of a manipulator. That is, only the specification of motion without regard to the forces and torques required to cause motion In this

More information

Lecture Note 12: Dynamics of Open Chains: Lagrangian Formulation

Lecture Note 12: Dynamics of Open Chains: Lagrangian Formulation ECE5463: Introduction to Robotics Lecture Note 12: Dynamics of Open Chains: Lagrangian Formulation Prof. Wei Zhang Department of Electrical and Computer Engineering Ohio State University Columbus, Ohio,

More information

Lecture Note 1: Background

Lecture Note 1: Background ECE5463: Introduction to Robotics Lecture Note 1: Background Prof. Wei Zhang Department of Electrical and Computer Engineering Ohio State University Columbus, Ohio, USA Spring 2018 Lecture 1 (ECE5463 Sp18)

More information

Ch. 5: Jacobian. 5.1 Introduction

Ch. 5: Jacobian. 5.1 Introduction 5.1 Introduction relationship between the end effector velocity and the joint rates differentiate the kinematic relationships to obtain the velocity relationship Jacobian matrix closely related to the

More information

Dynamics of Open Chains

Dynamics of Open Chains Chapter 9 Dynamics of Open Chains According to Newton s second law of motion, any change in the velocity of a rigid body is caused by external forces and torques In this chapter we study once again the

More information

MEAM 520. More Velocity Kinematics

MEAM 520. More Velocity Kinematics MEAM 520 More Velocity Kinematics Katherine J. Kuchenbecker, Ph.D. General Robotics, Automation, Sensing, and Perception Lab (GRASP) MEAM Department, SEAS, University of Pennsylvania Lecture 12: October

More information

8 Velocity Kinematics

8 Velocity Kinematics 8 Velocity Kinematics Velocity analysis of a robot is divided into forward and inverse velocity kinematics. Having the time rate of joint variables and determination of the Cartesian velocity of end-effector

More information

Position and orientation of rigid bodies

Position and orientation of rigid bodies Robotics 1 Position and orientation of rigid bodies Prof. Alessandro De Luca Robotics 1 1 Position and orientation right-handed orthogonal Reference Frames RF A A p AB B RF B rigid body position: A p AB

More information

Lecture 7: Kinematics: Velocity Kinematics - the Jacobian

Lecture 7: Kinematics: Velocity Kinematics - the Jacobian Lecture 7: Kinematics: Velocity Kinematics - the Jacobian Manipulator Jacobian c Anton Shiriaev. 5EL158: Lecture 7 p. 1/?? Lecture 7: Kinematics: Velocity Kinematics - the Jacobian Manipulator Jacobian

More information

Exercise 1b: Differential Kinematics of the ABB IRB 120

Exercise 1b: Differential Kinematics of the ABB IRB 120 Exercise 1b: Differential Kinematics of the ABB IRB 120 Marco Hutter, Michael Blösch, Dario Bellicoso, Samuel Bachmann October 5, 2016 Abstract The aim of this exercise is to calculate the differential

More information

Interpolated Rigid-Body Motions and Robotics

Interpolated Rigid-Body Motions and Robotics Interpolated Rigid-Body Motions and Robotics J.M. Selig London South Bank University and Yuanqing Wu Shanghai Jiaotong University. IROS Beijing 2006 p.1/22 Introduction Interpolation of rigid motions important

More information

Robotics & Automation. Lecture 17. Manipulability Ellipsoid, Singularities of Serial Arm. John T. Wen. October 14, 2008

Robotics & Automation. Lecture 17. Manipulability Ellipsoid, Singularities of Serial Arm. John T. Wen. October 14, 2008 Robotics & Automation Lecture 17 Manipulability Ellipsoid, Singularities of Serial Arm John T. Wen October 14, 2008 Jacobian Singularity rank(j) = dimension of manipulability ellipsoid = # of independent

More information

ME 115(b): Homework #2 Solution. Part (b): Using the Product of Exponentials approach, the structure equations take the form:

ME 115(b): Homework #2 Solution. Part (b): Using the Product of Exponentials approach, the structure equations take the form: ME 5(b): Homework #2 Solution Problem : Problem 2 (d,e), Chapter 3 of MLS. Let s review some material from the parts (b) of this problem: Part (b): Using the Product of Exponentials approach, the structure

More information

Dynamics 12e. Copyright 2010 Pearson Education South Asia Pte Ltd. Chapter 20 3D Kinematics of a Rigid Body

Dynamics 12e. Copyright 2010 Pearson Education South Asia Pte Ltd. Chapter 20 3D Kinematics of a Rigid Body Engineering Mechanics: Dynamics 12e Chapter 20 3D Kinematics of a Rigid Body Chapter Objectives Kinematics of a body subjected to rotation about a fixed axis and general plane motion. Relative-motion analysis

More information

MODERN ROBOTICS MECHANICS, PLANNING, AND CONTROL. Practice Exercises. Contributions from Tito Fernandez, Kevin Lynch, Huan Weng, and Zack Woodruff

MODERN ROBOTICS MECHANICS, PLANNING, AND CONTROL. Practice Exercises. Contributions from Tito Fernandez, Kevin Lynch, Huan Weng, and Zack Woodruff MODERN ROBOTICS MECHANICS, PLANNING, AND CONTROL Practice Exercises Contributions from Tito Fernandez, Kevin Lynch, Huan Weng, and Zack Woodruff December 6, 2018 This is a supplemental document to Modern

More information

Multibody simulation

Multibody simulation Multibody simulation Dynamics of a multibody system (Newton-Euler formulation) Dimitar Dimitrov Örebro University June 8, 2012 Main points covered Newton-Euler formulation forward dynamics inverse dynamics

More information

Nonholonomic Constraints Examples

Nonholonomic Constraints Examples Nonholonomic Constraints Examples Basilio Bona DAUIN Politecnico di Torino July 2009 B. Bona (DAUIN) Examples July 2009 1 / 34 Example 1 Given q T = [ x y ] T check that the constraint φ(q) = (2x + siny

More information

ROBOTICS: ADVANCED CONCEPTS & ANALYSIS

ROBOTICS: ADVANCED CONCEPTS & ANALYSIS ROBOTICS: ADVANCED CONCEPTS & ANALYSIS MODULE 5 VELOCITY AND STATIC ANALYSIS OF MANIPULATORS Ashitava Ghosal 1 1 Department of Mechanical Engineering & Centre for Product Design and Manufacture Indian

More information

Robot Dynamics II: Trajectories & Motion

Robot Dynamics II: Trajectories & Motion Robot Dynamics II: Trajectories & Motion Are We There Yet? METR 4202: Advanced Control & Robotics Dr Surya Singh Lecture # 5 August 23, 2013 metr4202@itee.uq.edu.au http://itee.uq.edu.au/~metr4202/ 2013

More information

Lecture «Robot Dynamics»: Kinematics 2

Lecture «Robot Dynamics»: Kinematics 2 Lecture «Robot Dynamics»: Kinematics 2 151-0851-00 V lecture: CAB G11 Tuesday 10:15 12:00, every week exercise: HG E1.2 Wednesday 8:15 10:00, according to schedule (about every 2nd week) Marco Hutter,

More information

Robotics I Kinematics, Dynamics and Control of Robotic Manipulators. Velocity Kinematics

Robotics I Kinematics, Dynamics and Control of Robotic Manipulators. Velocity Kinematics Robotics I Kinematics, Dynamics and Control of Robotic Manipulators Velocity Kinematics Dr. Christopher Kitts Director Robotic Systems Laboratory Santa Clara University Velocity Kinematics So far, we ve

More information

The Jacobian. Jesse van den Kieboom

The Jacobian. Jesse van den Kieboom The Jacobian Jesse van den Kieboom jesse.vandenkieboom@epfl.ch 1 Introduction 1 1 Introduction The Jacobian is an important concept in robotics. Although the general concept of the Jacobian in robotics

More information

Robotics & Automation. Lecture 06. Serial Kinematic Chain, Forward Kinematics. John T. Wen. September 11, 2008

Robotics & Automation. Lecture 06. Serial Kinematic Chain, Forward Kinematics. John T. Wen. September 11, 2008 Robotics & Automation Lecture 06 Serial Kinematic Chain, Forward Kinematics John T. Wen September 11, 2008 So Far... We have covered rigid body rotational kinematics: representations of SO(3), change of

More information

Lecture Schedule Week Date Lecture (M: 2:05p-3:50, 50-N202)

Lecture Schedule Week Date Lecture (M: 2:05p-3:50, 50-N202) J = x θ τ = J T F 2018 School of Information Technology and Electrical Engineering at the University of Queensland Lecture Schedule Week Date Lecture (M: 2:05p-3:50, 50-N202) 1 23-Jul Introduction + Representing

More information

Example: RR Robot. Illustrate the column vector of the Jacobian in the space at the end-effector point.

Example: RR Robot. Illustrate the column vector of the Jacobian in the space at the end-effector point. Forward kinematics: X e = c 1 + c 12 Y e = s 1 + s 12 = s 1 s 12 c 1 + c 12, = s 12 c 12 Illustrate the column vector of the Jacobian in the space at the end-effector point. points in the direction perpendicular

More information

Robot Dynamics Instantaneous Kinematiccs and Jacobians

Robot Dynamics Instantaneous Kinematiccs and Jacobians Robot Dynamics Instantaneous Kinematiccs and Jacobians 151-0851-00 V Lecture: Tuesday 10:15 12:00 CAB G11 Exercise: Tuesday 14:15 16:00 every 2nd week Marco Hutter, Michael Blösch, Roland Siegwart, Konrad

More information

Inverse differential kinematics Statics and force transformations

Inverse differential kinematics Statics and force transformations Robotics 1 Inverse differential kinematics Statics and force transformations Prof Alessandro De Luca Robotics 1 1 Inversion of differential kinematics! find the joint velocity vector that realizes a desired

More information

Advanced Robotic Manipulation

Advanced Robotic Manipulation Lecture Notes (CS327A) Advanced Robotic Manipulation Oussama Khatib Stanford University Spring 2005 ii c 2005 by Oussama Khatib Contents 1 Spatial Descriptions 1 1.1 Rigid Body Configuration.................

More information

Screw Theory and its Applications in Robotics

Screw Theory and its Applications in Robotics Screw Theory and its Applications in Robotics Marco Carricato Group of Robotics, Automation and Biomechanics University of Bologna Italy IFAC 2017 World Congress, Toulouse, France Table of Contents 1.

More information

ROBOTICS 01PEEQW. Basilio Bona DAUIN Politecnico di Torino

ROBOTICS 01PEEQW. Basilio Bona DAUIN Politecnico di Torino ROBOTICS 01PEEQW Basilio Bona DAUIN Politecnico di Torino Kinematic Functions Kinematic functions Kinematics deals with the study of four functions(called kinematic functions or KFs) that mathematically

More information

Chapter 3 + some notes on counting the number of degrees of freedom

Chapter 3 + some notes on counting the number of degrees of freedom Chapter 3 + some notes on counting the number of degrees of freedom Minimum number of independent parameters = Some number of dependent parameters minus the number of relationships (equations) you can

More information

(W: 12:05-1:50, 50-N202)

(W: 12:05-1:50, 50-N202) 2016 School of Information Technology and Electrical Engineering at the University of Queensland Schedule of Events Week Date Lecture (W: 12:05-1:50, 50-N202) 1 27-Jul Introduction 2 Representing Position

More information

Multibody simulation

Multibody simulation Multibody simulation Dynamics of a multibody system (Euler-Lagrange formulation) Dimitar Dimitrov Örebro University June 16, 2012 Main points covered Euler-Lagrange formulation manipulator inertia matrix

More information

DYNAMICS OF PARALLEL MANIPULATOR

DYNAMICS OF PARALLEL MANIPULATOR DYNAMICS OF PARALLEL MANIPULATOR PARALLEL MANIPULATORS 6-degree of Freedom Flight Simulator BACKGROUND Platform-type parallel mechanisms 6-DOF MANIPULATORS INTRODUCTION Under alternative robotic mechanical

More information

ECE569 Exam 1 October 28, Name: Score: /100. Please leave fractions as fractions, but simplify them, etc.

ECE569 Exam 1 October 28, Name: Score: /100. Please leave fractions as fractions, but simplify them, etc. ECE569 Exam 1 October 28, 2015 1 Name: Score: /100 This exam is closed-book. You must show ALL of your work for full credit. Please read the questions carefully. Please check your answers carefully. Calculators

More information

Kinematics. Basilio Bona. Semester 1, DAUIN Politecnico di Torino. B. Bona (DAUIN) Kinematics Semester 1, / 15

Kinematics. Basilio Bona. Semester 1, DAUIN Politecnico di Torino. B. Bona (DAUIN) Kinematics Semester 1, / 15 Kinematics Basilio Bona DAUIN Politecnico di Torino Semester 1, 2016-17 B. Bona (DAUIN) Kinematics Semester 1, 2016-17 1 / 15 Introduction The kinematic quantities used to represent a body frame are: position

More information

Introduction to Robotics

Introduction to Robotics J. Zhang, L. Einig 277 / 307 MIN Faculty Department of Informatics Lecture 8 Jianwei Zhang, Lasse Einig [zhang, einig]@informatik.uni-hamburg.de University of Hamburg Faculty of Mathematics, Informatics

More information

Robotics: Tutorial 3

Robotics: Tutorial 3 Robotics: Tutorial 3 Mechatronics Engineering Dr. Islam Khalil, MSc. Omar Mahmoud, Eng. Lobna Tarek and Eng. Abdelrahman Ezz German University in Cairo Faculty of Engineering and Material Science October

More information

DYNAMICS OF SERIAL ROBOTIC MANIPULATORS

DYNAMICS OF SERIAL ROBOTIC MANIPULATORS DYNAMICS OF SERIAL ROBOTIC MANIPULATORS NOMENCLATURE AND BASIC DEFINITION We consider here a mechanical system composed of r rigid bodies and denote: M i 6x6 inertia dyads of the ith body. Wi 6 x 6 angular-velocity

More information

RECURSIVE INVERSE DYNAMICS

RECURSIVE INVERSE DYNAMICS We assume at the outset that the manipulator under study is of the serial type with n+1 links including the base link and n joints of either the revolute or the prismatic type. The underlying algorithm

More information

Chapter 6. Screw theory for instantaneous kinematics. 6.1 Introduction. 6.2 Exponential coordinates for rotation

Chapter 6. Screw theory for instantaneous kinematics. 6.1 Introduction. 6.2 Exponential coordinates for rotation Screw theory for instantaneous kinematics 6.1 Introduction Chapter 6 Screw theory was developed by Sir Robert Stawell Ball [111] in 1876, for application in kinematics and statics of mechanisms (rigid

More information

Lecture Notes Multibody Dynamics B, wb1413

Lecture Notes Multibody Dynamics B, wb1413 Lecture Notes Multibody Dynamics B, wb1413 A. L. Schwab & Guido M.J. Delhaes Laboratory for Engineering Mechanics Mechanical Engineering Delft University of Technolgy The Netherlands June 9, 29 Contents

More information

Case Study: The Pelican Prototype Robot

Case Study: The Pelican Prototype Robot 5 Case Study: The Pelican Prototype Robot The purpose of this chapter is twofold: first, to present in detail the model of the experimental robot arm of the Robotics lab. from the CICESE Research Center,

More information

Robotics & Automation. Lecture 25. Dynamics of Constrained Systems, Dynamic Control. John T. Wen. April 26, 2007

Robotics & Automation. Lecture 25. Dynamics of Constrained Systems, Dynamic Control. John T. Wen. April 26, 2007 Robotics & Automation Lecture 25 Dynamics of Constrained Systems, Dynamic Control John T. Wen April 26, 2007 Last Time Order N Forward Dynamics (3-sweep algorithm) Factorization perspective: causal-anticausal

More information

DYNAMICS OF PARALLEL MANIPULATOR

DYNAMICS OF PARALLEL MANIPULATOR DYNAMICS OF PARALLEL MANIPULATOR The 6nx6n matrices of manipulator mass M and manipulator angular velocity W are introduced below: M = diag M 1, M 2,, M n W = diag (W 1, W 2,, W n ) From this definitions

More information

Single Exponential Motion and Its Kinematic Generators

Single Exponential Motion and Its Kinematic Generators PDFaid.Com #1 Pdf Solutions Single Exponential Motion and Its Kinematic Generators Guanfeng Liu, Yuanqin Wu, and Xin Chen Abstract Both constant velocity (CV) joints and zero-torsion parallel kinematic

More information

The Principle of Virtual Power Slide companion notes

The Principle of Virtual Power Slide companion notes The Principle of Virtual Power Slide companion notes Slide 2 In Modules 2 and 3 we have seen concepts of Statics and Kinematics in a separate way. In this module we shall see how the static and the kinematic

More information

Artificial Intelligence & Neuro Cognitive Systems Fakultät für Informatik. Robot Dynamics. Dr.-Ing. John Nassour J.

Artificial Intelligence & Neuro Cognitive Systems Fakultät für Informatik. Robot Dynamics. Dr.-Ing. John Nassour J. Artificial Intelligence & Neuro Cognitive Systems Fakultät für Informatik Robot Dynamics Dr.-Ing. John Nassour 25.1.218 J.Nassour 1 Introduction Dynamics concerns the motion of bodies Includes Kinematics

More information

Lecture IV: Time Discretization

Lecture IV: Time Discretization Lecture IV: Time Discretization Motivation Kinematics: continuous motion in continuous time Computer simulation: Discrete time steps t Discrete Space (mesh particles) Updating Position Force induces acceleration.

More information

Kinematics of a UR5. Rasmus Skovgaard Andersen Aalborg University

Kinematics of a UR5. Rasmus Skovgaard Andersen Aalborg University Kinematics of a UR5 May 3, 28 Rasmus Skovgaard Andersen Aalborg University Contents Introduction.................................... Notation.................................. 2 Forward Kinematics for

More information

Dynamics. Basilio Bona. Semester 1, DAUIN Politecnico di Torino. B. Bona (DAUIN) Dynamics Semester 1, / 18

Dynamics. Basilio Bona. Semester 1, DAUIN Politecnico di Torino. B. Bona (DAUIN) Dynamics Semester 1, / 18 Dynamics Basilio Bona DAUIN Politecnico di Torino Semester 1, 2016-17 B. Bona (DAUIN) Dynamics Semester 1, 2016-17 1 / 18 Dynamics Dynamics studies the relations between the 3D space generalized forces

More information

Sequential Bayesian Updating

Sequential Bayesian Updating BS2 Statistical Inference, Lectures 14 and 15, Hilary Term 2009 May 28, 2009 We consider data arriving sequentially X 1,..., X n,... and wish to update inference on an unknown parameter θ online. In a

More information

, respectively to the inverse and the inverse differential problem. Check the correctness of the obtained results. Exercise 2 y P 2 P 1.

, respectively to the inverse and the inverse differential problem. Check the correctness of the obtained results. Exercise 2 y P 2 P 1. Robotics I July 8 Exercise Define the orientation of a rigid body in the 3D space through three rotations by the angles α β and γ around three fixed axes in the sequence Y X and Z and determine the associated

More information

Robotics, Geometry and Control - Rigid body motion and geometry

Robotics, Geometry and Control - Rigid body motion and geometry Robotics, Geometry and Control - Rigid body motion and geometry Ravi Banavar 1 1 Systems and Control Engineering IIT Bombay HYCON-EECI Graduate School - Spring 2008 The material for these slides is largely

More information

1 Kalman Filter Introduction

1 Kalman Filter Introduction 1 Kalman Filter Introduction You should first read Chapter 1 of Stochastic models, estimation, and control: Volume 1 by Peter S. Maybec (available here). 1.1 Explanation of Equations (1-3) and (1-4) Equation

More information

Framework Comparison Between a Multifingered Hand and a Parallel Manipulator

Framework Comparison Between a Multifingered Hand and a Parallel Manipulator Framework Comparison Between a Multifingered Hand and a Parallel Manipulator Júlia Borràs and Aaron M. Dollar Abstract In this paper we apply the kineto-static mathematical models commonly used for robotic

More information

Robotics I. Classroom Test November 21, 2014

Robotics I. Classroom Test November 21, 2014 Robotics I Classroom Test November 21, 2014 Exercise 1 [6 points] In the Unimation Puma 560 robot, the DC motor that drives joint 2 is mounted in the body of link 2 upper arm and is connected to the joint

More information

Video 1.1 Vijay Kumar and Ani Hsieh

Video 1.1 Vijay Kumar and Ani Hsieh Video 1.1 Vijay Kumar and Ani Hsieh 1 Robotics: Dynamics and Control Vijay Kumar and Ani Hsieh University of Pennsylvania 2 Why? Robots live in a physical world The physical world is governed by the laws

More information

Advanced Robotic Manipulation

Advanced Robotic Manipulation Advanced Robotic Manipulation Handout CS37A (Spring 017 Solution Set # Problem 1 - Redundant robot control The goal of this problem is to familiarize you with the control of a robot that is redundant with

More information

Advanced Robotic Manipulation

Advanced Robotic Manipulation Advanced Robotic Manipulation Handout CS37A (Spring 017) Solution Set #3 Problem 1 - Inertial properties In this problem, you will explore the inertial properties of a manipulator at its end-effector.

More information

2-D Motion of Rigid Bodies - Kinematics

2-D Motion of Rigid Bodies - Kinematics 1 2.003J/1.053J Dynamics and Control I, Spring 2007 Professor Thomas Peacock 2/28/2007 Lecture 7 2-D Motion of Rigid Bodies - Kinematics Kinematics of Rigid Bodies Williams 3-3 (No method of instant centers)

More information

DIFFERENTIAL KINEMATICS. Geometric Jacobian. Analytical Jacobian. Kinematic singularities. Kinematic redundancy. Inverse differential kinematics

DIFFERENTIAL KINEMATICS. Geometric Jacobian. Analytical Jacobian. Kinematic singularities. Kinematic redundancy. Inverse differential kinematics DIFFERENTIAL KINEMATICS relationship between joint velocities and end-effector velocities Geometric Jacobian Analytical Jacobian Kinematic singularities Kinematic redundancy Inverse differential kinematics

More information

the EL equation for the x coordinate is easily seen to be (exercise)

the EL equation for the x coordinate is easily seen to be (exercise) Physics 6010, Fall 2016 Relevant Sections in Text: 1.3 1.6 Examples After all this formalism it is a good idea to spend some time developing a number of illustrative examples. These examples represent

More information

Generalized coordinates and constraints

Generalized coordinates and constraints Generalized coordinates and constraints Basilio Bona DAUIN Politecnico di Torino Semester 1, 2014-15 B. Bona (DAUIN) Generalized coordinates and constraints Semester 1, 2014-15 1 / 25 Coordinates A rigid

More information

1 Simple Harmonic Oscillator

1 Simple Harmonic Oscillator Massachusetts Institute of Technology MITES 2017 Physics III Lectures 02 and 03: Simple Harmonic Oscillator, Classical Pendulum, and General Oscillations In these notes, we introduce simple harmonic oscillator

More information

Multiple Integrals and Vector Calculus (Oxford Physics) Synopsis and Problem Sets; Hilary 2015

Multiple Integrals and Vector Calculus (Oxford Physics) Synopsis and Problem Sets; Hilary 2015 Multiple Integrals and Vector Calculus (Oxford Physics) Ramin Golestanian Synopsis and Problem Sets; Hilary 215 The outline of the material, which will be covered in 14 lectures, is as follows: 1. Introduction

More information

1 Trajectory Generation

1 Trajectory Generation CS 685 notes, J. Košecká 1 Trajectory Generation The material for these notes has been adopted from: John J. Craig: Robotics: Mechanics and Control. This example assumes that we have a starting position

More information

5. Nonholonomic constraint Mechanics of Manipulation

5. Nonholonomic constraint Mechanics of Manipulation 5. Nonholonomic constraint Mechanics of Manipulation Matt Mason matt.mason@cs.cmu.edu http://www.cs.cmu.edu/~mason Carnegie Mellon Lecture 5. Mechanics of Manipulation p.1 Lecture 5. Nonholonomic constraint.

More information

Lecture 38: Equations of Rigid-Body Motion

Lecture 38: Equations of Rigid-Body Motion Lecture 38: Equations of Rigid-Body Motion It s going to be easiest to find the equations of motion for the object in the body frame i.e., the frame where the axes are principal axes In general, we can

More information

Robot Dynamics Lecture Notes. Robotic Systems Lab, ETH Zurich

Robot Dynamics Lecture Notes. Robotic Systems Lab, ETH Zurich Robot Dynamics Lecture Notes Robotic Systems Lab, ETH Zurich HS 217 Contents 1 Introduction 1 1.1 Nomenclature.............................. 2 1.2 Operators................................ 3 2 Kinematics

More information

NMT EE 589 & UNM ME 482/582 ROBOT ENGINEERING. Dr. Stephen Bruder NMT EE 589 & UNM ME 482/582

NMT EE 589 & UNM ME 482/582 ROBOT ENGINEERING. Dr. Stephen Bruder NMT EE 589 & UNM ME 482/582 NM EE 589 & UNM ME 48/58 ROBO ENGINEERING Dr. Stephen Bruder NM EE 589 & UNM ME 48/58 5. Robot Dynamics 5. he Microbot Arm Dynamic Model A Second Dynamic Model Example: he Microbot Robot Arm he Denavit-Hartenberg

More information

3 Space curvilinear motion, motion in non-inertial frames

3 Space curvilinear motion, motion in non-inertial frames 3 Space curvilinear motion, motion in non-inertial frames 3.1 In-class problem A rocket of initial mass m i is fired vertically up from earth and accelerates until its fuel is exhausted. The residual mass

More information

Lecture Note 7: Switching Stabilization via Control-Lyapunov Function

Lecture Note 7: Switching Stabilization via Control-Lyapunov Function ECE7850: Hybrid Systems:Theory and Applications Lecture Note 7: Switching Stabilization via Control-Lyapunov Function Wei Zhang Assistant Professor Department of Electrical and Computer Engineering Ohio

More information

Pseudoinverse and Adjoint Operators

Pseudoinverse and Adjoint Operators ECE 275AB Lecture 5 Fall 2008 V1.1 c K. Kreutz-Delgado, UC San Diego p. 1/1 Lecture 5 ECE 275A Pseudoinverse and Adjoint Operators ECE 275AB Lecture 5 Fall 2008 V1.1 c K. Kreutz-Delgado, UC San Diego p.

More information

Chapter 1. Rigid Body Kinematics. 1.1 Introduction

Chapter 1. Rigid Body Kinematics. 1.1 Introduction Chapter 1 Rigid Body Kinematics 1.1 Introduction This chapter builds up the basic language and tools to describe the motion of a rigid body this is called rigid body kinematics. This material will be the

More information

Rigid Body Motion. Greg Hager Simon Leonard

Rigid Body Motion. Greg Hager Simon Leonard Rigid ody Motion Greg Hager Simon Leonard Overview Different spaces used in robotics and why we need to get from one space to the other Focus on Cartesian space Transformation between two Cartesian coordinate

More information

Robotics. Dynamics. Marc Toussaint U Stuttgart

Robotics. Dynamics. Marc Toussaint U Stuttgart Robotics Dynamics 1D point mass, damping & oscillation, PID, dynamics of mechanical systems, Euler-Lagrange equation, Newton-Euler recursion, general robot dynamics, joint space control, reference trajectory

More information

Rigid Object. Chapter 10. Angular Position. Angular Position. A rigid object is one that is nondeformable

Rigid Object. Chapter 10. Angular Position. Angular Position. A rigid object is one that is nondeformable Rigid Object Chapter 10 Rotation of a Rigid Object about a Fixed Axis A rigid object is one that is nondeformable The relative locations of all particles making up the object remain constant All real objects

More information

Kinematics. Basilio Bona. Semester 1, DAUIN Politecnico di Torino. B. Bona (DAUIN) Kinematics Semester 1, / 15

Kinematics. Basilio Bona. Semester 1, DAUIN Politecnico di Torino. B. Bona (DAUIN) Kinematics Semester 1, / 15 Kinematics Basilio Bona DAUIN Politecnico di Torino Semester 1, 2014-15 B. Bona (DAUIN) Kinematics Semester 1, 2014-15 1 / 15 Introduction The kinematic quantities used are: position r, linear velocity

More information

Lecture 14: Kinesthetic haptic devices: Higher degrees of freedom

Lecture 14: Kinesthetic haptic devices: Higher degrees of freedom ME 327: Design and Control of Haptic Systems Autumn 2018 Lecture 14: Kinesthetic haptic devices: Higher degrees of freedom Allison M. Okamura Stanford University (This lecture was not given, but the notes

More information

PC4262 Remote Sensing Scattering and Absorption

PC4262 Remote Sensing Scattering and Absorption PC46 Remote Sensing Scattering and Absorption Dr. S. C. Liew, Jan 003 crslsc@nus.edu.sg Scattering by a single particle I(θ, φ) dφ dω F γ A parallel beam of light with a flux density F along the incident

More information

13 Path Planning Cubic Path P 2 P 1. θ 2

13 Path Planning Cubic Path P 2 P 1. θ 2 13 Path Planning Path planning includes three tasks: 1 Defining a geometric curve for the end-effector between two points. 2 Defining a rotational motion between two orientations. 3 Defining a time function

More information

Rotational & Rigid-Body Mechanics. Lectures 3+4

Rotational & Rigid-Body Mechanics. Lectures 3+4 Rotational & Rigid-Body Mechanics Lectures 3+4 Rotational Motion So far: point objects moving through a trajectory. Next: moving actual dimensional objects and rotating them. 2 Circular Motion - Definitions

More information

Kinematics. Basilio Bona. October DAUIN - Politecnico di Torino. Basilio Bona (DAUIN - Politecnico di Torino) Kinematics October / 15

Kinematics. Basilio Bona. October DAUIN - Politecnico di Torino. Basilio Bona (DAUIN - Politecnico di Torino) Kinematics October / 15 Kinematics Basilio Bona DAUIN - Politecnico di Torino October 2013 Basilio Bona (DAUIN - Politecnico di Torino) Kinematics October 2013 1 / 15 Introduction The kinematic quantities used are: position r,

More information

PHYSICS I. Lecture 1. Charudatt Kadolkar. Jul-Nov IIT Guwahati

PHYSICS I. Lecture 1. Charudatt Kadolkar. Jul-Nov IIT Guwahati PHYSICS I Lecture 1 Charudatt Kadolkar IIT Guwahati Jul-Nov 2014 Section 1 Introduction to the Course Syllabus Topics Classical Mechanics: Kinetic Energy rest mass energy Syllabus Topics Classical Mechanics:

More information

NONLINEAR MECHANICAL SYSTEMS (MECHANISMS)

NONLINEAR MECHANICAL SYSTEMS (MECHANISMS) NONLINEAR MECHANICAL SYSTEMS (MECHANISMS) The analogy between dynamic behavior in different energy domains can be useful. Closer inspection reveals that the analogy is not complete. One key distinction

More information

Institute of Geometry, Graz, University of Technology Mobile Robots. Lecture notes of the kinematic part of the lecture

Institute of Geometry, Graz, University of Technology   Mobile Robots. Lecture notes of the kinematic part of the lecture Institute of Geometry, Graz, University of Technology www.geometrie.tugraz.at Institute of Geometry Mobile Robots Lecture notes of the kinematic part of the lecture Anton Gfrerrer nd Edition 4 . Contents

More information

Module II: Relativity and Electrodynamics

Module II: Relativity and Electrodynamics Module II: Relativity and Electrodynamics Lecture 2: Lorentz transformations of observables Amol Dighe TIFR, Mumbai Outline Length, time, velocity, acceleration Transformations of electric and magnetic

More information

Numerical Methods for Rigid Multibody Dynamics

Numerical Methods for Rigid Multibody Dynamics Numerical Methods for Rigid Multibody Dynamics Claus Führer Centre for Mathematical Sciences Lund University Lappenranta 2012 Unit 0: Preface These notes serve as a skeleton for the compact course. They

More information

12. Foundations of Statics Mechanics of Manipulation

12. Foundations of Statics Mechanics of Manipulation 12. Foundations of Statics Mechanics of Manipulation Matt Mason matt.mason@cs.cmu.edu http://www.cs.cmu.edu/~mason Carnegie Mellon Lecture 12. Mechanics of Manipulation p.1 Lecture 12. Foundations of statics.

More information

Dynamics modeling of an electro-hydraulically actuated system

Dynamics modeling of an electro-hydraulically actuated system Dynamics modeling of an electro-hydraulically actuated system Pedro Miranda La Hera Dept. of Applied Physics and Electronics Umeå University xavier.lahera@tfe.umu.se Abstract This report presents a discussion

More information

ECE531 Lecture 10b: Maximum Likelihood Estimation

ECE531 Lecture 10b: Maximum Likelihood Estimation ECE531 Lecture 10b: Maximum Likelihood Estimation D. Richard Brown III Worcester Polytechnic Institute 05-Apr-2011 Worcester Polytechnic Institute D. Richard Brown III 05-Apr-2011 1 / 23 Introduction So

More information

Articulated body dynamics

Articulated body dynamics Articulated rigid bodies Articulated body dynamics Beyond human models How would you represent a pose? Quadraped animals Wavy hair Animal fur Plants Maximal vs. reduced coordinates How are things connected?

More information