Robotics 1 Inverse kinematics

Size: px
Start display at page:

Download "Robotics 1 Inverse kinematics"

Transcription

1 Robotics 1 Inverse kinematics Prof. Alessandro De Luca Robotics 1 1

2 Inverse kinematics what are we looking for? direct kinematics is always unique; how about inverse kinematics for this 6R robot? Robotics 1

3 Inverse kinematics problem! given a desired end-effector pose (position + orientation), find the values of the joint variables that will realize it! a synthesis problem, with input data in the form! T = R p classical formulation: inverse kinematics for a given end-effector pose! a typical nonlinear problem! existence of a solution (workspace definition)! uniqueness/multiplicity of solutions! solution methods p " r =, or any other task vector! generalized formulation: inverse kinematics for a given value of task variables Robotics 1 3

4 Solvability and robot workspace! primary workspace WS 1 : set of all positions p that can be reached with at least one orientation (! or R)! out of WS 1 there is no solution to the problem! for p " WS 1 and a suitable! (or R) there is at least one solution! secondary (or dexterous) workspace WS : set of positions p that can be reached with any orientation (among those feasible for the robot direct kinematics)! for p " WS there is at least one solution for any feasible! (or R)! WS # WS 1 Robotics 1 4

5 Workspace of Fanuc R-000i/165F section for a constant angle $ 1 WS 1 (! WS for spherical wrist without joint limits) rotating the base joint angle $ 1 Robotics 1 5

6 Workspace of planar R arm y p orientations l 1 +l l q l 1 -l l 1! if l 1 % l q 1! WS 1 = {p " R : l 1 -l &!p!& l 1 +l }! WS = '! if l 1 = l = "! WS 1 = {p " R :!p!& "} x (WS 1 inner and outer boundaries 1 orientation! WS = {p = 0} (infinite number of feasible orientations at the origin) Robotics 1 6

7 Wrist position and E-E pose inverse solutions for an articulated 6R robot LEFT DOWN Unimation PUMA 560 RIGHT DOWN 4 inverse solutions out of singularities (for the position of the wrist center only) LEFT UP 8 inverse solutions considering the complete E-E pose (spherical wrist: alternative solutions for the last 3 joints) RIGHT UP Robotics 1 7

8 Counting and visualizing the 8 solutions to the inverse kinematics of a Unimation Puma 560 RIGHT UP RIGHT DOWN LEFT UP LEFT DOWN Robotics 1 8

9 Multiplicity of solutions some examples! E-E positioning of a planar R robot arm! regular solutions in WS 1! 1 solution on (WS 1! for l 1 = l : ) solutions in WS singular solutions! E-E positioning of an articulated elbow-type 3R robot arm! 4 regular solutions in WS 1! spatial 6R robot arms! & 16 distinct solutions, out of singularities: this upper bound of solutions was shown to be attained by a particular instance of orthogonal robot, i.e., with twist angles * i = 0 or ±+/ (,i)! analysis based on algebraic transformations of robot kinematics! transcendental equations are transformed into a single polynomial equation of one variable! seek for an equivalent polynomial equation of the least possible degree Robotics 1 9

10 A planar 3R arm workspace and number/type of inverse solutions y q 3 l1 = l = l 3 = " p l 1 l q l 3 WS 1 = {p " R :!p!& 3"} WS = {p " R :!p!& "} q 1 x any planar orientation is feasible in WS 1. in WS 1 : ) 1 regular solutions (except for. and 3.), at which the E-E can take a continuum of ) orientations (but not all orientations in the plane!). if!p!= 3" : only 1 solution, singular 3. if!p!= " : ) 1 solutions, 3 of which singular 4. if!p!< " : ) 1 regular solutions (never singular) Robotics 1 10

11 ! if m = n!! solutions Multiplicity of solutions summary of the general cases! a finite number of solutions (regular/generic case)! degenerate solutions: infinite or finite set, but anyway different in number from the generic case (singularity)! if m < n (robot is redundant for the kinematic task)!! solutions! ) n-m solutions (regular/generic case)! a finite or infinite number of singular solutions! use of the term singularity will become clearer when dealing with differential kinematics! instantaneous velocity mapping from joint to task velocity! lack of full rank of the associated m"n Jacobian matrix J(q) Robotics 1 11

12 Dexter robot (8R arm)! m = 6 (position and orientation of E-E)! n = 8 (all revolute joints)! ) inverse kinematic solutions (redundancy degree = n-m = ) video exploring inverse kinematic solutions by a self-motion Robotics 1 1

13 Solution methods ANALYTICAL solution (in closed form) " preferred, if it can be found * " use ad-hoc geometric inspection " algebraic methods (solution of polynomial equations) " systematic ways for generating a reduced set of equations to be solved * sufficient conditions for 6-dof arms 3 consecutive rotational joint axes are incident (e.g., spherical wrist), or 3 consecutive rotational joint axes are parallel D. Pieper, PhD thesis, Stanford University, 1968 NUMERICAL solution (in iterative form) " certainly needed if n>m (redundant case), or at/close to singularities " slower, but easier to be set up " in its basic form, it uses the (analytical) Jacobian matrix of the direct kinematics map J r (q) = (f r (q) (q " Newton method, Gradient method, and so on Robotics 1 13

