-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathquadrotor_simulator.m
410 lines (322 loc) · 12.7 KB
/
quadrotor_simulator.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
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
%% Initializations
clc; clear; close all;
g = 9.81; % The gravitational acceleration [m/s^2]
l = 0.2; % Distance from the center of mass to each rotor [m]
m = 0.5; % Total mass of the quadrotor [kg]
I = [1.24, 1.24, 2.48]; % Mass moment of inertia [kg m^2]. DIAGONAL of 3x3
mu = 3.0; % Maximum thrust of each rotor [N]
sigma = 0.01; % The proportionality constant relating thrust to torque [m]
%Problem parameters
p = [g l m I mu sigma];
%% Initial conditions
r = [0; 0; 0];
n = [0; 0; 0];
% State Vectors - start and final:
z0 = [0; 0; 0; zeros(9,1)]; % starting pose
%UAV Kinematics
%UAV initial position
%circling
% z0 = [0; 0; 0; zeros(9,1)];
% y0 = [6 4 8]';
% % freq = 2*pi*0.3;
% uav_dyn = @(t) [-sin(t); cos(t); 0];
% uav_traj = @(t) y0 + [cos(t); sin(t); 0];
%circle-success - only depends on the starting points
% z0 = [0; 0; 0; zeros(9,1)];
% y0 = [2 2 8]';
% % freq = 2*pi*0.3;
% uav_dyn = @(t) [-sin(t); cos(t); 0];
% uav_traj = @(t) y0 + [cos(t); sin(t); 0];
% tailing-crash
% z0 = [0; 0; 0; zeros(9,1)];
% y0 = [5 5 5]';
% uav_dyn = @(t) y0*0.2; %return performance gets worse for higher multiplier
% uav_traj = @(t) y0 + t*uav_dyn(t);
% tailing-success
% z0 = [0; 0; 0; zeros(9,1)];
% y0 = [2 2 2]';
% uav_dyn = @(t) y0*0.2; %return performance gets worse for higher multiplier
% uav_traj = @(t) y0 + t*uav_dyn(t);
%head on1
% z0 = [0; 0; 0; zeros(9,1)];
% y0 = [9 9 9]';
% uav_dyn = @(t) -y0/10;
% uav_traj = @(t) y0 + t*uav_dyn(t);
%head on2
% z0 = [0; 0; 0; zeros(9,1)];
% y0 = [7 2 4]';
% uav_dyn = @(t) -y0/5;
% uav_traj = @(t) y0 + t*uav_dyn(t);
%steep climb and descent
% z0 = [0; 10; 0; zeros(9,1)];
% y0 = [8 2 4]';
% uav_dyn = @(t) [0; 0.4; 2*square(t)];
% uav_traj = @(t) y0 + t*uav_dyn(t);
%sinusoidal climb and descent
% z0 = [0; 0; 0; zeros(9,1)];
% y0 = [1 2 5]';
% uav_dyn = @(t) [0.5; 0; cos(t)]*2.3;
% uav_traj = @(t) y0 + [0.5*t; 0; sin(t)]*2.3;
%sinusoidal climb and descent 2
% z0 = [0; 0; 0; zeros(9,1)];
% y0 = [1 2 5]';
% uav_dyn = @(t) [0.5; 0; cos(t)]*2.5;
% uav_traj = @(t) y0 + [0.5*t; 0; sin(t)]*2.5; %return crash
%spiral ascent
% z0 = [0; 0; 0; zeros(9,1)];
% y0 = [6 4 2]';
% uav_dyn = @(t) [-sin(t); cos(t); 0.1]*2;
% uav_traj = @(t) y0 + [cos(t); sin(t); 0.1*t];
%spiral descent
% z0 = [0; 0; 0; zeros(9,1)];
% y0 = [6 4 8]';
% freq = 2*pi*0.3;
% uav_dyn = @(t) [-sin(t); cos(t); -0.1];
% uav_traj = @(t) y0 + [cos(t); sin(t); -0.1*t];
% %test trajectory1
% z0 = [2; 2; 0; zeros(9,1)];
% y0 = [9; 9; 9]
% uav_dyn = @(t) [-0.5; -0.5; -0.5*t + 0.1]*1.2 %failure to return home due to bad angles
% uav_traj = @(t) y0 + t*uav_dyn(t);
%test trajectory2
% z0 = [2; 2; 0; zeros(9,1)]; % starting pose
% y0 = [6; 0.1; 0.1]
% uav_dyn = @(t) [0.5; 0.5; 0.5*t + 0.1]
% uav_traj = @(t) y0 + t*uav_dyn(t);
% %test trajectory3
% z0 = [0; 10; 0; zeros(9,1)]; % starting pose
% y0 = [6; 9.5; 9.5]
% uav_dyn = @(t) [-0.1; -0.2; (-0.2*t^2 - 0.1)]*0.6;
% uav_traj = @(t) y0 + t*uav_dyn(t);
% %test trajectory4
% z0 = [0; 0; 0; zeros(9,1)]; % starting pose
% y0 = [5; 0.1; 8];
% uav_dyn = @(t) [0.5; 0.09*exp(0.09*t); 0];
% uav_traj = @(t) y0 + [0.5*t; exp(0.09*t); 0];
%Initial augmented state vector
z0_I = [z0; y0];
%% LQR Test - using MATLAB LQR:
% syms z1 z2 z3 z4 z5 z6 z7 z8 z9 z10 z11 z12 r1 r2 r3 n1 n2 n3 'real'
% syms u1 u2 u3 u4 'positive'
% zp = [z1; z2; z3; z4; z5; z6; z7; z8; z9; z10; z11; z12];
% up = [u1; u2; u3; u4];
% dz = quadrotor(0, zp, up, p, [r1;r2;r3], [n1;n2;n3]);
% Au = @(t,z) (subs(jacobian(dz,zp), [zp; up], [z0; u0]));
% Bu = @(t,z) (subs(jacobian(dz,up), [zp; up], [z0; u0]));
% G = Au(100)
% H = Bu(100)
% Matrices:
A = [0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0;
0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0;
0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0;
0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0;
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0;
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1;
0, 0, 0, 0, g, 0, 0, 0, 0, 0, 0, 0;
0, 0, 0, -g, 0, 0, 0, 0, 0, 0, 0, 0;
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0;
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0;
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0;
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0];
B = [ 0, 0, 0, 0;
0, 0, 0, 0;
0, 0, 0, 0;
0, 0, 0, 0;
0, 0, 0, 0;
0, 0, 0, 0;
0, 0, 0, 0;
0, 0, 0, 0;
1/m, 1/m, 1/m, 1/m;
0, l/I(1), 0,-l/I(1);
-l/I(2), 0, l/I(2), 0;
sigma/I(3),-sigma/I(3),sigma/I(3),-sigma/I(3)];
Q = [0.2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0;
0, 0.2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0;
0, 0, 0.2, 0, 0, 0, 0, 0, 0, 0, 0, 0;
0, 0, 0, 10, 0, 0, 0, 0, 0, 0, 0, 0;
0, 0, 0, 0, 10, 0, 0, 0, 0, 0, 0, 0;
0, 0, 0, 0, 0, 10, 0, 0, 0, 0, 0, 0;
0, 0, 0, 0, 0, 0, 0.0, 0, 0, 0, 0, 0;
0, 0, 0, 0, 0, 0, 0, 0.0, 0, 0, 0, 0;
0, 0, 0, 0, 0, 0, 0, 0, 0.0, 0, 0, 0;
0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0;
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0;
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1];
R = 1/(mu)*eye(4);
[K,S,pole] = lqr(A, B, Q, R);
%poles = [-2 -0.5+1i -0.5+1i -0.2+0.1i -0.2-0.1i -0.4-0.2i -0.08 -0.3-0.23i -0.8 + 0.4i -1.2 -1.1 -1.5];
%Pcl = pole(syscl)
%K = place(A,B,pole)
%Alternate way of defining our system
syscl = ss(A, B, eye(12), 0);
%zd = @(t) [2*cos(t); 2*sin(t); min(t,7); 0; zeros(8,1)]; % desired pose for test
% zd = [4; 0; 5; 0; zeros(8,1)];
% Inputs:
ud = [1 1 1 1]'*m*g/4;
u = @(z, zd, ud, K) ud + K*(zd - z);
% Problem parameters
epsilon = 0.2*2;
% epsilon = 1;
%Drone returns back home after UAV leaves airfield
threshold = [0 10;0 10;0 10];
%% Phase I: Pursue
sample = 2000;
tspan_I = linspace(0, 40, sample);
options = odeset('Events', @(t,z) interceptdrone(t, z, epsilon, threshold),...
'RelTol', 1e-2);
%options = odeset('Events', @(t,z) interceptdrone(t, z, epsilon),...
% 'Events', @(t,z) boundary_condition(t,z,threshold), 'RelTol', 1e-6);
vel = y0;
count = 0;
% [t_K, uav_traj] = ode45(@(t,uav_traj) uav_dyn(t), tspan_I, y0);
% option2 = odeset('Events', @(t,z) boundary_condition(t,z,threshold));
% options = odeset(option1, option2)
[t_I, z_I, te, ze] = ode45(@(t, z) augmentedSystem(t, z, uav_dyn, u, K, p, zeros(3,1), zeros(3,1), uav_traj),...
tspan_I, z0_I, options);
%% Phase II: Return
if(isempty(te)) % if the robot failed to catch the bug
% Decoupling the augmented state vector z from only phase I
t = t_I;
z = z_I(:,1:12);
y = z_I(:,13:15);
disp('Drone incapable of capturing the UAV...Returning to base')
else
tspan_II = [te, tspan_I(end)];
z0_II = z_I(end,1:12)';
zd = [0; 0; 1; zeros(9,1)];
ud = [1 1 1 1]'*m*g/4;
if (any(threshold (:,1) > ze(13:15)') || any(ze(13:15)' > threshold(:,2)))
disp('UAV left the airfield...Returning empty handed')
[t_II, z_II] = ode45(@(t,z) quadrotor(t, z, u(z, zd, ud, K), p, r, n),...
tspan_II, z0_II);
else
%add disturbance and if any change in dynamics to solve
disp('Target acquired. Its coming home!')
%disp('UAV capture successful...It is resisting the capture...Bringing it back to base')
r = @(t) [0.1*sin(t); 0; 0.1*square(t)]*0
n = @(t) [0.1; 0.2; 0.3]*0;
% q = [0.1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0;
% 0, 0.1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0;
% 0, 0, 0.1, 0, 0, 0, 0, 0, 0, 0, 0, 0;
% 0, 0, 0, 10, 0, 0, 0, 0, 0, 0, 0, 0;
% 0, 0, 0, 0, 10, 0, 0, 0, 0, 0, 0, 0;
% 0, 0, 0, 0, 0, 10, 0, 0, 0, 0, 0, 0;
% 0, 0, 0, 0, 0, 0, 0.1, 0, 0, 0, 0, 0;
% 0, 0, 0, 0, 0, 0, 0, 0.1, 0, 0, 0, 0;
% 0, 0, 0, 0, 0, 0, 0, 0, 0.1, 0, 0, 0;
% 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0;
% 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0;
% 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1];
%
% Q = q;
%
% R = 1/(mu)*eye(4);
%
% [K,S,pole] = lqr(A, B, Q, R);
[t_II, z_II] = ode45(@(t,z) quadrotor(t, z, u(z, zd, ud, K), p, r(t), n(t)),...
tspan_II, z0_II);
end
% Decoupling the augmented state vector z from phase I and phase II
t = [t_I; t_II];
% t = t_I;
% z = z_I;
z = [z_I(:,1:12); z_II];
y = [z_I(:,13:15); z_II(:,1:3)];
end
%using this to track distance until we have point-mass in simulation
cost = zeros(length(z_I),1);
for i = 1:length(z_I)
dist_y_z(i,1) = norm(y(i,1:3) - z(i,1:3));
end
%% Plotting the results
for i=1:4
ax(i) = subplot(2,2,i,'NextPlot','Add','Box','on','XGrid','on','YGrid','on',...
'Xlim',[t(1), t(end)],...
'TickLabelInterpreter','LaTeX','FontSize',14);
xlabel('t','Interpreter','LaTeX','FontSize',14);
end
plot(ax(1), t,y(:,1:3), 'LineWidth', 1.5);
legend(ax(1), {'$x_1$', '$x_2$', '$x_3$'},...
'Interpreter', 'LaTeX', 'FontSize', 14);
title(ax(1), '${\bf x}$','Interpreter','LaTeX','FontSize',14);
xlabel(ax(1), 't','Interpreter','LaTeX','FontSize',14);
plot(ax(3), t, z(:,4:6), 'LineWidth', 1.5);
legend(ax(3), {'$\phi$', '$\theta$', '$\psi$'},...
'Interpreter', 'LaTeX', 'FontSize', 14);
title(ax(3), '\boldmath$\alpha$','Interpreter','LaTeX','FontSize',14);
plot(ax(2), t, z(:,7:9), 'LineWidth', 1.5);
legend(ax(2), {'$\dot{x}_1$', '$\dot{x}_2$', '$\dot{x}_3$'},...
'Interpreter', 'LaTeX', 'FontSize', 14);
title(ax(2), '$\dot{\bf x}$','Interpreter','LaTeX','FontSize',14);
plot(ax(4), t, z(:,10:12), 'LineWidth', 1.5);
legend(ax(4), {'$\omega_1$', '$\omega_2$', '$\omega_3$'},...
'Interpreter', 'LaTeX', 'FontSize', 14);
title(ax(4), '\boldmath$\omega$','Interpreter','LaTeX','FontSize',14);
figure(2)
plot3(z(1:length(t_I),1),z(1:length(t_I),2),z(1:length(t_I),3), 'g', 'LineWidth', 3)
hold on
plot3(y(1:length(t_I),1),y(1:length(t_I),2),y(1:length(t_I),3), 'r', 'LineWidth', 2)
xlabel('X')
ylabel('Y')
zlabel('Z')
grid on
legend(["Drone", "UAV"])
title("Trajectories of Drone and UAV in space")
%% Animation
animation_fig = figure;
airspace_box_length = 10;
animation_axes = axes('Parent', animation_fig,...
'NextPlot','add','DataAspectRatio',[1 1 1],...
'Xlim',airspace_box_length*[-0.5 1.5],...
'Ylim',airspace_box_length*[-0.5 1.5],...
'Zlim',airspace_box_length*[0 1],...
'box','on','Xgrid','on','Ygrid','on','Zgrid','on',...
'TickLabelInterpreter','LaTeX','FontSize',14);
view(animation_axes, 3);
% Editing the Sim-Drone shape:
circleRadius = 0.8;
bodySize = 0.4;
droneLineWidth = 0.2;
N = 10;
Q = linspace(0,2*pi,N)';
circle = circleRadius*l*[cos(Q) sin(Q) zeros(N,1)];
loc = bodySize*[1 0 0; 0 1 0; -1 0 0; 0 -1 0];
silhouette = plot3(0,0,0, '--', 'Color', 0.5*[1 1 1], 'LineWidth', 1 ,...
'Parent', animation_axes);
uav = plot3(0, 0, 0, 'Color', 'r', 'LineWidth', droneLineWidth,...
'Parent', animation_axes);
body = plot3(0,0,0, 'Color', 'k', 'LineWidth', droneLineWidth,...
'Parent', animation_axes);
for i=1:4
rotor2(i) = plot3(0,0,0, 'Color', 'r', 'LineWidth', droneLineWidth,...
'Parent', animation_axes);
rotor(i) = plot3(0,0,0, 'Color', 'g', 'LineWidth', droneLineWidth,...
'Parent', animation_axes);
end
tic;
for k=1:length(t)
%f(k,1:12) = zd(k)' - z(k,:);
%f(k,1:12) = zd' - z(k,:);
R = [ cos(z(k,5))*cos(z(k,6)), sin(z(k,4))*sin(z(k,5))*cos(z(k,6)) - cos(z(k,4))*sin(z(k,6)), sin(z(k,4))*sin(z(k,6)) + cos(z(k,4))*sin(z(k,5))*cos(z(k,6));
cos(z(k,5))*sin(z(k,6)), cos(z(k,4))*cos(z(k,6)) + sin(z(k,4))*sin(z(k,5))*sin(z(k,6)), cos(z(k,4))*sin(z(k,5))*sin(z(k,6)) - sin(z(k,4))*cos(z(k,6));
-sin(z(k,5)), sin(z(k,4))*cos(z(k,5)), cos(z(k,4))*cos(z(k,5))];
for i=1:4
ctr(i,:) = z(k,1:3) + loc(i,:)*R';
ctr2(i,:) = y(k,1:3) + loc(i,:)*R';
pose = ones(N,1)*z(k,1:3) + (ones(N,1)*loc(i,:) + circle)*R';
set(rotor(i), 'XData', pose(:,1), 'YData', pose(:,2), 'ZData', pose(:,3) );
pose2 = ones(N,1)*y(k,1:3) + (ones(N,1)*loc(i,:) + circle)*R';
set(rotor2(i), 'XData', pose2(:,1), 'YData', pose2(:,2), 'ZData', pose2(:,3) );
end
set(silhouette,'XData', [0, z(k,1), z(k,1), z(k,1)],...
'YData', [0, 0, z(k,2), z(k,2)],...
'ZData', [0, 0, 0, z(k,3)]);
set(uav, 'XData', [ctr2([1 3],1); NaN; ctr2([2 4],1)], ...
'YData', [ctr2([1 3],2); NaN; ctr2([2 4],2)],...
'ZData', [ctr2([1 3],3); NaN; ctr2([2 4],3)] );
set(body, 'XData', [ctr([1 3],1); NaN; ctr([2 4],1)], ...
'YData', [ctr([1 3],2); NaN; ctr([2 4],2)],...
'ZData', [ctr([1 3],3); NaN; ctr([2 4],3)] );
pause(t(k)-toc);
pause(0.01);
end