Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/simulink/arducopter/sid_pre.m
Views: 1799
% Reads ArduPilot's system identification dataflash logs and extracts the SID1% subsections of the fligts into .mat file, discarding all irrelevant data2%3%4% Fabian Bredemeier - IAV GmbH5% License: GPL v367close all;89%% File selection by user1011% ---------------------------------------------- %12% %13% File selection %14% %15% ---------------------------------------------- %1617% 1) Ask user if next data should be added to existing data set18if exist('sidLogs', 'var')19% Abort if config data for existing data is missing20if ~exist('loadedDataConfig', 'var')21error('No configuration of the existing data could be found. Aborting...');22end23addData = input('Add next data to existing data set (0: no, 1: yes)?');24if addData > 1 && ~isnumeric(addData)25error('Input not valid. Only 0 or 1 are allowed.')26end27else28addData = 0;29end3031% Delete old data of new data will not be added. Otherwise get number of32% existing elements33if ~addData34clear sidLogs idData35numOldSubflights = 0;36numOldSysidflights = 0;37else38numOldSubflights = numel(sidLogs);39if exist('idData', 'var')40numOldSysidflights = numel(idData);41end42end4344% 2) User chooses new flight data from explorer45mainPath = pwd;46flightDataSearchPath = [mainPath];47[files,flightDataPath] = uigetfile({'*.*'},...48'Select One or More Files', ...49'MultiSelect', 'on', ...50flightDataSearchPath);51% If only one file is selected, convert char array to cell array52if ~iscell(files)53files = cellstr(files);54numFiles = 1;55else56numFiles = size(files,2);57end5859% 3) Get file extensions - .BIN oder .mat60fileExt = cell(numFiles,1);61for i=1:numFiles62fileExt{i} = files{i}(end-2:end);63end6465% 4) Create cell array with file names66fileNames = cell(numFiles,1);67for i=1:numFiles68fileNames{i} = [flightDataPath files{i}];69end7071% 5) Load .mat files - loadedDataConfig is struct, so load fileName field72chooseSubflights = false;73for i=1:numFiles74if strcmp(fileExt{i}, 'mat')75load(fileNames{i});76fileNames = loadedDataConfig.fileNames;77% Fill chooseSubflights variable with false for amount of78% subflights79for j=1:length(loadedDataConfig.subflights)80chooseSubflights(j) = false;81end82else83% Activate subflight choosing if BIN files were selected84chooseSubflights(i) = true;85end86end8788%% Load complete log data and show tested modes8990% ---------------------------------------------- %91% %92% Loading Dataflash Logs %93% %94% ---------------------------------------------- %9596fprintf('\n-------------------------------------------\nLoading Flash Logs...\n')97fprintf('-------------------------------------------\n');9899% Variables to store subflight numbers,amount of subflights and modes100subflights = 0;101fileIndices = 0;102numSubflights = 0;103modes = 0;104105for fileIdx = 1:length(fileNames)106107fprintf('Processing file %d ...\n', fileIdx);108109% Throw error if files cannot be found110if ~isfile(fileNames{fileIdx})111error(['File ' + string(fileNames{fileIdx}) + ' could not be found.']);112end113logs(fileIdx) = Ardupilog(char(fileNames{fileIdx}));114115% Plot and Output for sysid mode116if any(logs(fileIdx).MODE.Mode == 25)117fig = figure;118set(fig, 'defaultAxesColorOrder', [[0 0 0]; [0 0 0]]); % Set axes color to black119120subplot(2, 1, 1);121plot(logs(fileIdx).MODE.TimeS, logs(fileIdx).MODE.ModeNum, 'k*');122ylabel(logs(fileIdx).getLabel('MODE/ModeNum'));123if ~issorted(logs(fileIdx).MODE.TimeS, 'strictascend')124disp([char(fileNames{fileIdx}) ' MODE.TimeS is not monotonic!'])125end126title(['Sysid Mode' fileNames{fileIdx}], 'Interpreter', 'none');127128% Plot tested SID axes129hold on;130yyaxis right;131plot(logs(fileIdx).SIDS.TimeS, logs(fileIdx).SIDS.Ax, 'r*');132ylabel(logs(fileIdx).getLabel('SIDS/Ax'));133if ~issorted(logs(fileIdx).SIDS.TimeS, 'strictascend')134disp([char(fileNames{fileIdx}) ' SIDS.TimeS is not monotonic!'])135end136xlim([logs(fileIdx).MODE.TimeS(1) logs(fileIdx).PIDR.TimeS(end)]);137hold off;138139% Plot frequency of SID tests140subplot(2, 1, 2);141plot(logs(fileIdx).SIDD.TimeS, logs(fileIdx).SIDD.F, 'b.');142ylabel(logs(fileIdx).getLabel('SIDD/F'));143if ~issorted(logs(fileIdx).SIDD.TimeS, 'strictascend')144disp([char(fileNames{fileIdx}) ' SIDD.TimeS is not monotonic!'])145end146hold on;147148% Plot subflight numbers149yyaxis right;150TimeS = logs(fileIdx).MODE.TimeS;151subflightNr = 1:length(logs(fileIdx).MODE.Mode);152plot(TimeS, subflightNr, 'k*');153ylabel('subflight');154if ~issorted(logs(fileIdx).SIDS.TimeS, 'strictascend')155disp([char(fileNames{fileIdx}) ' SIDS.TimeS is not monotonic!'])156end157xlim([logs(fileIdx).MODE.TimeS(1) logs(fileIdx).PIDR.TimeS(end)]);158hold off;159end160161% Plot for z position controller162if ~isempty(logs(fileIdx).PSCD.TimeS)163fig = figure;164set(fig, 'defaultAxesColorOrder', [[0 0 0]; [0 0 0]]); % Set axes color to black165166% Plot mode numbers167subplot(2, 1, 1);168plot(logs(fileIdx).MODE.TimeS, logs(fileIdx).MODE.ModeNum, 'k*');169ylabel(logs(fileIdx).getLabel('MODE/ModeNum'));170if ~issorted(logs(fileIdx).MODE.TimeS, 'strictascend')171disp([char(fileNames{fileIdx}) ' MODE.TimeS is not monotonic!'])172end173xlim([logs(fileIdx).MODE.TimeS(1) logs(fileIdx).PIDR.TimeS(end)]);174ylim([min(logs(fileIdx).MODE.ModeNum)-1 max(logs(fileIdx).MODE.ModeNum)+1]);175title(['Other Modes' fileNames{fileIdx}], 'Interpreter', 'none');176177% Plot measured z position178subplot(2,1,2);179plot(logs(fileIdx).PSCD.TimeS, -1*(logs(fileIdx).PSCD.PD), 'b.'); % -1 because of inverted logging of PSCD.PD180ylabel('z-Position (m)');181if ~issorted(logs(fileIdx).PSCD.TimeS, 'strictascend')182disp([char(fileNames{fileIdx}) ' PSCD.TimeS is not monotonic!'])183end184% Plot subflight numbers185hold on;186yyaxis right;187TimeS = logs(fileIdx).MODE.TimeS;188subflightNr = 1:length(logs(fileIdx).MODE.Mode);189plot(TimeS, subflightNr, 'k*');190ylabel('subflight');191xlim([logs(fileIdx).MODE.TimeS(1) logs(fileIdx).PIDR.TimeS(end)]);192ylim([0 subflightNr(end)+1]);193hold off;194end195196% Plot for x-y position controller197if ~isempty(logs(fileIdx).PSCN.TimeS) && ~isempty(logs(fileIdx).PSCE.TimeS)198fig = figure;199set(fig, 'defaultAxesColorOrder', [[0 0 0]; [0 0 0]]); % Set axes color to black200201% Plot mode numbers202subplot(2, 1, 1);203plot(logs(fileIdx).MODE.TimeS, logs(fileIdx).MODE.ModeNum, 'k*');204ylabel(logs(fileIdx).getLabel('MODE/ModeNum'));205if ~issorted(logs(fileIdx).MODE.TimeS, 'strictascend')206disp([char(fileNames{fileIdx}) ' MODE.TimeS is not monotonic!'])207end208xlim([logs(fileIdx).MODE.TimeS(1) logs(fileIdx).PIDR.TimeS(end)]);209ylim([min(logs(fileIdx).MODE.ModeNum)-1 max(logs(fileIdx).MODE.ModeNum)+1]);210title(['Other Modes' fileNames{fileIdx}], 'Interpreter', 'none');211212% Plot measured x and y position213subplot(2,1,2);214plot(logs(fileIdx).PSCN.TimeS, logs(fileIdx).PSCN.PN, 'r.');215ylabel('Position (m)');216if ~issorted(logs(fileIdx).PSCN.TimeS, 'strictascend')217disp([char(fileNames{fileIdx}) ' PSCN.TimeS is not monotonic!'])218end219hold on;220plot(logs(fileIdx).PSCE.TimeS, logs(fileIdx).PSCE.PE', 'b.');221if ~issorted(logs(fileIdx).PSCE.TimeS, 'strictascend')222disp([char(fileNames{fileIdx}) ' PSCE.TimeS is not monotonic!'])223end224225% Plot subflight numbers226yyaxis right;227TimeS = logs(fileIdx).MODE.TimeS;228subflightNr = 1:length(logs(fileIdx).MODE.Mode);229plot(TimeS, subflightNr, 'k*');230ylabel('subflight');231xlim([logs(fileIdx).MODE.TimeS(1) logs(fileIdx).PIDR.TimeS(end)]);232ylim([0 subflightNr(end)+1]);233hold off;234legend('x-Position', 'y-Position', 'Subflight') % PSCN is x, PSCE is y235end236237% This aids the users configuring the subflights238disp('Tested Flight Modes:');239disp(' flight filename');240disp([' ' num2str(fileIdx) ' ' char(fileNames{fileIdx})]);241fprintf('Subflight\tMode\tSID_AXIS\n');242j = 1;243for i=1:length(logs(fileIdx).MODE.Mode)244if logs(fileIdx).MODE.Mode(i) == 25245% If mode is sysid, print tested axis246247% Decrement sysid mode index j if the start time of248% sysid mode was not tracked (and does not equal the mode249% time stamps as a result). If it was not tracked, the250% settings are identical to the sysid mode before and were251% not changed.252if abs(logs(fileIdx).MODE.TimeS(i)-logs(fileIdx).SIDS.TimeS(j)) > 0.01 && j > 1253j = j-1;254end255256fprintf('\t%d\t\t%d\t\t%d\n', i, logs(fileIdx).MODE.Mode(i), logs(fileIdx).SIDS.Ax(j));257258% Increment sysid mode index j only if the start time was259% tracked (and equals the mode time stamps as a result).260% Otherwise, the tracked sysid information belongs to the261% next sysid flight and is equal to the current, so that262% the index should not be changed to derive the same infos.263if abs(logs(fileIdx).MODE.TimeS(i)-logs(fileIdx).SIDS.TimeS(j)) < 0.01264j = j+1;265end266else267% If not, just print mode268fprintf('\t%d\t\t%d\t\t-\n', i, logs(fileIdx).MODE.Mode(i));269end270end271272% Let the user select the subflight if BIN files are selected273iSubflights = 1;274while(true)275if chooseSubflights(fileIdx)276nextSubflight = input('Insert number of subflight to be saved (skip with 0): ');277% Repeat loop if input is empty278if isempty(nextSubflight)279continue;280end281% Leave loop when nextSubflight is zero282if nextSubflight == 0283fprintf(['Subflight selection for flight ' num2str(fileIdx) ' done.\n']);284break;285end286% Give warnings when given number exceeds number of287% subflights...288if nextSubflight > length(logs(fileIdx).MODE.Mode)289warning('Given number exceeds number of subflights!');290continue291end292% ...or when subflight was selected twice for the same flight293if any(nextSubflight == subflights(numSubflights+1:end))294warning('Subflight already selected!');295continue296end297298else299% Break if number of added subflights equals the total number300% of loaded subflights for that file (represented by appearence301% of the respective file index in fileIndices)302if numel(subflights)-numSubflights >= sum(loadedDataConfig.fileIndices == fileIdx) && subflights ~= 0303break;304end305% mat file was chosen - read subflight from config306nextSubflight = loadedDataConfig.subflights(numSubflights+iSubflights);307end308309% Add subflight, file index and mode310subflights(numSubflights+iSubflights) = nextSubflight;311fileIndices(numSubflights+iSubflights) = fileIdx;312modes(numSubflights+iSubflights) = logs(fileIdx).MODE.Mode(nextSubflight);313modesConfig(numSubflights+iSubflights) = ModeConfig(modes(end));314iSubflights = iSubflights + 1; % Update subflight index315316% Break loop if number of selected subflights equals number of317% modes318if length(logs(fileIdx).MODE.Mode) < iSubflights319break;320end321end322% Update amount of subflights only if 0 was not chosen as subflight323if ~any(subflights == 0)324numSubflights = length(subflights);325end326end327clear file ax TimeS subflightNr fig nextSubflight iSubflights numFiles fileIdx fileExt328clear flightDataSearchPath329%% Slice logs to desired subflights330331% Time increment that is used to extend the slicing time interval to332% prevent signals (that are only defined at the first time step) to be333% excluded from the sliced log because of floating point precision334dt_ext = 0.001;335336% Create list for axis that were tested (axis=0 if sysid was not used)337axisList = 0;338339% ---------------------------------------------- %340% %341% Extract relevant log messages and slice logs %342% %343% ---------------------------------------------- %344345% slice the system identification flight subsection(s)346fprintf('\n-------------------------------------------\n')347fprintf('Extracting messages and slicing logs...\n');348fprintf('-------------------------------------------\n');349% Delete sid in case of reloading for new config350clear sid351for i = 1:length(fileIndices)352fprintf(['Subflight Nr. ' num2str(i) '\n']);353% Check if current subflight number doesn't exceed actual subflights354if (subflights(i) > length(logs(fileIndices(i)).MODE.Mode) )355error(['Defined subflight (index ' num2str(i) ') exceeds amount of actual subflights!']);356end357358% Filter log messages359logFilterMsgs = {};360logFilterMsgs = modesConfig(i).filter_msgs;361% Check if log_filter_msgs is not empty362if ~iscellstr(logFilterMsgs)363error('logFilterMsgs variable is not a string cell array');364end365% Check if message is included in flight log366for msg = logFilterMsgs367% Skip message if it was not defined - delete it from array368if ~isprop(logs(fileIndices(i)), msg{1})369warning(['Message ' msg{1} ' not included in subflight ' ...370num2str(subflights(i)) ' of logfile ' ...371fileNames{fileIndices(i)} '!'])372elseif isempty(logs(fileIndices(i)).(msg{1}).LineNo)373warning(['Message ' msg{1} ' not included in subflight ' ...374num2str(subflights(i)) ' of logfile ' ...375fileNames{fileIndices(i)} '!']);376logFilterMsgs(strcmp(logFilterMsgs, msg{1})) = [];377end378end379log = logs(fileIndices(i)).filterMsgs(logFilterMsgs);380381% Slice log to desired time section382if subflights(i) < length(logs(fileIndices(i)).MODE.Mode)383% Current subflight is not last subflight of log384start_time = logs(fileIndices(i)).MODE.TimeUS(subflights(i))/1e6;385% end time: Subtract 2*dt_ext to prevent first time step of386% next flight mode to be part of sliced log387end_time = logs(fileIndices(i)).MODE.TimeUS(subflights(i)+1)/1e6-2*dt_ext;388else % use end time of TimeUS message in case of the last subflight389start_time = logs(fileIndices(i)).MODE.TimeUS(subflights(i))/1e6;390end_time = logs(fileIndices(i)).RATE.TimeUS(end)/1e6;391end392log = log.getSlice( [start_time-dt_ext end_time+dt_ext], 'TimeS');393394% Check if flight mode of log corresponds to defined mode in config395if modes(i) ~= log.MODE.Mode396error_msg = ['Defined Mode (' num2str(modes(i)) ') in ' ...397'mode_list with index ' num2str(i) ' does not correspond '...398'to mode of log (' num2str(log.MODE.Mode) ')!'];399error(error_msg);400end401402% preserve some messages that are outside of the slice time interval403log.FMT = logs(fileIndices(i)).FMT;404log.UNIT = logs(fileIndices(i)).UNIT;405log.FMTU = logs(fileIndices(i)).FMTU;406log.MULT = logs(fileIndices(i)).MULT;407log.PARM = logs(fileIndices(i)).PARM;408% Update the number of actual included messages409log.numMsgs = 0;410for msg = log.msgsContained411msgName = char(msg);412% Check if message has been sliced off log413if ~isvalid(log.(msgName))414warning(['Message ' msg{1} ' in log ' ...415num2str(i) ' was sliced off message!']);416else417log.numMsgs = log.numMsgs + length(log.(msgName).LineNo);418end419end420421% Get axis from flight. Set to 0 if sysid mode is not active.422axis = get_axis(log);423axis = axis(1);424% Add new axis.425axisList(i) = axis;426427% Resample log and save it to sid array428sidLogs(numOldSubflights + i).data = resampleLog(log, true, 'linear');429end430431% Print modes and/or tested sid axis in log array432fprintf('\nChosen test flights:\n')433fprintf('Dataset\t|File\t|Subflight\t|Mode\n')434for i=1:length(sidLogs)-numOldSubflights435fprintf('sid(%d)\t|%d\t\t|%d\t\t\t|%d\n', int16(i+numOldSubflights), ...436fileIndices(i), subflights(i), sidLogs(numOldSubflights + i).data.MODE.Mode(1));437end438439% Save configuration of loaded data to struct and to repo440if numOldSubflights == 0441% No configuration in workspace yet442loadedDataConfig.fileNames = fileNames;443loadedDataConfig.fileIndices = fileIndices;444loadedDataConfig.subflights = subflights;445loadedDataConfig.modes = modes;446loadedDataConfig.modesConfig = modesConfig;447loadedDataConfig.axisList = axisList;448else449% Add new configuration to existing configuration array450for i=1:length(fileNames)451loadedDataConfig.fileNames{end+1} = fileNames{i};452end453for i=1:length(fileIndices)454% File indices must be adjusted to index of file in existing config455loadedDataConfig.fileIndices(numOldSubflights+i) = length(loadedDataConfig.fileNames);456loadedDataConfig.subflights(numOldSubflights+i) = subflights(i);457loadedDataConfig.modes(numOldSubflights+i) = modes(i);458loadedDataConfig.modesConfig(numOldSubflights+i) = modesConfig(i);459loadedDataConfig.axisList(numOldSubflights+i) = axisList(i);460end461end462loadedDataConfigFile = [flightDataPath 'dataLoadConfig.mat'];463save(loadedDataConfigFile, 'loadedDataConfig');464465% Save new flightdata to repo466newDataFile = 'sid.mat';467newDataFile = [flightDataPath newDataFile];468if exist(newDataFile, 'file')469[filename, path] = uiputfile({'*.mat','Mat file (*.mat)';'*.*','All files (*.*)'}, 'Save File Name', ...470newDataFile);471% Set user-specified file name472newDataFile = [flightDataPath filename];473end474if newDataFile ~= 0475if exist('idData','var')476save(newDataFile, 'sidLogs', 'idData', 'loadedDataConfig');477else478save(newDataFile, 'sidLogs', 'loadedDataConfig');479end480end481482clear msg msgName filename path in_dat out_dat len idd delta_T k483clear start_time end_time sid idDataObj minNumElem484clear newDataFile logPathName numOldSubflights numOldSysidflights485clear fmin fminSweep fmax fmaxSweep addData logs486487clear i j dt_ext log_filenames axis axisList files chooseSubflights488clear numSubflights storedFile logFilterMsgs fileNames fileIndices subflights489clear dataLoadConfigFile dataStored loadedDataConfigFile modes modesConfig490491% Interact with user to continue492uiwait(msgbox(['Data loaded. Press ok to close figures and continue.'],'Data loaded','none','nonmodal'));493close all494%% Functions495% Function to read tested axis from log496function axis = get_axis(obj)497if isprop(obj, 'SIDS')498axis = obj.SIDS.Ax;499else500% Set to zero if sysid mode is not active501axis = 0;502end503end504505