14 y p y Inverse kinematics of planar R arm l q p direct kinematics p x = l 1 c 1 + l c 1 l 1 p y = l 1 s 1 + l s 1 q 1 p x x data q 1, q unknowns squaring and summing the equations of the direct kinematics p x + p y - (l 1 + l ) = l 1 l (c 1 c 1 + s 1 s 1 ) = l 1 l c and from this in analytical form c = (p x + p y - l 1 - l )/ l 1 l, s = ±-1 - c q = ATAN {s, c } must be in [-1,1] (else, point p is outside robot workspace!) solutions Robotics 1 14

15 y p y. Inverse kinematics of R arm (cont d) q 1 * q p p x solutions (one for each value of s ) x by geometric inspection q 1 = * -. q 1 = ATAN {p y, p x } - ATAN {l s, l 1 + l c } q 1 q p note: difference of ATAN needs to be re-expressed in (-+, +]! {q 1,q } UP/LEFT {q q 1,q } DOWN/RIGHT q 1 q e q have same absolute value, but opposite signs Robotics 1 15

16 Algebraic solution for q 1 another solution method p x = l 1 c 1 + l c 1 = l 1 c 1 + l (c 1 c - s 1 s ) p y = l 1 s 1 + l s 1 = l 1 s 1 + l (s 1 c + c 1 s ) linear in s 1 and c 1 l 1 + l c - l s c 1 = p x l s l 1 + l c s 1 p y except for l 1 =l and c =-1 det = (l 1 + l + l 1 l c ) > 0 being then q 1 undefined (singular case: ) 1 solutions) q 1 = ATAN {s 1, c 1 } = ATAN {(p y (l 1 +l c )-p x l s )/det, (p x (l 1 +l c )+p y l s )/det} notes: a) this method provides directly the result in (-+, +] b) when evaluating ATAN, det > 0 can be eliminated from the expressions of s 1 and c 1 Robotics 1 16

17 Inverse kinematics of polar (RRP) arm q is NOT a DH variable! p z q 3 p x = q 3 c c 1 p y = q 3 c s 1 d 1 q p z = d 1 + q 3 s p x + p y + (p z - d 1 ) = q 3 p y q 3 = + -p x + p y + (p z - d 1 ) p x q 1 our choice: take here only the positive value... if q 3 = 0, then q 1 and q remain both undefined (stop); else q = ATAN{(p z - d 1 )/q 3, ± -(p x + p y )/q 3 } if p x +p y = 0, then q 1 remains undefined (stop); else q 1 = ATAN{p y /c, p x /c } ( regular solutions {q 1,q,q 3 }) (if it stops, a singular case: ) or ) 1 solutions) Robotics 1 we have eliminated q 3 >0 from both arguments! 17

18 Inverse kinematics for robots with spherical wrist j6 first 3 robot joints of any type (RRR, RRP, PPP, ) W z 4 z 3 z 5 y 6 x 6 O 6 = p z 6 = a z 0 j5 j4 d 6 x 0 j1 y 0 find q 1,, q 6 from the input data: p (origin O 6 ) R = [n s a] (orientation of RF 6 ) 1. W = p - d 6 a / q 1, q, q 3 (inverse position kinematics for main axes). R = 0 R 3 (q 1, q, q 3 ) 3 R 6 (q 4, q 5, q 6 ) / 3 R 6 (q 4, q 5, q 6 ) = 0 R T 3 R / q 4, q 5, q 6 (inverse orientation given known, Euler ZYZ or ZXZ kinematics for wrist) after 1. rotation matrix Robotics 1 18

19 6R example: Unimation PUMA 600 spherical wrist n = 0 x 6 (q) s = 0 y 6 (q) a function of q 1, q, q 3 only! a = 0 z 6 (q) p = 0 6 (q) 8 different inverse solutions that can be found in closed form (see Paul, Shimano, Mayer; 1981) here d 6 =0, Robotics 1 so that 0 6 =W directly 19

