Forward kinematics and Denavit Hartenburg convention Prof. Enver Tatlicioglu Department of Electrical & Electronics Engineering Izmir Institute of Technology Chapter 5 Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 1 / 57
Kinematics Kinematics is the study of motion without regard to the forces which cause it. Within the science of kinematics one studies position, velocity and acceleration and all higher order derivatives of the position variable. The study of kinematics of robot manipulators refer to all the geometric and time based properties of the motion, and in particular how various links move with respect to one and other. The central aim of this lecture is finding a method to obtain position and orientation of the robot manipulator s end effector (relative to the base of the robot manipulator) as a function of the joint variables. This is called forward kinematics or direct kinematics. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 2 / 57
Key problem: Forward kinematics To find the position of the end effector for a given specific configuration, we need to find the mapping f : R n R m x = f (θ) where x R m and θ R n. The systematic and general approach for finding f is the Denavit Hartenberg (D H) Algorithm/Convention. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 3 / 57
D H procedure In 1955, Denavit & Hartenberg proposed a matrix based approach for systematically assigning coordinate frames to each link of a serial link robot manipulators. There are two commonly used D H parameter representation in the robotics literature: Standard D H convention Modified D H convention We will use the standard D H convention. D H convention is a general procedure for modeling any robot manipulator. We set up coordinate frames fixed in each link, starting with the base. We then find homogeneous transformation matrices [ H i i 1] between consecutive frames. Finally, we get forward kinematics from [ H 1 0 ] [ H 2 1 ]... [ H n n 1 ]. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 4 / 57
D H notation Note that, joint i connects links (i 1) and i. We start at ground which is considered as link 0. The joint variables are q 1,..., q n, and the joint variable vector is q [q 1,..., q n ] T R n. These joint variables may be angles or displacements. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 5 / 57
How to set up D H frames? Key: Frame {x i, y i, z i } in each link i has z i axis along axis of motion of joint (i + 1) for rotations about z i axis, for translations along z i axis. Four important parameters characterize each frame to frame transformation: Link parameters: o Link length, o Twist angle. Joint parameters: o Link perpendicular distance, o Joint rotation angle. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 6 / 57
D H frames Link parameters Each link is characterized by two constant parameters: Link length denoted by a i, Twist angle denoted by α i. Start with: Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 7 / 57
D H frames Link parameters Find the common unit normal between z i 1 and z i. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 8 / 57
D H frames Link parameters Choose unit vector x i along common normal at z i. The distance between z i 1 and z i axes along common unit normal x i is the link length (i.e., a i ). Note that, if z i 1 and z i axes intersect, a i = 0. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 9 / 57
D H frames Link parameters The angle between z i 1 and z i axes measured about x i (from z i 1 to z i ) is the twist angle (i.e., α i ). Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 10 / 57
D H frames Joint parameters A link pair is characterized by two parameters: Link perpendicular distance denoted by d i, Joint rotation angle denoted by θ i. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 11 / 57
D H frames Joint parameters The distance along z i 1 axis between common normals x i 1 and x i is the link perpendicular distance (i.e., d i ). The link perpendicular distance is variable if the joint i is prismatic. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 12 / 57
D H frames Joint parameters The angle between x i 1 and x i axes measured about z i 1 is joint rotation angle (i.e., θ i ). The joint rotation angle is variable if the joint i is revolute. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 13 / 57
D H parameters Summary a i link length distance between z i 1 and z i axes along common unit normal x i a i = 0 if z i 1 and z i axes intersect α i twist angle angle between z i 1 and z i axes measured about x i (from z i 1 to z i ). d i link perpendicular distance distance along z i 1 axis between common normals x i 1 and x i. Link perpendicular distance is variable if joint i is prismatic. θ i joint rotation angle angle between x i 1 and x i axes measured about z i 1. Joint rotation angle is variable if joint i is revolute. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 14 / 57
Detailed D H procedure 1 Set axes z i along direction of motion of link (i + 1). 2 Form and label base frame {x 0, y 0, z 0 }. For i = 1,..., (n 1) follow steps 3 5. 3 Find the origin O i where the common normal of z i 1 and z i intersects z i or at the intersection of z i 1 and z i. If z i 1 and z i are parallel, then locate the origin at the common normal through joint (i + 1). 4 Establish x i along common normal between z i 1 and z i at O i. If z i 1 and z i intersect, in direction normal to (z i 1, z i ) plane. 5 y i = z i x i. 6 Establish end effector frame (more later). 7 Set up link parameter table. 8 Form homogeneous transformation matrices [Hi 1 i ] i = 1,..., n, and [H0 n] [H1 0 ]...[Hn n 1 ]. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 15 / 57
D H Frame to frame transformation Systematic approach involving only x and z axes: 1 Rotate about z i 1 by θ i, 2 Translate along z i 1 by distance d i, 3 Translate along (rotated) x i by distance a i, 4 Rotate about x i by α i. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 16 / 57
D H Link parameter table The link parameter table is constructed as Joint 1 Joint 2 θ i d i a i α i. Joint n where there is one variable (either θ i or d i ) per row, which is marked with. In summary, there are 3 constant parameters, and one variable which is either θ i or d i. Note that, the frame to frame translation is contained in d i and a i. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 17 / 57
D H The homogenous transformation matrix is obtained by inserting the values from the link parameter table once the frames are set up [Hi 1] i = [Rot(z, θ i )][Trans(0, 0, d i )][Trans(a i, 0, 0)][Rot(x, α i )] cos θ i sin θ i 0 0 1 0 0 0 = sin θ i cos θ i 0 0 0 0 1 0 0 1 0 0 0 0 1 d i 0 0 0 1 0 0 0 1 = 1 0 0 a i 0 1 0 0 0 0 1 0 0 0 0 1 1 0 0 0 0 cos α i sin α i 0 0 sin α i cos α i 0 0 0 0 1 cos θ i cos α i sin θ i sin α i sin θ i a i cos θ i sin θ i cos α i cos θ i sin α i cos θ i a i sin θ i 0 sin α i cos α i d i 0 0 0 1 Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 18 / 57.
D H Special cases for prismatic joints For prismatic joints, joint variable is d i not θ i. Everything is same as before, with two special cases: When first joint is a prismatic joint, convention is to choose axes such that θ 1 = 0. Similarly, when last joint is a prismatic joint, convention is to choose the direction of x n such that θ n = 0. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 19 / 57
D H summary Now, we can systematically analyze forward kinematics for any robot manipulator. We obtain (one time only) parameters a i and α i from links. We obtain parameter/variable pair θ i and d i from link link connections. We populate the link parameter table, and set up homogeneous transformation matrices. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 20 / 57
End effector frame Standard way of describing the end effector frame is given in below figure where a is the approach vector (z), s is the sliding vector (y), and n is the normal vector (x). This is only for the spatial case and it can be chosen arbitrarily in plane. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 21 / 57
End effector frame with respect to the world frame The location of the end effector with respect to the world frame can be obtained from n x s x a x p x [H0 n ] = n y s y a y p y n z s z a z p z 0 0 0 1 where p = [p x, p y, p z ] T is the position of the end effector and [n, s, a] is the orientation of the end effector. So the 3 by 3 matrix [R0 n] in [Hn 0 ] gives the orientation of end effector axes (x n, y n, z n ) in base frame, where n is orientation of x axis, s is orientation of y axis, a is orientation of z axis. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 22 / 57
Why? A unit vector in z direction with respect to the hand frame is [0, 0, 1] T while the same vector with respect to the base frame is expressed as [H0 n ] 0 0 1 1 = = n x s x a x p x n y s y a y p y n z s z a z p z 0 0 0 1 a x a y a z 1 + p x p y p z 0. 0 0 1 1 Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 23 / 57
D H Problems 1 For base frame (i.e., frame 0), only the direction of z 0 axis is specified; then, O 0 and x 0 can be arbitrarily chosen. 2 For frame n, only the choice of x n axis is constrainted (i.e., it has to be normal to the z n 1 axis). Since there is no joint (n + 1) and thus z n axis is not constrainted, it can be chosen arbitrarily. 3 When two consecutive axes are parallel, the common normal of them is not uniquely defined. 4 When two consecutive axes intersect, the direction of x i axis is arbitrary. 5 When joint i is prismatic only the direction of z i 1 axis is determined. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 24 / 57
D H Solutions 1 Let the origin of the base frame be same as the origin of frame 1. 2 Let the origin of the last link (i.e., link n) be same as link (n 1) frame. 3 In case of intersecting joint axes, the origin is at the point of intersection of the joint axes. 4 If the axes are parallel, the origin is chosen to make the joint distance 0 for the next link whose coordinate origin is defined. 5 In the cases of intersecting joints, the direction of the x axis is parallel (or anti parallel) to the vector cross product of z i 1 and z i. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 25 / 57
Consider the planar one degree of freedom (R) manipulator shown below. Set up the link parameter table, and derive [H0 1 ], using the Denavit Hartenburg convention. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 26 / 57
Link parameter table is obtained as [H0 1 ] is obtained as [ ] H 1 0 = θ i d i a i α i Joint 1 0 l 1 0 cos θ 1 sin θ 1 0 l 1 cos θ 1 sin θ 1 cos θ 1 0 l 1 sin θ 1 0 0 1 0 0 0 0 1. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 27 / 57
Consider the two degree of freedom (RR) manipulator shown below. Draw the coordinate axes for each link, set up the link parameter table, and derive [H0 1], [H2 1 ], and [H2 0 ], using the Denavit Hartenburg convention. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 28 / 57
Coordinate frames are chosen as Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 29 / 57
Link parameter table is obtained as θ i d i a i α i Joint 1 0 l 1 0 Joint 2 0 l 2 0 Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 30 / 57
[H0 1], [H2 1 ], and [H2 0 ] = [H1 0 ][H2 1 ] are obtained as [ H 1 0 ] [ H 2 1 ] [ H 2 0 ] = = = cos θ 1 sin θ 1 0 l 1 cos θ 1 sin θ 1 cos θ 1 0 l 1 sin θ 1 0 0 1 0 0 0 0 1 cos θ 2 sin θ 2 0 l 2 cos θ 2 sin θ 2 cos θ 2 0 l 2 sin θ 2 0 0 1 0 0 0 0 1 c 12 s 12 0 l 1 c 1 + l 2 c 12 s 12 c 12 0 l 1 s 1 + l 2 s 12 0 0 1 0 0 0 0 1,., Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 31 / 57
Consider the planar three degree of freedom (RRP) manipulator shown below. Draw the coordinate axes for each link, set up the link parameter table, and derive each [Hi 1 i ], and [H3 0 ], using the Denavit Hartenburg convention. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 32 / 57
where end effector frame is arbitrarily chosen. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 33 / 57 Example Coordinate frames are chosen as
Link parameter table is obtained as θ i d i a i α i Joint 1 0 L 0 Joint 2 0 0 90 Joint 3 0 0 0 Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 34 / 57
[H0 1], [H2 1 ], [H3 2 ] are obtained as [ H 1 0 ] [ H 2 1 ] [ H 3 2 ] = = = cos θ 1 sin θ 1 0 L cos θ 1 sin θ 1 cos θ 1 0 L sin θ 1 0 0 1 0 0 0 0 1 cos θ 2 0 sin θ 2 0 sin θ 2 0 cos θ 2 0 0 1 0 0 0 0 0 1 1 0 0 0 0 1 0 0 0 0 1 d 3 0 0 0 1.,, Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 35 / 57
[H0 3] = [H1 0 ][H2 1 ][H3 2 ] is obtained as [ ] H 3 0 = c 12 0 s 12 Lc 1 + d 3 s 12 s 12 0 c 12 Ls 1 d 3 c 12 0 1 0 0 0 0 0 1. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 36 / 57
Consider the planar three degree of freedom (PRR) manipulator shown below. Draw the coordinate axes for each link, set up the link parameter table, and derive each [Hi 1 i ], and [H3 0 ], using the Denavit Hartenburg convention. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 37 / 57
Coordinate frames are chosen as where end effector frame is arbitrarily chosen, directions of x 0 and y 0 are arbitrarily chosen (not z 0 ), and directions of all x i s could be reversed. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 38 / 57
Link parameter table is obtained as θ i d i a i α i Joint 1 0 0 90 Joint 2 0 L 2 0 Joint 3 0 L 3 0 Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 39 / 57
[H0 1], [H2 1 ], [H3 2 ] are obtained as [ H 1 0 ] [ H 2 1 ] [ H 3 2 ] = = = 1 0 0 0 0 0 1 0 0 1 0 d 1 0 0 0 1, cos θ 2 sin θ 2 0 L 2 cos θ 2 sin θ 2 cos θ 2 0 L 2 sin θ 2 0 0 1 0 0 0 0 1 cos θ 3 sin θ 3 0 L 3 cos θ 3 sin θ 3 cos θ 3 0 L 3 sin θ 3 0 0 1 0 0 0 0 1,. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 40 / 57
[H0 3] = [H1 0 ][H2 1 ][H3 2 ] is obtained as [ ] H 3 0 = c 23 s 23 0 L 2 c 2 + L 3 c 23 0 0 1 0 s 23 c 23 0 d 1 L 2 s 2 L 3 s 23 0 0 0 1. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 41 / 57
Consider the coordinate axes for four degree of freedom (RRRP) robot manipulator shown in the next slide. This arm has all four axes parallel (perpendicular to the floor) base rotation, three co planar arm motions (shoulder, elbow, and wrist), and the tool roll. Set up the link parameter table, and derive each [H i i 1 ] and [H4 0 ], using the Denavit Hartenburg convention. What are the directions of the unit vectors {x 3, y 3, z 3 } at the end effector frame as seen from the base frame? Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 42 / 57
Coordinate frames are given as Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 43 / 57
Link parameter table is obtained as θ i d i a i α i Joint 1 d 1 a 1 180 Joint 2 0 a 2 0 Joint 3 d 3 0 0 Joint 4 0 0 0 Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 44 / 57
[H0 1], [H2 1 ], [H3 2 ], [H4 3 ] are obtained as [ H 1 0 ] [ H 2 1 ] [ H 3 2 ] = = = cos θ 1 sin θ 1 0 a 1 cos θ 1 sin θ 1 cos θ 1 0 a 1 sin θ 1 0 0 1 d 1 0 0 0 1 cos θ 2 sin θ 2 0 a 2 cos θ 2 sin θ 2 cos θ 2 0 a 2 sin θ 2 0 0 1 0 0 0 0 1 cos θ 3 sin θ 3 0 0 sin θ 3 cos θ 3 0 0 0 0 1 d 3 0 0 0 1, [ H 4 3,, ] = 1 0 0 0 0 1 0 0 0 0 1 d 4 0 0 0 1. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 45 / 57
[H0 4] = [H1 0 ][H2 1 ][H3 2 ][H4 3 ] is obtained as [ ] H0 4 = cos(θ 1 θ 2 θ 3) sin(θ 1 θ 2 θ 3) 0 a 1 cos θ 1 + a 2 cos(θ 1 θ 2) sin(θ 1 θ 2 θ 3) cos(θ 1 θ 2 θ 3) 0 a 1 sin θ 1 + a 2 sin(θ 1 θ 2) 0 0 1 d 1 d 3 d 4 0 0 0 1 Note that [H3 4 ] does not include any rotation. From the top left part of [H0 4] (which is identical to that of [H3 0 ] s), with respect to the base frame, {x 3, y 3, z 3 } are given by cos(θ 1 θ 2 θ 3 ) sin(θ 1 θ 2 θ 3 ) 0, sin(θ 1 θ 2 θ 3 ) cos(θ 1 θ 2 θ 3 ) 0, 0 0 1.. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 46 / 57
Consider the five degree of freedom (RRRRR) robot manipulator (Alpha II) shown in the next slide. This arm has five axes (base rotation, three co planar arm motions (shoulder, elbow, and wrist), and tool roll). Note that the base rotation and tool roll are perpendicular to the shoulder/elbow/wrist motions. Draw the coordinate axes for each link, set up the parameter table, and derive each [Hi 1 i ] and [H5 0 ], using the Denavit Hartenburg convention. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 47 / 57
Alpha II robot arm Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 48 / 57
Coordinate frames are chosen as Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 49 / 57
The translation parameters are given as Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 50 / 57
Link parameter table is obtained as θ i d i a i α i Joint 1 0 0 90 Joint 2 0 a 2 0 Joint 3 0 a 3 0 Joint 4 0 0 90 Joint 5 d 5 0 0 Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 51 / 57
[H0 1], [H2 1 ], [H3 2 ] are obtained as [ H 1 0 ] [ H 2 1 ] [ H 3 2 ] = = = cos θ 1 0 sin θ 1 0 sin θ 1 0 cos θ 1 0 0 1 0 0 0 0 0 1, cos θ 2 sin θ 2 0 a 2 cos θ 2 sin θ 2 cos θ 2 0 a 2 sin θ 2 0 0 1 0 0 0 0 1 cos θ 3 sin θ 3 0 a 3 cos θ 3 sin θ 3 cos θ 3 0 a 3 sin θ 3 0 0 1 0 0 0 0 1,. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 52 / 57
[H3 4], [H5 4 ], and [H5 0 ] = [H1 0 ][H2 1 ][H3 2 ][H4 3 ][H5 4 ] are obtained as [ H 4 3 ] [ H 5 4 ] [ H 5 0 ] = = = cos θ 4 0 sin θ 4 0 sin θ 4 0 cos θ 4 0 0 1 0 0 0 0 0 1 cos θ 5 sin θ 5 0 0 sin θ 5 cos θ 5 0 0 0 0 1 d 5 0 0 0 1 n x s x a x p x n y s y a y p y n z s z a z p z 0 0 0 1.,, Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 53 / 57
The entries of [H0 5] are n x = cos θ 1 cos(θ 2 + θ 3 + θ 4 ) cos θ 5 + sin θ 1 sin θ 5, n y = sin θ 1 cos(θ 2 + θ 3 + θ 4 ) cos θ 5 cos θ 1 sin θ 5, n z = sin(θ 2 + θ 3 + θ 4 ) cos θ 5, s x = cos θ 1 cos(θ 2 + θ 3 + θ 4 ) sin θ 5 + sin θ 1 cos θ 5, s y = sin θ 1 cos(θ 2 + θ 3 + θ 4 ) sin θ 5 cos θ 1 cos θ 5, s z = sin(θ 2 + θ 3 + θ 4 ) sin θ 5, a x = cos θ 1 sin(θ 2 + θ 3 + θ 4 ), a y = sin θ 1 sin(θ 2 + θ 3 + θ 4 ), a z = cos(θ 2 + θ 3 + θ 4 ), p x = cos θ 1 (a 2 cos θ 2 + a 3 cos(θ 2 + θ 3 ) d 5 sin(θ 2 + θ 3 + θ 4 ), p y = sin θ 1 (a 2 cos θ 2 + a 3 cos(θ 2 + θ 3 ) d 5 sin(θ 2 + θ 3 + θ 4 ), p z = a 2 sin θ 2 a 3 sin(θ 2 + θ 3 ) d 5 cos(θ 2 + θ 3 + θ 4 ). Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 54 / 57
Consider the four degree of freedom (RRRR) finger model shown below. Set up the link parameter table using the Denavit Hartenburg convention. Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 55 / 57
Link parameter table can be obtained as θ i d i a i α i Joint 1 0 0 90 Joint 2 0 a 2 0 Joint 3 0 a 3 0 Joint 4 0 a 4 0 Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 56 / 57
What happens when the order of base frame and first frame change (i.e., z 0 becomes z 1 and z 1 becomes z 0 )? Link parameter table can now be obtained as θ i d i a i α i Joint 1 0 0 90 Joint 2 0 a 2 90 Joint 3 0 a 3 0 Joint 4 0 a 4 0 Dr. Tatlicioglu (EEE@IYTE) EE463 Introduction to Robotics Chapter 5 57 / 57