-
Notifications
You must be signed in to change notification settings - Fork 6
/
RNE.m
208 lines (176 loc) · 6.31 KB
/
RNE.m
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
function RNE()
clc
clear all
close all
figure;
hold on;
h1 = plot3(0,0,0, 'b'); % The link
h2 = plot3(0,0,0, 'or'); % The joint/end-effector
h3 = plot3(0,0,0, 'xk'); % The center of mass
xlabel('x')
ylabel('y')
zlabel('z')
view([0 0 1]);
axis equal;
xlim([-2 2]);
ylim([-2 2]);
zlim([-0.5 0.5]);
legend('Link', 'Joint', 'Center of Mass')
% -------------------------------------------------------------------------
% Define the DH parameters
N_DOFS = 3;
dh.theta = [0 0 0];
dh.alpha = [0 0 0];
dh.offset = [0 0 0];
dh.d = [0 0 0];
dh.a = [0.5 0.5 0.5];
dh.type = ['r' 'r' 'r'];
% -------------------------------------------------------------------------
% Rigid body paramaters: inertia, mass, and cener of mass
rb.I = repmat(eye(3), 1, 1, N_DOFS);
rb.m = [1 1 1];
% In standard DH, COM is mesured respect to its end-effector (using local
% frame). When COM is [0 0 0]', it means the COM is located exactly at the
% end-effector. Therefore, COM usually has negative values, which means the
% COM is behind the end-effector
rb.r = [-0.25 0 0; -0.25 0 0; -0.25 0 0]';
% -------------------------------------------------------------------------
% Arbitrary trajectory as the inputs: joint position, velocity, and
% acceleration
ts = 0.001;
time_span = 0:ts:1;
qc = [pi/3*sin(2*pi*1*time_span)' pi/3*sin(2*pi*1*time_span)' pi/3*sin(2*pi*1*time_span)'];
qcdot = gradient(qc', ts)';
qcddot = gradient(qcdot', ts)';
% -------------------------------------------------------------------------
% Kinematic simulation, optional, for visualization purpose!
% End-effector position, form the base which is located at [0 0 0]'
EE = zeros(3, N_DOFS+1);
COM = zeros(3, N_DOFS);
for k = 1 : length(time_span)
for i = 1 : 1 : N_DOFS
T = calc_transformation(0, i, dh, qc(k,:));
EE(:,i+1) = T(1:3,4);
COM(:,i) = EE(:,i+1) + T(1:3,1:3) * rb.r(:,i);
end
% Draw the robot
set(h1, 'XData', EE(1, :), 'YData', EE(2, :),'ZData', EE(3, :));
set(h2, 'XData', EE(1, :), 'YData', EE(2, :),'ZData', EE(3, :));
set(h3, 'XData', COM(1, :), 'YData', COM(2, :),'ZData', COM(3, :));
drawnow;
end
% -------------------------------------------------------------------------
% Here we go!
Q = invdyn(dh, rb, qc, qcdot, qcddot, [0; -9.8; 0]);
% ------------------------------------------------------------------------
% Plotting
figure;
hold on;
plot(time_span, Q(1,:), 'b');
plot(time_span, Q(2,:), 'r');
plot(time_span, Q(3,:), 'g');
% -------------------------------------------------------------------------
% For validation purpose, using RVC Toolbox for comparison
% Disable these lines below if you don't want to try Peter Corkee's RVC
% toolbox
L(1) = Revolute('d', 0, 'a', 0.5, 'alpha', 0, ...
'm', rb.m(1), 'I', rb.I(:,:,1), 'r', rb.r(:,1));
L(2) = Revolute('d', 0, 'a', 0.5, 'alpha', 0, ...
'm', rb.m(2), 'I', rb.I(:,:,2), 'r', rb.r(:,2));
L(3) = Revolute('d', 0, 'a', 0.5, 'alpha', 0, ...
'm', rb.m(3), 'I', rb.I(:,:,3), 'r', rb.r(:,3));
threelink = SerialLink(L, 'name', 'two link');
threelink.gravity = [0; -9.8; 0];
torque_by_rvc_toolbox = threelink.rne(qc, qcdot, qcddot);
plot(time_span, torque_by_rvc_toolbox(:,1), '-.b', 'LineWidth', 2);
plot(time_span, torque_by_rvc_toolbox(:,2), '-.r', 'LineWidth', 2);
plot(time_span, torque_by_rvc_toolbox(:,3), '-.g', 'LineWidth', 2);
legend('Torque 1', 'Torque 2', 'Torque 3', ...
'Torque 1 by RVC', 'Torque 2 by RVC', 'Torque 3 by RVC');
end
% -------------------------------------------------------------------------
function Q = invdyn(dh, rb, qc, qcdot, qcddot, grav)
% Inverse dynamic with recursive Newton-Euler
if nargin < 6
grav = [0;0;0];
end
z0 = [0; 0; 1];
for k = 1 : length(qc)
q = qc(k, :);
qdot = qcdot(k, :);
qddot = qcddot(k, :);
N_DOFS = length(q);
% ---------------------------------------------------------------------
% Forward recursion
for i = 1 : N_DOFS
T = calc_transformation(i-1, i, dh, q);
R = T(1:3, 1:3);
p = [dh.a(i); dh.d(i)*sin(dh.alpha(i)); dh.d(i)*cos(dh.alpha(i))];
if i > 1
w(:, i) = R'*(w(:, i-1) + z0.*qdot(i));
wdot(:, i) = R'*(wdot(:, i-1) + z0.*qddot(i) + ...
cross(w(:, i-1), z0.*qdot(i)));
vdot(:,i) = R'*vdot(:,i-1) + cross(wdot(:,i), p) + ...
cross(w(:,i), cross(w(:,i),p));
else
w(:, i) = R'*(z0.*qdot(i));
wdot(:, i) = R'*(z0.*qddot(i));
vdot(:,i) = R'*grav + cross(wdot(:,i), p) + ...
cross(w(:,i), cross(w(:,i),p));
end
end
% Dynamic simulation
% Backward recursion
for i = N_DOFS:-1:1
p = [dh.a(i); dh.d(i)*sin(dh.alpha(i)); dh.d(i)*cos(dh.alpha(i))];
vcdot = vdot(:,i) + cross(wdot(:,i),rb.r(:,i)) + ...
cross(w(:,i),cross(w(:,i),rb.r(:,i)));
F = rb.m(i)*vcdot;
N = rb.I(:,:,i)*wdot(:,i)+cross(w(:,i),rb.I(:,:,i)*w(:,i));
if i < N_DOFS
T = calc_transformation(i, i+1, dh, q);
R = T(1:3, 1:3);
n(:,i) = R*(n(:,i+1) + cross(R'*p, f(:,i+1))) + ...
cross(rb.r(:,i)+p,F) + N;
f(:,i) = R*f(:,i+1) + F;
else
n(:,i) = cross(rb.r(:,i)+p,F) + N;
f(:,i) = F;
end
T = calc_transformation(i-1, i, dh, q);
R = T(1:3, 1:3);
if dh.type(i) == 't'
Q(i,k) = f(:,i)'*R'*z0;
elseif dh.type(i) == 'r'
Q(i,k) = n(:,i)'*R'*z0;
end
end
end
end
% -------------------------------------------------------------------------
function T = calc_transformation(from, to, dh, qc)
% Transformation from one joint to another joint
% 0<=from<N_DOFS
% 0<to<=N_DOFS
T = eye(4);
N_DOFS = length(qc);
% Sanity check
if (from >= N_DOFS) || (from < 0) || (to <= 0) || (to > N_DOFS)
return;
end
for i = from+1 : to
if dh.type(i) == 'r'
dh.theta(i) = qc(i);
elseif dh.type(i) == 'p'
dh.d(i) = qc(i);
end
ct = cos(dh.theta(i) + dh.offset(i));
st = sin(dh.theta(i) + dh.offset(i));
ca = cos(dh.alpha(i));
sa = sin(dh.alpha(i));
T = T * [ ct -st*ca st*sa dh.a(i)*ct ; ...
st ct*ca -ct*sa dh.a(i)*st ; ...
0 sa ca dh.d(i) ; ...
0 0 0 1 ];
end
end