20 Numerical solution of inverse kinematics problems! use when a closed-form solution q to r d = f r (q) does not exist or is too hard to be found! J r (q) = (f r (analytical Jacobian) (q! Newton method (here for m=n)! r d = f r (q) = f r (q k ) + J r (q k ) (q - q k ) + o(!q - q k! ) q k+1 = q k + J r -1 (q k ) [r d - f r (q k )] 0 neglected! convergence if q 0 (initial guess) is close enough to some q * : f r (q * ) = r d! problems near singularities of the Jacobian matrix J r (q)! in case of robot redundancy (m<n), use the pseudo-inverse J r# (q)! has quadratic convergence rate when near to solution (fast!) Robotics 1 0

21 Operation of Newton method! in the scalar case, also known as method of the tangent! for a differentiable function f(x), find a root of f(x)=0 by iterating as x k+1 = x k " f(x k ) f'(x k ) an approximating sequence { x 1,x,x 3,x 4,x 5,...} animation from Robotics 1 1

22 Numerical solution of inverse kinematics problems (cont d)! Gradient method (max descent)! minimize the error function H(q) = #!r d - f r (q)! = # [r d - f r (q)] T [r d - f r (q)] q k+1 = q k - * 1 q H(q k ) from 1H(q) = - J rt (q) [r d - f r (q)], we get q k+1 = q k + * J rt (q k ) [r d - f r (q k )]! the scalar step size * > 0 should be chosen so as to guarantee a decrease of the error function at each iteration (too large values for * may lead the method to miss the minimum)! when the step size * is too small, convergence is extremely slow Robotics 1

23 Revisited as a feedback scheme r d + - r e J rt (q) f r (q). q q(0) 3 q r d = cost (* = 1) e = r d - f r (q) / 0 4 closed-loop equilibrium e=0 is asymptotically stable V = # e T e 5 0 Lyapunov candidate function... V = e T e = e T d ( q dt (r d - f r (q)) = - et J r = - e T J r J rt e & 0. V = 0 4 e " Ker(J rt ) in particular e = 0 asymptotic stability Robotics 1 3

24 Properties of Gradient method! computationally simpler: Jacobian transpose, rather than its (pseudo)-inverse! direct use also for robots that are redundant for the task! may not converge to a solution, but it never diverges! the discrete time evolution of the continuous scheme q k+1 = q k + 6T J rt (q k ) [r d - f(q k )] (* = 6T) is equivalent to an iteration of the Gradient method! scheme can be accelerated by using a gain matrix K>0. q = J rt (q) K e note: K can be used also to escape from being stuck in a stationary point, by rotating the error e out of the kernel of J r T (if a singularity is encountered) Robotics 1 4

25 A case study analytic expressions of Newton and gradient iterations! R robot with l 1 =l =1, desired end-effector position r d = (1,1)! direct kinematic function and error " f r (q) = c 1 + c 1 % " $ ' e = r # s 1 + s 1 & d - f r (q) = $ 1% ' 1 - f # & r (q)! Jacobian matrix J r (q) = " f r(q) " q = # -(s + s ) -s & % ( $ c 1 + c 1 c 1 '! Newton versus Gradient iteration det J r (q) q k+1 = q k + J -1 r (q k ) 1 " c 1 s 1 % $ ' s #-(c 1 + c 1 ) -(s 1 + s 1 )& # " -(s + s ) c + c & % ( $ -s 1 c 1 ' J r T (q k ) " 1- (c 1 + c 1 )% $ ' # 1- (s 1 + s 1 )& Robotics 1 5 q=q k q=q k e k q=q k

26 Error function! R robot with l1=l=1, desired end-effector position rd = (1,1) e = rd - fr(q) plot of!e! as a function of q = (q1,q) Robotics 1 two local minima (inverse kinematic solutions) 6

27 Error reduction by Gradient method!! flow of iterations along the negative (or anti-) gradient two possible cases: convergence or stuck (at zero gradient) start one solution. local maximum (stop if this is the initial guess). saddle point (stop after some iterations) another start......the other solution (q1,q) =(0,!/) (q1,q) =(!/,-!/) Robotics 1 (q1,q)max =(-3!/4,0) (q1,q)saddle =(!/4,0) e " Ker(JrT)! 7

28 ! initial guess q 0 Issues in implementation! only one inverse solution is generated for each guess! multiple initializations for obtaining other solutions! optimal step size * in Gradient method! a constant step may work good initially, but not close to the solution (or vice versa)! an adaptive one-dimensional line search (e.g., Armijo s rule) could be used to choose the best * at each iteration! stopping criteria Cartesian error (possibly, separate for position and orientation)!r d - f(q k )! $ #! understanding closeness to singularities algorithm increment!q k+1 -q k! $ # q $ min {J(q k )} % $ 0 numerical conditioning of Jacobian matrix (SVD) (or a simpler test on its determinant, for m=n) Robotics 1 8

29 Numerical tests on RRP robot! RRP/polar robot: desired E-E position r d = p d = (1, 1,1) see slide 17, d 1 =0.5! the two (known) analytic solutions, with q 3 % 0, are: q * = (0.7854, , 1.5) q ** = (q 1* +, + q *, q 3* ) = (-.356,.8018, 1.5)! norms # = 10-5 (max Cartesian error), # q =10-6 (min joint increment)! k max =15 (max iterations), det(j r ) $ 10-4 (closeness to singularity)! numerical performance of Gradient (with different *) vs. Newton! test 1: q 0 = (0, 0, 1) as initial guess! test : q 0 = (-+/4, +/, 1) singular start, since c =0 (see slide 17)! test 3: q 0 = (0, +/, 0) double singular start, since also q 3 =0! solution and plots with Matlab code Robotics 1 9

30 Numerical test! -1 test 1: q0 = (0, 0, 1) as initial guess; evolution of error norm Gradient: * = 0.5 Gradient: * = 1 too large, oscillates around solution slow, 15 (max) iterations good, converges in 11 iterations 0.57䏙10-5 Newton very fast, converges in 5 iterations Gradient: * = 0.7 Cartesian errors component-wise ex ey ez Robotics 䏙

31 Numerical test - 1! test 1: q 0 = (0, 0, 1) as initial guess; evolution of joint variables Gradient: * = 1 Gradient: * = 0.7 not converging to a solution converges in 11 iterations Newton converges in 5 iterations both to solution q * = (0.7854, , 1.5) Robotics 1 31

32 Numerical test -! test : q 0 = (-+/4, +/, 1): singular start error norms Gradient * = 0.7 Newton with check of singularity: blocked at start without check: it diverges! starts toward solution, but slowly stops (in singularity): when Cartesian error vector e Ker(J rt ) joint variables!! Robotics 1 3

33 Numerical test - 3! test 3: q 0 = (0, +/, 0): double singular start error norm Gradient (with * = 0.7) starts toward solution exits the double singularity slowly converges in 19 iterations to the solution q * =(0.7854, , 1.5) Newton is either blocked at start or (w/o check) explodes (NaN)!! Cartesian errors joint variables Robotics 1 33

34 Final remarks! an efficient iterative scheme can be devised by combining! initial iterations with Gradient method ( sure but slow, having linear convergence rate)! switch then to Newton method (quadratic terminal convergence rate)! joint range limits are considered only at the end! check if the found solution is feasible, as for analytical methods! if the problem has to be solved on-line! execute iterations and associate an actual robot motion: repeat steps at times t 0, t 1 =t 0 +T,..., t k =t k-1 +T (e.g., every T=40 ms)! the good choice for the initial q 0 at t k is the solution of the previous problem at t k-1 (gives continuity, needs only 1- Newton iterations)! crossing of singularities and handling of joint range limits need special care in this case! Jacobian-based inversion schemes are used also for kinematic control, along a continuous task trajectory r d (t) Robotics 1 34

Robotics 1 Inverse kinematics

Robotics 1 Inverse kinematics Robotics 1 Inverse kinematics Prof. Alessandro De Luca Robotics 1 1 Inverse kinematics what are we looking for? direct kinematics is always unique; how about inverse kinematics for this 6R robot? Robotics

More information

Robotics 1 Inverse kinematics

Robotics 1 Inverse kinematics Robotics 1 Inverse kinematics Prof. Alessandro De Luca Robotics 1 1 Inverse kinematics what are we looking for? direct kinematics is always unique; how about inverse kinematics for this 6R robot? Robotics

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

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

Robotics I. February 6, 2014

Robotics I. February 6, 2014 Robotics I February 6, 214 Exercise 1 A pan-tilt 1 camera sensor, such as the commercial webcams in Fig. 1, is mounted on the fixed base of a robot manipulator and is used for pointing at a (point-wise)

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

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

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

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

Robotics I. April 1, the motion starts and ends with zero Cartesian velocity and acceleration;

Robotics I. April 1, the motion starts and ends with zero Cartesian velocity and acceleration; Robotics I April, 6 Consider a planar R robot with links of length l = and l =.5. he end-effector should move smoothly from an initial point p in to a final point p fin in the robot workspace so that the

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

Lecture «Robot Dynamics» : Kinematics 3

Lecture «Robot Dynamics» : Kinematics 3 Lecture «Robot Dynamics» : Kinematics 3 151-0851-00 V lecture: CAB G11 Tuesday 10:15-12:00, every week exercise: HG G1 Wednesday 8:15-10:00, according to schedule (about every 2nd week) office hour: LEE

More information

Robotics 2 Robot Interaction with the Environment

Robotics 2 Robot Interaction with the Environment Robotics 2 Robot Interaction with the Environment Prof. Alessandro De Luca Robot-environment interaction a robot (end-effector) may interact with the environment! modifying the state of the environment

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

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

A new large projection operator for the redundancy framework

A new large projection operator for the redundancy framework 21 IEEE International Conference on Robotics and Automation Anchorage Convention District May 3-8, 21, Anchorage, Alaska, USA A new large projection operator for the redundancy framework Mohammed Marey

More information

Trajectory Planning from Multibody System Dynamics

Trajectory Planning from Multibody System Dynamics Trajectory Planning from Multibody System Dynamics Pierangelo Masarati Politecnico di Milano Dipartimento di Ingegneria Aerospaziale Manipulators 2 Manipulator: chain of

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

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

Robotics I June 11, 2018

Robotics I June 11, 2018 Exercise 1 Robotics I June 11 018 Consider the planar R robot in Fig. 1 having a L-shaped second link. A frame RF e is attached to the gripper mounted on the robot end effector. A B y e C x e Figure 1:

More information

Robotics I. June 6, 2017

Robotics I. June 6, 2017 Robotics I June 6, 217 Exercise 1 Consider the planar PRPR manipulator in Fig. 1. The joint variables defined therein are those used by the manufacturer and do not correspond necessarily to a Denavit-Hartenberg

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

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

Kinematic representation! Iterative methods! Optimization methods

Kinematic representation! Iterative methods! Optimization methods Human Kinematics Kinematic representation! Iterative methods! Optimization methods Kinematics Forward kinematics! given a joint configuration, what is the position of an end point on the structure?! Inverse

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

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

Control of Mobile Robots

Control of Mobile Robots Control of Mobile Robots Regulation and trajectory tracking Prof. Luca Bascetta (luca.bascetta@polimi.it) Politecnico di Milano Dipartimento di Elettronica, Informazione e Bioingegneria Organization and

More information

Video 8.1 Vijay Kumar. Property of University of Pennsylvania, Vijay Kumar

Video 8.1 Vijay Kumar. Property of University of Pennsylvania, Vijay Kumar Video 8.1 Vijay Kumar 1 Definitions State State equations Equilibrium 2 Stability Stable Unstable Neutrally (Critically) Stable 3 Stability Translate the origin to x e x(t) =0 is stable (Lyapunov stable)

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 z A p AB B RF B z B x B y A rigid body

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

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

q 1 F m d p q 2 Figure 1: An automated crane with the relevant kinematic and dynamic definitions.

q 1 F m d p q 2 Figure 1: An automated crane with the relevant kinematic and dynamic definitions. Robotics II March 7, 018 Exercise 1 An automated crane can be seen as a mechanical system with two degrees of freedom that moves along a horizontal rail subject to the actuation force F, and that transports

More information

Robust Control of Cooperative Underactuated Manipulators

Robust Control of Cooperative Underactuated Manipulators Robust Control of Cooperative Underactuated Manipulators Marcel Bergerman * Yangsheng Xu +,** Yun-Hui Liu ** * Automation Institute Informatics Technology Center Campinas SP Brazil + The Robotics Institute

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

Robotics I. Test November 29, 2013

Robotics I. Test November 29, 2013 Exercise 1 [6 points] Robotics I Test November 9, 013 A DC motor is used to actuate a single robot link that rotates in the horizontal plane around a joint axis passing through its base. The motor is connected

More information

Directional Redundancy for Robot Control

Directional Redundancy for Robot Control ACCEPTED FOR PUBLICATION IN IEEE TRANSACTIONS ON AUTOMATIC CONTROL Directional Redundancy for Robot Control Nicolas Mansard, François Chaumette, Member, IEEE Abstract The paper presents a new approach

More information

Algorithms for Sensor-Based Robotics: Potential Functions

Algorithms for Sensor-Based Robotics: Potential Functions Algorithms for Sensor-Based Robotics: Potential Functions Computer Science 336 http://www.cs.jhu.edu/~hager/teaching/cs336 Professor Hager http://www.cs.jhu.edu/~hager The Basic Idea A really simple idea:

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

Given U, V, x and θ perform the following steps: a) Find the rotation angle, φ, by which u 1 is rotated in relation to x 1

Given U, V, x and θ perform the following steps: a) Find the rotation angle, φ, by which u 1 is rotated in relation to x 1 1 The Jacobian can be expressed in an arbitrary frame, such as the base frame located at the first joint, the hand frame located at the end-effector, or the global frame located somewhere else. The SVD

