CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/simulink/arducopter/sid_pre.m
Views: 1799
1
% Reads ArduPilot's system identification dataflash logs and extracts the SID
2
% subsections of the fligts into .mat file, discarding all irrelevant data
3
%
4
%
5
% Fabian Bredemeier - IAV GmbH
6
% License: GPL v3
7
8
close all;
9
10
%% File selection by user
11
12
% ---------------------------------------------- %
13
% %
14
% File selection %
15
% %
16
% ---------------------------------------------- %
17
18
% 1) Ask user if next data should be added to existing data set
19
if exist('sidLogs', 'var')
20
% Abort if config data for existing data is missing
21
if ~exist('loadedDataConfig', 'var')
22
error('No configuration of the existing data could be found. Aborting...');
23
end
24
addData = input('Add next data to existing data set (0: no, 1: yes)?');
25
if addData > 1 && ~isnumeric(addData)
26
error('Input not valid. Only 0 or 1 are allowed.')
27
end
28
else
29
addData = 0;
30
end
31
32
% Delete old data of new data will not be added. Otherwise get number of
33
% existing elements
34
if ~addData
35
clear sidLogs idData
36
numOldSubflights = 0;
37
numOldSysidflights = 0;
38
else
39
numOldSubflights = numel(sidLogs);
40
if exist('idData', 'var')
41
numOldSysidflights = numel(idData);
42
end
43
end
44
45
% 2) User chooses new flight data from explorer
46
mainPath = pwd;
47
flightDataSearchPath = [mainPath];
48
[files,flightDataPath] = uigetfile({'*.*'},...
49
'Select One or More Files', ...
50
'MultiSelect', 'on', ...
51
flightDataSearchPath);
52
% If only one file is selected, convert char array to cell array
53
if ~iscell(files)
54
files = cellstr(files);
55
numFiles = 1;
56
else
57
numFiles = size(files,2);
58
end
59
60
% 3) Get file extensions - .BIN oder .mat
61
fileExt = cell(numFiles,1);
62
for i=1:numFiles
63
fileExt{i} = files{i}(end-2:end);
64
end
65
66
% 4) Create cell array with file names
67
fileNames = cell(numFiles,1);
68
for i=1:numFiles
69
fileNames{i} = [flightDataPath files{i}];
70
end
71
72
% 5) Load .mat files - loadedDataConfig is struct, so load fileName field
73
chooseSubflights = false;
74
for i=1:numFiles
75
if strcmp(fileExt{i}, 'mat')
76
load(fileNames{i});
77
fileNames = loadedDataConfig.fileNames;
78
% Fill chooseSubflights variable with false for amount of
79
% subflights
80
for j=1:length(loadedDataConfig.subflights)
81
chooseSubflights(j) = false;
82
end
83
else
84
% Activate subflight choosing if BIN files were selected
85
chooseSubflights(i) = true;
86
end
87
end
88
89
%% Load complete log data and show tested modes
90
91
% ---------------------------------------------- %
92
% %
93
% Loading Dataflash Logs %
94
% %
95
% ---------------------------------------------- %
96
97
fprintf('\n-------------------------------------------\nLoading Flash Logs...\n')
98
fprintf('-------------------------------------------\n');
99
100
% Variables to store subflight numbers,amount of subflights and modes
101
subflights = 0;
102
fileIndices = 0;
103
numSubflights = 0;
104
modes = 0;
105
106
for fileIdx = 1:length(fileNames)
107
108
fprintf('Processing file %d ...\n', fileIdx);
109
110
% Throw error if files cannot be found
111
if ~isfile(fileNames{fileIdx})
112
error(['File ' + string(fileNames{fileIdx}) + ' could not be found.']);
113
end
114
logs(fileIdx) = Ardupilog(char(fileNames{fileIdx}));
115
116
% Plot and Output for sysid mode
117
if any(logs(fileIdx).MODE.Mode == 25)
118
fig = figure;
119
set(fig, 'defaultAxesColorOrder', [[0 0 0]; [0 0 0]]); % Set axes color to black
120
121
subplot(2, 1, 1);
122
plot(logs(fileIdx).MODE.TimeS, logs(fileIdx).MODE.ModeNum, 'k*');
123
ylabel(logs(fileIdx).getLabel('MODE/ModeNum'));
124
if ~issorted(logs(fileIdx).MODE.TimeS, 'strictascend')
125
disp([char(fileNames{fileIdx}) ' MODE.TimeS is not monotonic!'])
126
end
127
title(['Sysid Mode' fileNames{fileIdx}], 'Interpreter', 'none');
128
129
% Plot tested SID axes
130
hold on;
131
yyaxis right;
132
plot(logs(fileIdx).SIDS.TimeS, logs(fileIdx).SIDS.Ax, 'r*');
133
ylabel(logs(fileIdx).getLabel('SIDS/Ax'));
134
if ~issorted(logs(fileIdx).SIDS.TimeS, 'strictascend')
135
disp([char(fileNames{fileIdx}) ' SIDS.TimeS is not monotonic!'])
136
end
137
xlim([logs(fileIdx).MODE.TimeS(1) logs(fileIdx).PIDR.TimeS(end)]);
138
hold off;
139
140
% Plot frequency of SID tests
141
subplot(2, 1, 2);
142
plot(logs(fileIdx).SIDD.TimeS, logs(fileIdx).SIDD.F, 'b.');
143
ylabel(logs(fileIdx).getLabel('SIDD/F'));
144
if ~issorted(logs(fileIdx).SIDD.TimeS, 'strictascend')
145
disp([char(fileNames{fileIdx}) ' SIDD.TimeS is not monotonic!'])
146
end
147
hold on;
148
149
% Plot subflight numbers
150
yyaxis right;
151
TimeS = logs(fileIdx).MODE.TimeS;
152
subflightNr = 1:length(logs(fileIdx).MODE.Mode);
153
plot(TimeS, subflightNr, 'k*');
154
ylabel('subflight');
155
if ~issorted(logs(fileIdx).SIDS.TimeS, 'strictascend')
156
disp([char(fileNames{fileIdx}) ' SIDS.TimeS is not monotonic!'])
157
end
158
xlim([logs(fileIdx).MODE.TimeS(1) logs(fileIdx).PIDR.TimeS(end)]);
159
hold off;
160
end
161
162
% Plot for z position controller
163
if ~isempty(logs(fileIdx).PSCD.TimeS)
164
fig = figure;
165
set(fig, 'defaultAxesColorOrder', [[0 0 0]; [0 0 0]]); % Set axes color to black
166
167
% Plot mode numbers
168
subplot(2, 1, 1);
169
plot(logs(fileIdx).MODE.TimeS, logs(fileIdx).MODE.ModeNum, 'k*');
170
ylabel(logs(fileIdx).getLabel('MODE/ModeNum'));
171
if ~issorted(logs(fileIdx).MODE.TimeS, 'strictascend')
172
disp([char(fileNames{fileIdx}) ' MODE.TimeS is not monotonic!'])
173
end
174
xlim([logs(fileIdx).MODE.TimeS(1) logs(fileIdx).PIDR.TimeS(end)]);
175
ylim([min(logs(fileIdx).MODE.ModeNum)-1 max(logs(fileIdx).MODE.ModeNum)+1]);
176
title(['Other Modes' fileNames{fileIdx}], 'Interpreter', 'none');
177
178
% Plot measured z position
179
subplot(2,1,2);
180
plot(logs(fileIdx).PSCD.TimeS, -1*(logs(fileIdx).PSCD.PD), 'b.'); % -1 because of inverted logging of PSCD.PD
181
ylabel('z-Position (m)');
182
if ~issorted(logs(fileIdx).PSCD.TimeS, 'strictascend')
183
disp([char(fileNames{fileIdx}) ' PSCD.TimeS is not monotonic!'])
184
end
185
% Plot subflight numbers
186
hold on;
187
yyaxis right;
188
TimeS = logs(fileIdx).MODE.TimeS;
189
subflightNr = 1:length(logs(fileIdx).MODE.Mode);
190
plot(TimeS, subflightNr, 'k*');
191
ylabel('subflight');
192
xlim([logs(fileIdx).MODE.TimeS(1) logs(fileIdx).PIDR.TimeS(end)]);
193
ylim([0 subflightNr(end)+1]);
194
hold off;
195
end
196
197
% Plot for x-y position controller
198
if ~isempty(logs(fileIdx).PSCN.TimeS) && ~isempty(logs(fileIdx).PSCE.TimeS)
199
fig = figure;
200
set(fig, 'defaultAxesColorOrder', [[0 0 0]; [0 0 0]]); % Set axes color to black
201
202
% Plot mode numbers
203
subplot(2, 1, 1);
204
plot(logs(fileIdx).MODE.TimeS, logs(fileIdx).MODE.ModeNum, 'k*');
205
ylabel(logs(fileIdx).getLabel('MODE/ModeNum'));
206
if ~issorted(logs(fileIdx).MODE.TimeS, 'strictascend')
207
disp([char(fileNames{fileIdx}) ' MODE.TimeS is not monotonic!'])
208
end
209
xlim([logs(fileIdx).MODE.TimeS(1) logs(fileIdx).PIDR.TimeS(end)]);
210
ylim([min(logs(fileIdx).MODE.ModeNum)-1 max(logs(fileIdx).MODE.ModeNum)+1]);
211
title(['Other Modes' fileNames{fileIdx}], 'Interpreter', 'none');
212
213
% Plot measured x and y position
214
subplot(2,1,2);
215
plot(logs(fileIdx).PSCN.TimeS, logs(fileIdx).PSCN.PN, 'r.');
216
ylabel('Position (m)');
217
if ~issorted(logs(fileIdx).PSCN.TimeS, 'strictascend')
218
disp([char(fileNames{fileIdx}) ' PSCN.TimeS is not monotonic!'])
219
end
220
hold on;
221
plot(logs(fileIdx).PSCE.TimeS, logs(fileIdx).PSCE.PE', 'b.');
222
if ~issorted(logs(fileIdx).PSCE.TimeS, 'strictascend')
223
disp([char(fileNames{fileIdx}) ' PSCE.TimeS is not monotonic!'])
224
end
225
226
% Plot subflight numbers
227
yyaxis right;
228
TimeS = logs(fileIdx).MODE.TimeS;
229
subflightNr = 1:length(logs(fileIdx).MODE.Mode);
230
plot(TimeS, subflightNr, 'k*');
231
ylabel('subflight');
232
xlim([logs(fileIdx).MODE.TimeS(1) logs(fileIdx).PIDR.TimeS(end)]);
233
ylim([0 subflightNr(end)+1]);
234
hold off;
235
legend('x-Position', 'y-Position', 'Subflight') % PSCN is x, PSCE is y
236
end
237
238
% This aids the users configuring the subflights
239
disp('Tested Flight Modes:');
240
disp(' flight filename');
241
disp([' ' num2str(fileIdx) ' ' char(fileNames{fileIdx})]);
242
fprintf('Subflight\tMode\tSID_AXIS\n');
243
j = 1;
244
for i=1:length(logs(fileIdx).MODE.Mode)
245
if logs(fileIdx).MODE.Mode(i) == 25
246
% If mode is sysid, print tested axis
247
248
% Decrement sysid mode index j if the start time of
249
% sysid mode was not tracked (and does not equal the mode
250
% time stamps as a result). If it was not tracked, the
251
% settings are identical to the sysid mode before and were
252
% not changed.
253
if abs(logs(fileIdx).MODE.TimeS(i)-logs(fileIdx).SIDS.TimeS(j)) > 0.01 && j > 1
254
j = j-1;
255
end
256
257
fprintf('\t%d\t\t%d\t\t%d\n', i, logs(fileIdx).MODE.Mode(i), logs(fileIdx).SIDS.Ax(j));
258
259
% Increment sysid mode index j only if the start time was
260
% tracked (and equals the mode time stamps as a result).
261
% Otherwise, the tracked sysid information belongs to the
262
% next sysid flight and is equal to the current, so that
263
% the index should not be changed to derive the same infos.
264
if abs(logs(fileIdx).MODE.TimeS(i)-logs(fileIdx).SIDS.TimeS(j)) < 0.01
265
j = j+1;
266
end
267
else
268
% If not, just print mode
269
fprintf('\t%d\t\t%d\t\t-\n', i, logs(fileIdx).MODE.Mode(i));
270
end
271
end
272
273
% Let the user select the subflight if BIN files are selected
274
iSubflights = 1;
275
while(true)
276
if chooseSubflights(fileIdx)
277
nextSubflight = input('Insert number of subflight to be saved (skip with 0): ');
278
% Repeat loop if input is empty
279
if isempty(nextSubflight)
280
continue;
281
end
282
% Leave loop when nextSubflight is zero
283
if nextSubflight == 0
284
fprintf(['Subflight selection for flight ' num2str(fileIdx) ' done.\n']);
285
break;
286
end
287
% Give warnings when given number exceeds number of
288
% subflights...
289
if nextSubflight > length(logs(fileIdx).MODE.Mode)
290
warning('Given number exceeds number of subflights!');
291
continue
292
end
293
% ...or when subflight was selected twice for the same flight
294
if any(nextSubflight == subflights(numSubflights+1:end))
295
warning('Subflight already selected!');
296
continue
297
end
298
299
else
300
% Break if number of added subflights equals the total number
301
% of loaded subflights for that file (represented by appearence
302
% of the respective file index in fileIndices)
303
if numel(subflights)-numSubflights >= sum(loadedDataConfig.fileIndices == fileIdx) && subflights ~= 0
304
break;
305
end
306
% mat file was chosen - read subflight from config
307
nextSubflight = loadedDataConfig.subflights(numSubflights+iSubflights);
308
end
309
310
% Add subflight, file index and mode
311
subflights(numSubflights+iSubflights) = nextSubflight;
312
fileIndices(numSubflights+iSubflights) = fileIdx;
313
modes(numSubflights+iSubflights) = logs(fileIdx).MODE.Mode(nextSubflight);
314
modesConfig(numSubflights+iSubflights) = ModeConfig(modes(end));
315
iSubflights = iSubflights + 1; % Update subflight index
316
317
% Break loop if number of selected subflights equals number of
318
% modes
319
if length(logs(fileIdx).MODE.Mode) < iSubflights
320
break;
321
end
322
end
323
% Update amount of subflights only if 0 was not chosen as subflight
324
if ~any(subflights == 0)
325
numSubflights = length(subflights);
326
end
327
end
328
clear file ax TimeS subflightNr fig nextSubflight iSubflights numFiles fileIdx fileExt
329
clear flightDataSearchPath
330
%% Slice logs to desired subflights
331
332
% Time increment that is used to extend the slicing time interval to
333
% prevent signals (that are only defined at the first time step) to be
334
% excluded from the sliced log because of floating point precision
335
dt_ext = 0.001;
336
337
% Create list for axis that were tested (axis=0 if sysid was not used)
338
axisList = 0;
339
340
% ---------------------------------------------- %
341
% %
342
% Extract relevant log messages and slice logs %
343
% %
344
% ---------------------------------------------- %
345
346
% slice the system identification flight subsection(s)
347
fprintf('\n-------------------------------------------\n')
348
fprintf('Extracting messages and slicing logs...\n');
349
fprintf('-------------------------------------------\n');
350
% Delete sid in case of reloading for new config
351
clear sid
352
for i = 1:length(fileIndices)
353
fprintf(['Subflight Nr. ' num2str(i) '\n']);
354
% Check if current subflight number doesn't exceed actual subflights
355
if (subflights(i) > length(logs(fileIndices(i)).MODE.Mode) )
356
error(['Defined subflight (index ' num2str(i) ') exceeds amount of actual subflights!']);
357
end
358
359
% Filter log messages
360
logFilterMsgs = {};
361
logFilterMsgs = modesConfig(i).filter_msgs;
362
% Check if log_filter_msgs is not empty
363
if ~iscellstr(logFilterMsgs)
364
error('logFilterMsgs variable is not a string cell array');
365
end
366
% Check if message is included in flight log
367
for msg = logFilterMsgs
368
% Skip message if it was not defined - delete it from array
369
if ~isprop(logs(fileIndices(i)), msg{1})
370
warning(['Message ' msg{1} ' not included in subflight ' ...
371
num2str(subflights(i)) ' of logfile ' ...
372
fileNames{fileIndices(i)} '!'])
373
elseif isempty(logs(fileIndices(i)).(msg{1}).LineNo)
374
warning(['Message ' msg{1} ' not included in subflight ' ...
375
num2str(subflights(i)) ' of logfile ' ...
376
fileNames{fileIndices(i)} '!']);
377
logFilterMsgs(strcmp(logFilterMsgs, msg{1})) = [];
378
end
379
end
380
log = logs(fileIndices(i)).filterMsgs(logFilterMsgs);
381
382
% Slice log to desired time section
383
if subflights(i) < length(logs(fileIndices(i)).MODE.Mode)
384
% Current subflight is not last subflight of log
385
start_time = logs(fileIndices(i)).MODE.TimeUS(subflights(i))/1e6;
386
% end time: Subtract 2*dt_ext to prevent first time step of
387
% next flight mode to be part of sliced log
388
end_time = logs(fileIndices(i)).MODE.TimeUS(subflights(i)+1)/1e6-2*dt_ext;
389
else % use end time of TimeUS message in case of the last subflight
390
start_time = logs(fileIndices(i)).MODE.TimeUS(subflights(i))/1e6;
391
end_time = logs(fileIndices(i)).RATE.TimeUS(end)/1e6;
392
end
393
log = log.getSlice( [start_time-dt_ext end_time+dt_ext], 'TimeS');
394
395
% Check if flight mode of log corresponds to defined mode in config
396
if modes(i) ~= log.MODE.Mode
397
error_msg = ['Defined Mode (' num2str(modes(i)) ') in ' ...
398
'mode_list with index ' num2str(i) ' does not correspond '...
399
'to mode of log (' num2str(log.MODE.Mode) ')!'];
400
error(error_msg);
401
end
402
403
% preserve some messages that are outside of the slice time interval
404
log.FMT = logs(fileIndices(i)).FMT;
405
log.UNIT = logs(fileIndices(i)).UNIT;
406
log.FMTU = logs(fileIndices(i)).FMTU;
407
log.MULT = logs(fileIndices(i)).MULT;
408
log.PARM = logs(fileIndices(i)).PARM;
409
% Update the number of actual included messages
410
log.numMsgs = 0;
411
for msg = log.msgsContained
412
msgName = char(msg);
413
% Check if message has been sliced off log
414
if ~isvalid(log.(msgName))
415
warning(['Message ' msg{1} ' in log ' ...
416
num2str(i) ' was sliced off message!']);
417
else
418
log.numMsgs = log.numMsgs + length(log.(msgName).LineNo);
419
end
420
end
421
422
% Get axis from flight. Set to 0 if sysid mode is not active.
423
axis = get_axis(log);
424
axis = axis(1);
425
% Add new axis.
426
axisList(i) = axis;
427
428
% Resample log and save it to sid array
429
sidLogs(numOldSubflights + i).data = resampleLog(log, true, 'linear');
430
end
431
432
% Print modes and/or tested sid axis in log array
433
fprintf('\nChosen test flights:\n')
434
fprintf('Dataset\t|File\t|Subflight\t|Mode\n')
435
for i=1:length(sidLogs)-numOldSubflights
436
fprintf('sid(%d)\t|%d\t\t|%d\t\t\t|%d\n', int16(i+numOldSubflights), ...
437
fileIndices(i), subflights(i), sidLogs(numOldSubflights + i).data.MODE.Mode(1));
438
end
439
440
% Save configuration of loaded data to struct and to repo
441
if numOldSubflights == 0
442
% No configuration in workspace yet
443
loadedDataConfig.fileNames = fileNames;
444
loadedDataConfig.fileIndices = fileIndices;
445
loadedDataConfig.subflights = subflights;
446
loadedDataConfig.modes = modes;
447
loadedDataConfig.modesConfig = modesConfig;
448
loadedDataConfig.axisList = axisList;
449
else
450
% Add new configuration to existing configuration array
451
for i=1:length(fileNames)
452
loadedDataConfig.fileNames{end+1} = fileNames{i};
453
end
454
for i=1:length(fileIndices)
455
% File indices must be adjusted to index of file in existing config
456
loadedDataConfig.fileIndices(numOldSubflights+i) = length(loadedDataConfig.fileNames);
457
loadedDataConfig.subflights(numOldSubflights+i) = subflights(i);
458
loadedDataConfig.modes(numOldSubflights+i) = modes(i);
459
loadedDataConfig.modesConfig(numOldSubflights+i) = modesConfig(i);
460
loadedDataConfig.axisList(numOldSubflights+i) = axisList(i);
461
end
462
end
463
loadedDataConfigFile = [flightDataPath 'dataLoadConfig.mat'];
464
save(loadedDataConfigFile, 'loadedDataConfig');
465
466
% Save new flightdata to repo
467
newDataFile = 'sid.mat';
468
newDataFile = [flightDataPath newDataFile];
469
if exist(newDataFile, 'file')
470
[filename, path] = uiputfile({'*.mat','Mat file (*.mat)';'*.*','All files (*.*)'}, 'Save File Name', ...
471
newDataFile);
472
% Set user-specified file name
473
newDataFile = [flightDataPath filename];
474
end
475
if newDataFile ~= 0
476
if exist('idData','var')
477
save(newDataFile, 'sidLogs', 'idData', 'loadedDataConfig');
478
else
479
save(newDataFile, 'sidLogs', 'loadedDataConfig');
480
end
481
end
482
483
clear msg msgName filename path in_dat out_dat len idd delta_T k
484
clear start_time end_time sid idDataObj minNumElem
485
clear newDataFile logPathName numOldSubflights numOldSysidflights
486
clear fmin fminSweep fmax fmaxSweep addData logs
487
488
clear i j dt_ext log_filenames axis axisList files chooseSubflights
489
clear numSubflights storedFile logFilterMsgs fileNames fileIndices subflights
490
clear dataLoadConfigFile dataStored loadedDataConfigFile modes modesConfig
491
492
% Interact with user to continue
493
uiwait(msgbox(['Data loaded. Press ok to close figures and continue.'],'Data loaded','none','nonmodal'));
494
close all
495
%% Functions
496
% Function to read tested axis from log
497
function axis = get_axis(obj)
498
if isprop(obj, 'SIDS')
499
axis = obj.SIDS.Ax;
500
else
501
% Set to zero if sysid mode is not active
502
axis = 0;
503
end
504
end
505