Robot Dynamics Exercise 1b Solution
Robot Dynamics Exercise 1b Solution
Abstract
The aim of this exercise is to calculate the differential kinematics of an
ABB robot arm. You will practice on the derivation of velocities for a multi-
body system, as well as derive the mapping of between generalized velocities
and end-effector velocities. A separate MATLAB script will be provided for
the 3D visualization of the robot arm.
1 Introduction
The following exercise is based on an ABB IRB 120 depicted in figure 2. It is a
6-link robotic manipulator with a fixed base. During the exercise you will imple-
ment several different MATLAB functions, which you should test carefully since the
∗ original contributors include Michael Blösch, Dario Bellicoso, and Samuel Bachmann
† [email protected], [email protected], [email protected]
1
Figure 2: ABB IRB 120 with coordinate systems and joints.
next exercises will depend on them. To help you with this, we have provided the
script prototypes at http://www.rsl.ethz.ch/education-students/lectures/
robotdynamics.html together with a visualizer of the manipulator.
Throughout this document, we will employ I for denoting the inertial world coor-
dinate system (which has the same pose as the coordinate system P0 in figure 2)
and E for the coordinate system attached to the end-effector (which has the same
pose as the coordinate system P6 in figure 2).
2 Differential Kinematics
Exercise 2.1
In this exercise, we seek to compute an analytical expression for the twist I wE =
T T
T
I vE I ωE of the end-effector. To this end, find the analytical expression of
the end-effector linear velocity vector I vE and angular velocity vector I ω IE as a
function of the linear and angular velocities of the coordinate frames attached to
each link.
Hint: start by writing the rigid body motion theorem and extend it to the case of a
6DoF arm.
Solution 2.1
2
P
Consider the coordinate frames shown in Fig.2. Frame 0 is fixed with respect to
the inertial frame I, while frame 1 has a linear velocity I v01 and angular velocity
I ω 01 with respect to frame 0. Thus, one has:
Consider a point P that is fixed with respect to frame 1. The linear velocity I vIP
of point P with respect to the fixed frame I is given by:
3
Figure 4: The kinematic structure of a planar two link robot arm.
Combining these results with the fact the frame 0 is fixed with respect to frame I
(i.e. I ω I0 = 0, I vI0 = 0), the end-effector linear velocity is given by:
This result can be extended to the case of the ABB IRB 120, yielding:
I ω IE = I ω I0 + I ω 01 + I ω 12 + · · · + I ω 56 + I ω 6E (6)
4
Exercise 2.2
This exercise focuses on deriving the mapping between the generalized velocities
q̇ and the end-effector twist I wE , namely the basic or geometric Jacobian I Je0 =
T T
T
I JP I JR . To this end, you should derive the translational and rotational
Jacobians of the end-effector, respectively I JP and I JR . To do this, you can start
from the derivation you found in exercise 1. The Jacobians should depend on the
minimal coordinates q only. Remember that Jacobians map joint space generalized
velocities to operational space generalized velocities:
1 function J P = jointToPosJac(q)
2 % Input: vector of generalized coordinates (joint angles)
3 % Output: Jacobian of the end−effector translation which maps joint
4 % velocities to end−effector linear velocities in I frame.
5
6 % Compute the translational jacobian.
7 J P = zeros(3, 6);
8 end
9
10 function J R = jointToRotJac(q)
11 % Input: vector of generalized coordinates (joint angles)
12 % Output: Jacobian of the end−effector orientation which maps joint
13 % velocities to end−effector angular velocities in I frame.
14
15 % Compute the rotational jacobian.
16 J R = zeros(3, 6);
17 end
Solution 2.2
The translation and rotation Jacobians can be evaluated starting from the results
that were obtained in the previous exercises. By combining the analytical expres-
sions of the linear and angular end-effector velocities, one has:
5
one has:
I vIE = (I ω 0 + I ω 01 ) × (I rI2 − I rI1 )
+ (I ω 1 + I ω 12 ) × (I rI3 − I rI2 )
+ ...
+ (I ω 5 + I ω 56 ) × (I rIE − I rI6 )
(11)
= (I n1 θ̇1 ) × (I rI2 − I rI1 )
+ (I n1 θ̇1 + I n2 θ̇2 ) × (I rI3 − I rI2 )
+ ...
+ (I n1 θ̇1 + · · · + I n6 θ̇6 ) × (I rIE − I rI6 )
Expanding and reordering the terms in the last equation, one has
where I JP (q) is the translation Jacobian matrix that projects a vector from the
joint velocity space to the cartesian linear velocity space.
Using the results obtained by solving Exercise 1, and taking into account that I ω I0
and I ω 6E are both equal to zero, one has
I ω IE = I ω 01 + I ω 12 + · · · + I ω 56
= I n1 θ̇1 + I n2 θ̇2 + · · · + I n6 θ̇6
(14)
= I n1 I n2 . . . I n6 · q̇
= I JR (q) · q̇,
where JR (q) is the rotation Jacobian matrix that projects a vector in the joint
velocity space to the Cartesian angular velocity space.
1 function J P = jointToPosJac(q)
2 % Input: vector of generalized coordinates (joint angles)
3 % Output: Jacobian of the end−effector orientation which maps joint
4 % velocities to end−effector linear velocities in I frame.
5
6 % Compute the relative homogeneous transformation matrices.
7 T I0 = getTransformI0();
8 T 01 = jointToTransform01(q(1));
9 T 12 = jointToTransform12(q(2));
10 T 23 = jointToTransform23(q(3));
11 T 34 = jointToTransform34(q(4));
12 T 45 = jointToTransform45(q(5));
13 T 56 = jointToTransform56(q(6));
14
15 % Compute the homogeneous transformation matrices from frame k to the
16 % inertial frame I.
6
17 T I1 = T I0 * T 01;
18 T I2 = T I1 * T 12;
19 T I3 = T I2 * T 23;
20 T I4 = T I3 * T 34;
21 T I5 = T I4 * T 45;
22 T I6 = T I5 * T 56;
23
24 % Extract the rotation matrices from each homogeneous transformation
25 % matrix.
26 R I1 = T I1(1:3,1:3);
27 R I2 = T I2(1:3,1:3);
28 R I3 = T I3(1:3,1:3);
29 R I4 = T I4(1:3,1:3);
30 R I5 = T I5(1:3,1:3);
31 R I6 = T I6(1:3,1:3);
32
33 % Extract the position vectors from each homogeneous transformation
34 % matrix.
35 r I I1 = T I1(1:3,4);
36 r I I2 = T I2(1:3,4);
37 r I I3 = T I3(1:3,4);
38 r I I4 = T I4(1:3,4);
39 r I I5 = T I5(1:3,4);
40 r I I6 = T I6(1:3,4);
41
42 % Define the unit vectors around which each link rotates in the ...
precedent
43 % coordinate frame.
44 n 1 = [0 0 1]';
45 n 2 = [0 1 0]';
46 n 3 = [0 1 0]';
47 n 4 = [1 0 0]';
48 n 5 = [0 1 0]';
49 n 6 = [1 0 0]';
50
51 % Compute the end−effector position vector.
52 r I IE = jointToPosition(q);
53
54 % Compute the translational jacobian.
55 J P = [ cross(R I1 * n 1, r I IE − r I I1) ...
56 cross(R I2 * n 2, r I IE − r I I2) ...
57 cross(R I3 * n 3, r I IE − r I I3) ...
58 cross(R I4 * n 4, r I IE − r I I4) ...
59 cross(R I5 * n 5, r I IE − r I I5) ...
60 cross(R I6 * n 6, r I IE − r I I6) ...
61 ];
62
63 end
64
65
66 function J R = jointToRotJac(q)
67 % Input: vector of generalized coordinates (joint angles)
68 % Output: Jacobian of the end−effector orientation which maps joint
69 % velocities to end−effector angular velocities in I frame.
70
71 % Compute the relative homogeneous transformation matrices.
72 T I0 = getTransformI0();
73 T 01 = jointToTransform01(q(1));
74 T 12 = jointToTransform12(q(2));
75 T 23 = jointToTransform23(q(3));
76 T 34 = jointToTransform34(q(4));
77 T 45 = jointToTransform45(q(5));
78 T 56 = jointToTransform56(q(6));
79
80 % Compute the homogeneous transformation matrices from frame k to the
81 % inertial frame I.
82 T I1 = T I0 * T 01;
7
83 T I2 = T I1 * T 12;
84 T I3 = T I2 * T 23;
85 T I4 = T I3 * T 34;
86 T I5 = T I4 * T 45;
87 T I6 = T I5 * T 56;
88
89 % Extract the rotation matrices from each homogeneous transformation
90 % matrix.
91 R I1 = T I1(1:3,1:3);
92 R I2 = T I2(1:3,1:3);
93 R I3 = T I3(1:3,1:3);
94 R I4 = T I4(1:3,1:3);
95 R I5 = T I5(1:3,1:3);
96 R I6 = T I6(1:3,1:3);
97
98 % Define the unit vectors around which each link rotates in the ...
precedent
99 % coordinate frame.
100 n 1 = [0 0 1]';
101 n 2 = [0 1 0]';
102 n 3 = [0 1 0]';
103 n 4 = [1 0 0]';
104 n 5 = [0 1 0]';
105 n 6 = [1 0 0]';
106
107 % Compute the rotational jacobian.
108 J R = [ R I1 * n 1 ...
109 R I2 * n 2 ...
110 R I3 * n 3 ...
111 R I4 * n 4 ...
112 R I5 * n 5 ...
113 R I6 * n 6 ...
114 ];
115
116 end