More information

Mathematical optimization

Mathematical optimization Optimization Mathematical optimization Determine the best solutions to certain mathematically defined problems that are under constrained determine optimality criteria determine the convergence of the

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

Math 302 Outcome Statements Winter 2013

Math 302 Outcome Statements Winter 2013 Math 302 Outcome Statements Winter 2013 1 Rectangular Space Coordinates; Vectors in the Three-Dimensional Space (a) Cartesian coordinates of a point (b) sphere (c) symmetry about a point, a line, and a

More information

GENG2140, S2, 2012 Week 7: Curve fitting

GENG2140, S2, 2012 Week 7: Curve fitting GENG2140, S2, 2012 Week 7: Curve fitting Curve fitting is the process of constructing a curve, or mathematical function, f(x) that has the best fit to a series of data points Involves fitting lines and

More information

Preliminary Examination in Numerical Analysis

Preliminary Examination in Numerical Analysis Department of Applied Mathematics Preliminary Examination in Numerical Analysis August 7, 06, 0 am pm. Submit solutions to four (and no more) of the following six problems. Show all your work, and justify

More information

Kinematic Analysis of the 6R Manipulator of General Geometry

Kinematic Analysis of the 6R Manipulator of General Geometry Kinematic Analysis of the 6R Manipulator of General Geometry Madhusudan Raghavan Powertrain Systems Research Lab General Motors R&D Center Warren, MI 48090-9055 and Bernard Roth, Professor Design Division

More information

Numerical Methods I Solving Nonlinear Equations

Numerical Methods I Solving Nonlinear Equations Numerical Methods I Solving Nonlinear Equations Aleksandar Donev Courant Institute, NYU 1 donev@courant.nyu.edu 1 MATH-GA 2011.003 / CSCI-GA 2945.003, Fall 2014 October 16th, 2014 A. Donev (Courant Institute)

More information

Chapter 3 Numerical Methods

Chapter 3 Numerical Methods Chapter 3 Numerical Methods Part 2 3.2 Systems of Equations 3.3 Nonlinear and Constrained Optimization 1 Outline 3.2 Systems of Equations 3.3 Nonlinear and Constrained Optimization Summary 2 Outline 3.2

More information

Chapter 3 Numerical Methods

Chapter 3 Numerical Methods Chapter 3 Numerical Methods Part 3 3.4 Differential Algebraic Systems 3.5 Integration of Differential Equations 1 Outline 3.4 Differential Algebraic Systems 3.4.1 Constrained Dynamics 3.4.2 First and Second

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

MULTIVARIABLE CALCULUS, LINEAR ALGEBRA, AND DIFFERENTIAL EQUATIONS

MULTIVARIABLE CALCULUS, LINEAR ALGEBRA, AND DIFFERENTIAL EQUATIONS T H I R D E D I T I O N MULTIVARIABLE CALCULUS, LINEAR ALGEBRA, AND DIFFERENTIAL EQUATIONS STANLEY I. GROSSMAN University of Montana and University College London SAUNDERS COLLEGE PUBLISHING HARCOURT BRACE

More information

Introduction to Mobile Robotics Compact Course on Linear Algebra. Wolfram Burgard, Cyrill Stachniss, Kai Arras, Maren Bennewitz

Introduction to Mobile Robotics Compact Course on Linear Algebra. Wolfram Burgard, Cyrill Stachniss, Kai Arras, Maren Bennewitz Introduction to Mobile Robotics Compact Course on Linear Algebra Wolfram Burgard, Cyrill Stachniss, Kai Arras, Maren Bennewitz Vectors Arrays of numbers Vectors represent a point in a n dimensional space

More information

Minimization of Static! Cost Functions!

Minimization of Static! Cost Functions! Minimization of Static Cost Functions Robert Stengel Optimal Control and Estimation, MAE 546, Princeton University, 2017 J = Static cost function with constant control parameter vector, u Conditions for

More information

Constrained optimization. Unconstrained optimization. One-dimensional. Multi-dimensional. Newton with equality constraints. Active-set method.

Constrained optimization. Unconstrained optimization. One-dimensional. Multi-dimensional. Newton with equality constraints. Active-set method. Optimization Unconstrained optimization One-dimensional Multi-dimensional Newton s method Basic Newton Gauss- Newton Quasi- Newton Descent methods Gradient descent Conjugate gradient Constrained optimization

More information

Math 411 Preliminaries

Math 411 Preliminaries Math 411 Preliminaries Provide a list of preliminary vocabulary and concepts Preliminary Basic Netwon s method, Taylor series expansion (for single and multiple variables), Eigenvalue, Eigenvector, Vector

More information

Linear Algebra and Robot Modeling

Linear Algebra and Robot Modeling Linear Algebra and Robot Modeling Nathan Ratliff Abstract Linear algebra is fundamental to robot modeling, control, and optimization. This document reviews some of the basic kinematic equations and uses

More information

Computational Methods. Least Squares Approximation/Optimization

Computational Methods. Least Squares Approximation/Optimization Computational Methods Least Squares Approximation/Optimization Manfred Huber 2011 1 Least Squares Least squares methods are aimed at finding approximate solutions when no precise solution exists Find the

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

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

Nonlinear Optimization for Optimal Control

Nonlinear Optimization for Optimal Control Nonlinear Optimization for Optimal Control Pieter Abbeel UC Berkeley EECS Many slides and figures adapted from Stephen Boyd [optional] Boyd and Vandenberghe, Convex Optimization, Chapters 9 11 [optional]

More information

ECEN 615 Methods of Electric Power Systems Analysis Lecture 18: Least Squares, State Estimation

ECEN 615 Methods of Electric Power Systems Analysis Lecture 18: Least Squares, State Estimation ECEN 615 Methods of Electric Power Systems Analysis Lecture 18: Least Squares, State Estimation Prof. om Overbye Dept. of Electrical and Computer Engineering exas A&M University overbye@tamu.edu Announcements

More information

Adaptive Robust Tracking Control of Robot Manipulators in the Task-space under Uncertainties

Adaptive Robust Tracking Control of Robot Manipulators in the Task-space under Uncertainties Australian Journal of Basic and Applied Sciences, 3(1): 308-322, 2009 ISSN 1991-8178 Adaptive Robust Tracking Control of Robot Manipulators in the Task-space under Uncertainties M.R.Soltanpour, M.M.Fateh

More information

Vector Derivatives and the Gradient

Vector Derivatives and the Gradient ECE 275AB Lecture 10 Fall 2008 V1.1 c K. Kreutz-Delgado, UC San Diego p. 1/1 Lecture 10 ECE 275A Vector Derivatives and the Gradient ECE 275AB Lecture 10 Fall 2008 V1.1 c K. Kreutz-Delgado, UC San Diego

More information

Nonlinear Optimization

Nonlinear Optimization Nonlinear Optimization (Com S 477/577 Notes) Yan-Bin Jia Nov 7, 2017 1 Introduction Given a single function f that depends on one or more independent variable, we want to find the values of those variables

More information

Mobile Robotics 1. A Compact Course on Linear Algebra. Giorgio Grisetti

Mobile Robotics 1. A Compact Course on Linear Algebra. Giorgio Grisetti Mobile Robotics 1 A Compact Course on Linear Algebra Giorgio Grisetti SA-1 Vectors Arrays of numbers They represent a point in a n dimensional space 2 Vectors: Scalar Product Scalar-Vector Product Changes

More information

CHAPTER 2 EXTRACTION OF THE QUADRATICS FROM REAL ALGEBRAIC POLYNOMIAL

CHAPTER 2 EXTRACTION OF THE QUADRATICS FROM REAL ALGEBRAIC POLYNOMIAL 24 CHAPTER 2 EXTRACTION OF THE QUADRATICS FROM REAL ALGEBRAIC POLYNOMIAL 2.1 INTRODUCTION Polynomial factorization is a mathematical problem, which is often encountered in applied sciences and many of

More information

, b = 0. (2) 1 2 The eigenvectors of A corresponding to the eigenvalues λ 1 = 1, λ 2 = 3 are

, b = 0. (2) 1 2 The eigenvectors of A corresponding to the eigenvalues λ 1 = 1, λ 2 = 3 are Quadratic forms We consider the quadratic function f : R 2 R defined by f(x) = 2 xt Ax b T x with x = (x, x 2 ) T, () where A R 2 2 is symmetric and b R 2. We will see that, depending on the eigenvalues

More information

Introduction to Mobile Robotics Compact Course on Linear Algebra. Wolfram Burgard, Cyrill Stachniss, Maren Bennewitz, Diego Tipaldi, Luciano Spinello

Introduction to Mobile Robotics Compact Course on Linear Algebra. Wolfram Burgard, Cyrill Stachniss, Maren Bennewitz, Diego Tipaldi, Luciano Spinello Introduction to Mobile Robotics Compact Course on Linear Algebra Wolfram Burgard, Cyrill Stachniss, Maren Bennewitz, Diego Tipaldi, Luciano Spinello Vectors Arrays of numbers Vectors represent a point

More information

CHAPTER 2: QUADRATIC PROGRAMMING

CHAPTER 2: QUADRATIC PROGRAMMING CHAPTER 2: QUADRATIC PROGRAMMING Overview Quadratic programming (QP) problems are characterized by objective functions that are quadratic in the design variables, and linear constraints. In this sense,

More information

Math, Numerics, & Programming. (for Mechanical Engineers)

Math, Numerics, & Programming. (for Mechanical Engineers) DRAFT V1.2 From Math, Numerics, & Programming (for Mechanical Engineers) Masayuki Yano James Douglass Penn George Konidaris Anthony T Patera September 212 The Authors. License: Creative Commons Attribution-Noncommercial-Share

More information

5 Handling Constraints

5 Handling Constraints 5 Handling Constraints Engineering design optimization problems are very rarely unconstrained. Moreover, the constraints that appear in these problems are typically nonlinear. This motivates our interest

More information

Structural topology, singularity, and kinematic analysis. J-P. Merlet HEPHAISTOS project INRIA Sophia-Antipolis

Structural topology, singularity, and kinematic analysis. J-P. Merlet HEPHAISTOS project INRIA Sophia-Antipolis Structural topology, singularity, and kinematic analysis J-P. Merlet HEPHAISTOS project INRIA Sophia-Antipolis 1 Parallel robots Definitions: a closed-loop mechanism whose end-effector is linked to the

More information

CS 542G: Robustifying Newton, Constraints, Nonlinear Least Squares

CS 542G: Robustifying Newton, Constraints, Nonlinear Least Squares CS 542G: Robustifying Newton, Constraints, Nonlinear Least Squares Robert Bridson October 29, 2008 1 Hessian Problems in Newton Last time we fixed one of plain Newton s problems by introducing line search

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

1. Method 1: bisection. The bisection methods starts from two points a 0 and b 0 such that

1. Method 1: bisection. The bisection methods starts from two points a 0 and b 0 such that Chapter 4 Nonlinear equations 4.1 Root finding Consider the problem of solving any nonlinear relation g(x) = h(x) in the real variable x. We rephrase this problem as one of finding the zero (root) of a

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

APPENDIX A. Background Mathematics. A.1 Linear Algebra. Vector algebra. Let x denote the n-dimensional column vector with components x 1 x 2.

APPENDIX A. Background Mathematics. A.1 Linear Algebra. Vector algebra. Let x denote the n-dimensional column vector with components x 1 x 2. APPENDIX A Background Mathematics A. Linear Algebra A.. Vector algebra Let x denote the n-dimensional column vector with components 0 x x 2 B C @. A x n Definition 6 (scalar product). The scalar product

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

Introduction to Mobile Robotics Compact Course on Linear Algebra. Wolfram Burgard, Bastian Steder

Introduction to Mobile Robotics Compact Course on Linear Algebra. Wolfram Burgard, Bastian Steder Introduction to Mobile Robotics Compact Course on Linear Algebra Wolfram Burgard, Bastian Steder Reference Book Thrun, Burgard, and Fox: Probabilistic Robotics Vectors Arrays of numbers Vectors represent

More information

MATHEMATICS COMPREHENSIVE EXAM: IN-CLASS COMPONENT

MATHEMATICS COMPREHENSIVE EXAM: IN-CLASS COMPONENT MATHEMATICS COMPREHENSIVE EXAM: IN-CLASS COMPONENT The following is the list of questions for the oral exam. At the same time, these questions represent all topics for the written exam. The procedure for

More information

Unconstrained optimization

Unconstrained optimization Chapter 4 Unconstrained optimization An unconstrained optimization problem takes the form min x Rnf(x) (4.1) for a target functional (also called objective function) f : R n R. In this chapter and throughout

More information

Numerical Methods for Inverse Kinematics

Numerical Methods for Inverse Kinematics Numerical Methods for Inverse Kinematics Niels Joubert, UC Berkeley, CS184 2008-11-25 Inverse Kinematics is used to pose models by specifying endpoints of segments rather than individual joint angles.

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

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

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

Ridig Body Motion Homogeneous Transformations

Ridig Body Motion Homogeneous Transformations Ridig Body Motion Homogeneous Transformations Claudio Melchiorri Dipartimento di Elettronica, Informatica e Sistemistica (DEIS) Università di Bologna email: claudio.melchiorri@unibo.it C. Melchiorri (DEIS)

More information

A nonlinear equation is any equation of the form. f(x) = 0. A nonlinear equation can have any number of solutions (finite, countable, uncountable)

A nonlinear equation is any equation of the form. f(x) = 0. A nonlinear equation can have any number of solutions (finite, countable, uncountable) Nonlinear equations Definition A nonlinear equation is any equation of the form where f is a nonlinear function. Nonlinear equations x 2 + x + 1 = 0 (f : R R) f(x) = 0 (x cos y, 2y sin x) = (0, 0) (f :

More information

Chapter 3: The Derivative in Graphing and Applications

Chapter 3: The Derivative in Graphing and Applications Chapter 3: The Derivative in Graphing and Applications Summary: The main purpose of this chapter is to use the derivative as a tool to assist in the graphing of functions and for solving optimization problems.

More information

ME451 Kinematics and Dynamics of Machine Systems

ME451 Kinematics and Dynamics of Machine Systems ME451 Kinematics and Dynamics of Machine Systems Newton-Raphson Method 4.5 Closing remarks, Kinematics Analysis October 25, 2010 Dan Negrut, 2011 ME451, UW-Madison Success is going from failure to failure

More information

1 Newton s Method. Suppose we want to solve: x R. At x = x, f (x) can be approximated by:

1 Newton s Method. Suppose we want to solve: x R. At x = x, f (x) can be approximated by: Newton s Method Suppose we want to solve: (P:) min f (x) At x = x, f (x) can be approximated by: n x R. f (x) h(x) := f ( x)+ f ( x) T (x x)+ (x x) t H ( x)(x x), 2 which is the quadratic Taylor expansion

More information

Lecture Notes: Geometric Considerations in Unconstrained Optimization

Lecture Notes: Geometric Considerations in Unconstrained Optimization Lecture Notes: Geometric Considerations in Unconstrained Optimization James T. Allison February 15, 2006 The primary objectives of this lecture on unconstrained optimization are to: Establish connections

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

LECTURE NOTES ELEMENTARY NUMERICAL METHODS. Eusebius Doedel

LECTURE NOTES ELEMENTARY NUMERICAL METHODS. Eusebius Doedel LECTURE NOTES on ELEMENTARY NUMERICAL METHODS Eusebius Doedel TABLE OF CONTENTS Vector and Matrix Norms 1 Banach Lemma 20 The Numerical Solution of Linear Systems 25 Gauss Elimination 25 Operation Count

More information

Linear Regression. Robot Image Credit: Viktoriya Sukhanova 123RF.com

Linear Regression. Robot Image Credit: Viktoriya Sukhanova 123RF.com Linear Regression These slides were assembled by Eric Eaton, with grateful acknowledgement of the many others who made their course materials freely available online. Feel free to reuse or adapt these

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

Scientific Computing: An Introductory Survey

Scientific Computing: An Introductory Survey Scientific Computing: An Introductory Survey Chapter 5 Nonlinear Equations Prof. Michael T. Heath Department of Computer Science University of Illinois at Urbana-Champaign Copyright c 2002. Reproduction

More information

Review of some mathematical tools

Review of some mathematical tools MATHEMATICAL FOUNDATIONS OF SIGNAL PROCESSING Fall 2016 Benjamín Béjar Haro, Mihailo Kolundžija, Reza Parhizkar, Adam Scholefield Teaching assistants: Golnoosh Elhami, Hanjie Pan Review of some mathematical

More information

Optimal control problems with PDE constraints

Optimal control problems with PDE constraints Optimal control problems with PDE constraints Maya Neytcheva CIM, October 2017 General framework Unconstrained optimization problems min f (q) q x R n (real vector) and f : R n R is a smooth function.

More information

Analysis of the Acceleration Characteristics of Non-Redundant Manipulators

Analysis of the Acceleration Characteristics of Non-Redundant Manipulators Analysis of the Acceleration Characteristics of Non-Redundant Manipulators Alan Bowling and Oussama Khatib Robotics Laboratory Computer Science Depart men t Stanford University Stanford, CA, USA 94305

More information

Introduction to gradient descent

Introduction to gradient descent 6-1: Introduction to gradient descent Prof. J.C. Kao, UCLA Introduction to gradient descent Derivation and intuitions Hessian 6-2: Introduction to gradient descent Prof. J.C. Kao, UCLA Introduction Our

More information

Numerical Methods. Root Finding

Numerical Methods. Root Finding Numerical Methods Solving Non Linear 1-Dimensional Equations Root Finding Given a real valued function f of one variable (say ), the idea is to find an such that: f() 0 1 Root Finding Eamples Find real

More information