QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
APMDataFlashLogParser.cc
Go to the documentation of this file.
2
5
6#include <QtConcurrent/QtConcurrent>
7#include <QtCore/QFile>
8#include <QtCore/QFutureWatcher>
9#include <QtCore/QHash>
10#include <QtCore/QSet>
11
12#include <algorithm>
13#include <cmath>
14#include <limits>
15
16QGC_LOGGING_CATEGORY(APMDataFlashLogParserLog, "AnalyzeView.APMDataFlashLogParser")
17
18namespace {
19struct ParseResult {
20 bool ok = false;
21 QString errorMessage;
22 QStringList availableFields;
23 QStringList plottableFields;
24 QVariantList parameters;
25 QVariantList events;
26 QVariantList messages;
27 QVariantList modeSegments;
28 QHash<QString, QVector<QPointF>> fieldSamples;
29 double minTimestamp = -1.0;
30 double maxTimestamp = -1.0;
31 int sampleCount = 0;
32 QString detectedVehicleType;
33};
34
35QString _vehicleTypeFromMessageText(const QString &messageText)
36{
37 const QString text = messageText.toLower();
38 if (text.contains(QStringLiteral("arducopter"))) {
39 return QStringLiteral("ArduCopter");
40 }
41 if (text.contains(QStringLiteral("arduplane"))) {
42 return QStringLiteral("ArduPlane");
43 }
44 if (text.contains(QStringLiteral("ardurover"))) {
45 return QStringLiteral("ArduRover");
46 }
47 if (text.contains(QStringLiteral("ardusub"))) {
48 return QStringLiteral("ArduSub");
49 }
50
51 return QString();
52}
53
54QString _ardupilotModeName(const QString &vehicleType, int modeNumber)
55{
56 static const QHash<int, QString> planeModes = {
57 {0, QStringLiteral("Manual")},
58 {1, QStringLiteral("CIRCLE")},
59 {2, QStringLiteral("STABILIZE")},
60 {3, QStringLiteral("TRAINING")},
61 {4, QStringLiteral("ACRO")},
62 {5, QStringLiteral("FBWA")},
63 {6, QStringLiteral("FBWB")},
64 {7, QStringLiteral("CRUISE")},
65 {8, QStringLiteral("AUTOTUNE")},
66 {10, QStringLiteral("Auto")},
67 {11, QStringLiteral("RTL")},
68 {12, QStringLiteral("Loiter")},
69 {13, QStringLiteral("TAKEOFF")},
70 {14, QStringLiteral("AVOID_ADSB")},
71 {15, QStringLiteral("Guided")},
72 {17, QStringLiteral("QSTABILIZE")},
73 {18, QStringLiteral("QHOVER")},
74 {19, QStringLiteral("QLOITER")},
75 {20, QStringLiteral("QLAND")},
76 {21, QStringLiteral("QRTL")},
77 {22, QStringLiteral("QAUTOTUNE")},
78 {23, QStringLiteral("QACRO")},
79 {24, QStringLiteral("THERMAL")},
80 {25, QStringLiteral("Loiter to QLand")},
81 {26, QStringLiteral("AUTOLAND")},
82 };
83 static const QHash<int, QString> copterModes = {
84 {0, QStringLiteral("Stabilize")},
85 {1, QStringLiteral("Acro")},
86 {2, QStringLiteral("AltHold")},
87 {3, QStringLiteral("Auto")},
88 {4, QStringLiteral("Guided")},
89 {5, QStringLiteral("Loiter")},
90 {6, QStringLiteral("RTL")},
91 {7, QStringLiteral("Circle")},
92 {9, QStringLiteral("Land")},
93 {11, QStringLiteral("Drift")},
94 {13, QStringLiteral("Sport")},
95 {14, QStringLiteral("Flip")},
96 {15, QStringLiteral("AutoTune")},
97 {16, QStringLiteral("PosHold")},
98 {17, QStringLiteral("Brake")},
99 {18, QStringLiteral("Throw")},
100 {19, QStringLiteral("Avoid_ADSB")},
101 {20, QStringLiteral("Guided_NoGPS")},
102 {21, QStringLiteral("Smart_RTL")},
103 {22, QStringLiteral("FlowHold")},
104 {23, QStringLiteral("Follow")},
105 {24, QStringLiteral("ZigZag")},
106 {25, QStringLiteral("SystemID")},
107 {26, QStringLiteral("Heli_Autorotate")},
108 {27, QStringLiteral("Auto RTL")},
109 {28, QStringLiteral("Turtle")},
110 };
111
112 if (vehicleType == QStringLiteral("ArduPlane")) {
113 return planeModes.value(modeNumber, QStringLiteral("Mode %1").arg(modeNumber));
114 }
115 if (vehicleType == QStringLiteral("ArduCopter")) {
116 return copterModes.value(modeNumber, QStringLiteral("Mode %1").arg(modeNumber));
117 }
118
119 // Numeric ArduPilot mode values are vehicle-specific. Without reliable
120 // vehicle-type detection, preserve numeric representation.
121 return QStringLiteral("Mode %1").arg(modeNumber);
122}
123
124QString _ardupilotErrDescription(int subsystem, int ecode)
125{
126 QString subsystemName;
127 switch (subsystem) {
128 case 1: subsystemName = APMDataFlashLogParser::tr("Main"); break;
129 case 2: subsystemName = APMDataFlashLogParser::tr("Radio"); break;
130 case 3: subsystemName = APMDataFlashLogParser::tr("Compass"); break;
131 case 4: subsystemName = APMDataFlashLogParser::tr("Optflow"); break;
132 case 5: subsystemName = APMDataFlashLogParser::tr("Radio Failsafe"); break;
133 case 6: subsystemName = APMDataFlashLogParser::tr("Battery Failsafe"); break;
134 case 7: subsystemName = APMDataFlashLogParser::tr("GPS Failsafe"); break;
135 case 8: subsystemName = APMDataFlashLogParser::tr("GCS Failsafe"); break;
136 case 9: subsystemName = APMDataFlashLogParser::tr("Fence Failsafe"); break;
137 case 10: subsystemName = APMDataFlashLogParser::tr("Flight mode"); break;
138 case 11: subsystemName = APMDataFlashLogParser::tr("GPS"); break;
139 case 12: subsystemName = APMDataFlashLogParser::tr("Crash Check"); break;
140 case 13: subsystemName = APMDataFlashLogParser::tr("Flip"); break;
141 case 14: subsystemName = APMDataFlashLogParser::tr("Autotune"); break;
142 case 15: subsystemName = APMDataFlashLogParser::tr("Parachute"); break;
143 case 16: subsystemName = APMDataFlashLogParser::tr("EKF Check"); break;
144 case 17: subsystemName = APMDataFlashLogParser::tr("EKF Failsafe"); break;
145 case 18: subsystemName = APMDataFlashLogParser::tr("Barometer"); break;
146 case 19: subsystemName = APMDataFlashLogParser::tr("CPU Load Watchdog"); break;
147 case 20: subsystemName = APMDataFlashLogParser::tr("ADSB Failsafe"); break;
148 case 21: subsystemName = APMDataFlashLogParser::tr("Terrain Data"); break;
149 case 22: subsystemName = APMDataFlashLogParser::tr("Navigation"); break;
150 case 23: subsystemName = APMDataFlashLogParser::tr("Terrain Failsafe"); break;
151 case 24: subsystemName = APMDataFlashLogParser::tr("EKF Primary"); break;
152 case 25: subsystemName = APMDataFlashLogParser::tr("Thrust Loss Check"); break;
153 case 26: subsystemName = APMDataFlashLogParser::tr("Sensor Failsafe"); break;
154 case 27: subsystemName = APMDataFlashLogParser::tr("Leak Failsafe"); break;
155 case 28: subsystemName = APMDataFlashLogParser::tr("Pilot Input"); break;
156 case 29: subsystemName = APMDataFlashLogParser::tr("Vibration Failsafe"); break;
157 case 30: subsystemName = APMDataFlashLogParser::tr("Internal Error"); break;
158 case 31: subsystemName = APMDataFlashLogParser::tr("Deadreckon Failsafe"); break;
159 default: subsystemName = APMDataFlashLogParser::tr("Subsystem %1").arg(subsystem); break;
160 }
161
162 QString ecodeText;
163 switch (subsystem) {
164 case 1: // MAIN
165 if (ecode == 1) { ecodeText = APMDataFlashLogParser::tr("INS delay"); }
166 break;
167 case 2: // RADIO
168 if (ecode == 0) { ecodeText = APMDataFlashLogParser::tr("Errors Resolved"); }
169 else if (ecode == 2) { ecodeText = APMDataFlashLogParser::tr("Late Frame"); }
170 break;
171 case 3: // COMPASS
172 if (ecode == 0) { ecodeText = APMDataFlashLogParser::tr("Errors Resolved"); }
173 else if (ecode == 1) { ecodeText = APMDataFlashLogParser::tr("Failed to initialise"); }
174 else if (ecode == 4) { ecodeText = APMDataFlashLogParser::tr("Unhealthy"); }
175 break;
176 case 5: // FAILSAFE_RADIO
177 case 6: // FAILSAFE_BATT
178 case 7: // FAILSAFE_GPS
179 case 8: // FAILSAFE_GCS
180 case 17: // FAILSAFE_EKFINAV
181 case 19: // CPU
182 case 23: // FAILSAFE_TERRAIN
183 case 26: // FAILSAFE_SENSORS
184 case 27: // FAILSAFE_LEAK
185 case 28: // PILOT_INPUT
186 case 31: // FAILSAFE_DEADRECKON
187 if (ecode == 0) { ecodeText = APMDataFlashLogParser::tr("Failsafe Resolved"); }
188 else if (ecode == 1) { ecodeText = APMDataFlashLogParser::tr("Failsafe Triggered"); }
189 break;
190 case 9: // FAILSAFE_FENCE
191 if (ecode == 0) { ecodeText = APMDataFlashLogParser::tr("Failsafe Resolved"); }
192 else if (ecode == 1) { ecodeText = APMDataFlashLogParser::tr("Altitude fence breach"); }
193 else if (ecode == 2) { ecodeText = APMDataFlashLogParser::tr("Circular fence breach"); }
194 else if (ecode == 3) { ecodeText = APMDataFlashLogParser::tr("Altitude and circular fence breach"); }
195 else if (ecode == 4) { ecodeText = APMDataFlashLogParser::tr("Polygon fence breach"); }
196 break;
197 case 10: // FLIGHT_MODE
198 if (ecode == 0) { ecodeText = APMDataFlashLogParser::tr("Flight mode change failure"); }
199 break;
200 case 11: // GPS
201 if (ecode == 0) { ecodeText = APMDataFlashLogParser::tr("Glitch cleared"); }
202 else if (ecode == 2) { ecodeText = APMDataFlashLogParser::tr("GPS glitch occurred"); }
203 break;
204 case 12: // CRASH_CHECK
205 if (ecode == 1) { ecodeText = APMDataFlashLogParser::tr("Crash into ground detected"); }
206 else if (ecode == 2) { ecodeText = APMDataFlashLogParser::tr("Loss of control detected"); }
207 break;
208 case 13: // FLIP
209 if (ecode == 2) { ecodeText = APMDataFlashLogParser::tr("Flip abandoned"); }
210 break;
211 case 15: // PARACHUTES
212 if (ecode == 2) { ecodeText = APMDataFlashLogParser::tr("Parachute not deployed (too low)"); }
213 else if (ecode == 3) { ecodeText = APMDataFlashLogParser::tr("Parachute not deployed (landed)"); }
214 break;
215 case 16: // EKFCHECK
216 if (ecode == 0) { ecodeText = APMDataFlashLogParser::tr("Variance cleared"); }
217 else if (ecode == 2) { ecodeText = APMDataFlashLogParser::tr("Bad variance"); }
218 break;
219 case 18: // BARO
220 if (ecode == 0) { ecodeText = APMDataFlashLogParser::tr("Errors Resolved"); }
221 else if (ecode == 2) { ecodeText = APMDataFlashLogParser::tr("Baro glitch"); }
222 else if (ecode == 3) { ecodeText = APMDataFlashLogParser::tr("Bad depth"); }
223 else if (ecode == 4) { ecodeText = APMDataFlashLogParser::tr("Unhealthy"); }
224 break;
225 case 20: // FAILSAFE_ADSB
226 if (ecode == 0) { ecodeText = APMDataFlashLogParser::tr("Failsafe Resolved"); }
227 else if (ecode == 1) { ecodeText = APMDataFlashLogParser::tr("No action report only"); }
228 else if (ecode == 2) { ecodeText = APMDataFlashLogParser::tr("Avoid by climb/descend"); }
229 else if (ecode == 3) { ecodeText = APMDataFlashLogParser::tr("Avoid by horizontal move"); }
230 else if (ecode == 4) { ecodeText = APMDataFlashLogParser::tr("Avoid perpendicular move"); }
231 else if (ecode == 5) { ecodeText = APMDataFlashLogParser::tr("RTL invoked"); }
232 break;
233 case 21: // TERRAIN
234 if (ecode == 2) { ecodeText = APMDataFlashLogParser::tr("Missing terrain data"); }
235 break;
236 case 22: // NAVIGATION
237 if (ecode == 2) { ecodeText = APMDataFlashLogParser::tr("Failed to set destination"); }
238 else if (ecode == 3) { ecodeText = APMDataFlashLogParser::tr("RTL restarted"); }
239 else if (ecode == 4) { ecodeText = APMDataFlashLogParser::tr("Circle initialisation failed"); }
240 else if (ecode == 5) { ecodeText = APMDataFlashLogParser::tr("Destination outside fence"); }
241 else if (ecode == 6) { ecodeText = APMDataFlashLogParser::tr("RTL missing rangefinder"); }
242 break;
243 case 24: // EKF_PRIMARY
244 if (ecode == 0) { ecodeText = APMDataFlashLogParser::tr("1st EKF became primary"); }
245 else if (ecode == 1) { ecodeText = APMDataFlashLogParser::tr("2nd EKF became primary"); }
246 break;
247 case 25: // THRUST_LOSS_CHECK
248 if (ecode == 0) { ecodeText = APMDataFlashLogParser::tr("Thrust restored"); }
249 else if (ecode == 1) { ecodeText = APMDataFlashLogParser::tr("Thrust loss detected"); }
250 break;
251 case 29: // FAILSAFE_VIBE
252 if (ecode == 0) { ecodeText = APMDataFlashLogParser::tr("Excessive vibration compensation de-activated"); }
253 else if (ecode == 1) { ecodeText = APMDataFlashLogParser::tr("Excessive vibration compensation activated"); }
254 break;
255 case 30: // INTERNAL_ERROR
256 if (ecode == 1) { ecodeText = APMDataFlashLogParser::tr("Internal errors detected"); }
257 break;
258 default:
259 break;
260 }
261
262 if (ecodeText.isEmpty()) {
263 ecodeText = APMDataFlashLogParser::tr("Code %1").arg(ecode);
264 }
265
266 return QStringLiteral("%1 (%2): %3 (%4)").arg(subsystemName).arg(subsystem).arg(ecodeText).arg(ecode);
267}
268
269QString _ardupilotEventDescription(int eventId)
270{
271 switch (eventId) {
272 case 10: return APMDataFlashLogParser::tr("Armed");
273 case 11: return APMDataFlashLogParser::tr("Disarmed");
274 case 15: return APMDataFlashLogParser::tr("Auto Armed");
275 case 17: return APMDataFlashLogParser::tr("Land Complete Maybe");
276 case 18: return APMDataFlashLogParser::tr("Land Complete");
277 case 19: return APMDataFlashLogParser::tr("Lost GPS");
278 case 21: return APMDataFlashLogParser::tr("Flip Start");
279 case 22: return APMDataFlashLogParser::tr("Flip End");
280 case 25: return APMDataFlashLogParser::tr("Set Home");
281 case 26: return APMDataFlashLogParser::tr("Simple Mode Enabled");
282 case 27: return APMDataFlashLogParser::tr("Simple Mode Disabled");
283 case 28: return APMDataFlashLogParser::tr("Not Landed");
284 case 29: return APMDataFlashLogParser::tr("Super Simple Mode Enabled");
285 case 30: return APMDataFlashLogParser::tr("AutoTune Initialised");
286 case 31: return APMDataFlashLogParser::tr("AutoTune Off");
287 case 32: return APMDataFlashLogParser::tr("AutoTune Restart");
288 case 33: return APMDataFlashLogParser::tr("AutoTune Success");
289 case 34: return APMDataFlashLogParser::tr("AutoTune Failed");
290 case 35: return APMDataFlashLogParser::tr("AutoTune Reached Limit");
291 case 36: return APMDataFlashLogParser::tr("AutoTune Pilot Testing");
292 case 37: return APMDataFlashLogParser::tr("AutoTune Saved Gains");
293 case 38: return APMDataFlashLogParser::tr("Save Trim");
294 case 39: return APMDataFlashLogParser::tr("Save Waypoint Add");
295 case 41: return APMDataFlashLogParser::tr("Fence Enabled");
296 case 42: return APMDataFlashLogParser::tr("Fence Disabled");
297 case 43: return APMDataFlashLogParser::tr("Acro Trainer Off");
298 case 44: return APMDataFlashLogParser::tr("Acro Trainer Leveling");
299 case 45: return APMDataFlashLogParser::tr("Acro Trainer Limited");
300 case 46: return APMDataFlashLogParser::tr("Gripper Grab");
301 case 47: return APMDataFlashLogParser::tr("Gripper Release");
302 case 49: return APMDataFlashLogParser::tr("Parachute Disabled");
303 case 50: return APMDataFlashLogParser::tr("Parachute Enabled");
304 case 51: return APMDataFlashLogParser::tr("Parachute Released");
305 case 52: return APMDataFlashLogParser::tr("Landing Gear Deployed");
306 case 53: return APMDataFlashLogParser::tr("Landing Gear Retracted");
307 case 54: return APMDataFlashLogParser::tr("Motors Emergency Stopped");
308 case 55: return APMDataFlashLogParser::tr("Motors Emergency Stop Cleared");
309 case 56: return APMDataFlashLogParser::tr("Motors Interlock Disabled");
310 case 57: return APMDataFlashLogParser::tr("Motors Interlock Enabled");
311 case 58: return APMDataFlashLogParser::tr("Rotor Runup Complete");
312 case 59: return APMDataFlashLogParser::tr("Rotor Speed Below Critical");
313 case 60: return APMDataFlashLogParser::tr("EKF Altitude Reset");
314 case 61: return APMDataFlashLogParser::tr("Land Cancelled By Pilot");
315 case 62: return APMDataFlashLogParser::tr("EKF Yaw Reset");
316 case 63: return APMDataFlashLogParser::tr("ADSB Avoidance Enabled");
317 case 64: return APMDataFlashLogParser::tr("ADSB Avoidance Disabled");
318 case 65: return APMDataFlashLogParser::tr("Proximity Avoidance Enabled");
319 case 66: return APMDataFlashLogParser::tr("Proximity Avoidance Disabled");
320 case 67: return APMDataFlashLogParser::tr("GPS Primary Changed");
321 case 71: return APMDataFlashLogParser::tr("ZigZag Store A");
322 case 72: return APMDataFlashLogParser::tr("ZigZag Store B");
323 case 73: return APMDataFlashLogParser::tr("Land Repo Active");
324 case 74: return APMDataFlashLogParser::tr("Standby Enabled");
325 case 75: return APMDataFlashLogParser::tr("Standby Disabled");
326 case 76: return APMDataFlashLogParser::tr("Fence Alt Max Enabled");
327 case 77: return APMDataFlashLogParser::tr("Fence Alt Max Disabled");
328 case 78: return APMDataFlashLogParser::tr("Fence Circle Enabled");
329 case 79: return APMDataFlashLogParser::tr("Fence Circle Disabled");
330 case 80: return APMDataFlashLogParser::tr("Fence Alt Min Enabled");
331 case 81: return APMDataFlashLogParser::tr("Fence Alt Min Disabled");
332 case 82: return APMDataFlashLogParser::tr("Fence Polygon Enabled");
333 case 83: return APMDataFlashLogParser::tr("Fence Polygon Disabled");
334 case 85: return APMDataFlashLogParser::tr("EK3 Source Set: Primary");
335 case 86: return APMDataFlashLogParser::tr("EK3 Source Set: Secondary");
336 case 87: return APMDataFlashLogParser::tr("EK3 Source Set: Tertiary");
337 case 90: return APMDataFlashLogParser::tr("Airspeed Primary Changed");
338 case 163: return APMDataFlashLogParser::tr("Surfaced");
339 case 164: return APMDataFlashLogParser::tr("Not Surfaced");
340 case 165: return APMDataFlashLogParser::tr("Bottomed");
341 case 166: return APMDataFlashLogParser::tr("Not Bottomed");
342 default: return APMDataFlashLogParser::tr("Event %1").arg(eventId);
343 }
344}
345
346double _extractTimestampSeconds(const QMap<QString, QVariant> &values)
347{
348 if (values.contains(QStringLiteral("TimeUS"))) {
349 return values.value(QStringLiteral("TimeUS")).toDouble() / 1000000.0;
350 }
351 if (values.contains(QStringLiteral("TimeMS"))) {
352 return values.value(QStringLiteral("TimeMS")).toDouble() / 1000.0;
353 }
354 if (values.contains(QStringLiteral("Time"))) {
355 return values.value(QStringLiteral("Time")).toDouble() / 1000.0;
356 }
357
358 return -1.0;
359}
360
361void _appendEvent(QVariantList &events, double timestampSecs, const QString &type, const QString &description)
362{
363 if ((timestampSecs < 0.0) || description.isEmpty()) {
364 return;
365 }
366
367 QVariantMap eventRow;
368 eventRow[QStringLiteral("time")] = timestampSecs;
369 eventRow[QStringLiteral("type")] = type;
370 eventRow[QStringLiteral("description")] = description;
371 events.append(eventRow);
372}
373
374ParseResult _parseDataFlashFile(const QString &filePath)
375{
376 ParseResult result;
377
378 QFile file(filePath);
379 if (!file.open(QIODevice::ReadOnly)) {
380 result.errorMessage = APMDataFlashLogParser::tr("Failed to open DataFlash file");
381 return result;
382 }
383
384 const qint64 fileSize = file.size();
385 if (fileSize <= 0) {
386 result.errorMessage = APMDataFlashLogParser::tr("DataFlash file is empty");
387 return result;
388 }
389 if (fileSize > std::numeric_limits<qsizetype>::max()) {
390 result.errorMessage = APMDataFlashLogParser::tr("DataFlash file is too large to parse");
391 return result;
392 }
393
394 uchar *const mappedData = file.map(0, fileSize);
395 if (mappedData == nullptr) {
396 result.errorMessage = APMDataFlashLogParser::tr("Failed to memory-map DataFlash file");
397 return result;
398 }
399
400 struct ScopedFileUnmap {
401 QFile &file;
402 uchar *data = nullptr;
403 ~ScopedFileUnmap()
404 {
405 if (data != nullptr) {
406 file.unmap(data);
407 }
408 }
409 } scopedFileUnmap{file, mappedData};
410
411 const QByteArray bytes = QByteArray::fromRawData(reinterpret_cast<const char *>(mappedData), static_cast<qsizetype>(fileSize));
412
413 QMap<uint8_t, APMDataFlashUtility::MessageFormat> formats;
414 if (!APMDataFlashUtility::parseFmtMessages(bytes.constData(), bytes.size(), formats)) {
415 result.errorMessage = APMDataFlashLogParser::tr("No valid FMT messages were found");
416 return result;
417 }
418
419 QSet<QString> signalSet;
420 QSet<QString> plottableSet;
421 double minTimestampSecs = -1.0;
422 double maxTimestampSecs = -1.0;
423 bool hasOpenModeSegment = false;
424 double modeSegmentStartSecs = -1.0;
425 QString currentModeName;
426
427 // Precompute, once per format, the fully-qualified signal names ("<msg>.<col>")
428 // and a lookup map from column name to that pre-formatted signal name. Building
429 // these names per-message via QString::arg() previously dominated parse cost.
430 QHash<uint8_t, QHash<QString, QString>> signalNameByCol;
431 signalNameByCol.reserve(formats.size());
432 for (auto fmtIt = formats.cbegin(); fmtIt != formats.cend(); ++fmtIt) {
433 const APMDataFlashUtility::MessageFormat &fmt = fmtIt.value();
434 QHash<QString, QString> &perCol = signalNameByCol[fmtIt.key()];
435 perCol.reserve(fmt.columns.size());
436 for (const QString &col : fmt.columns) {
437 perCol.insert(col, fmt.name + QLatin1Char('.') + col);
438 }
439 }
440
441 static const QString kPARM = QStringLiteral("PARM");
442 static const QString kMSG = QStringLiteral("MSG");
443 static const QString kMODE = QStringLiteral("MODE");
444 static const QString kERR = QStringLiteral("ERR");
445 static const QString kEV = QStringLiteral("EV");
446
447 APMDataFlashUtility::iterateMessages(bytes.constData(), bytes.size(), formats, [&result, &signalSet, &plottableSet, &minTimestampSecs, &maxTimestampSecs, &hasOpenModeSegment, &modeSegmentStartSecs, &currentModeName, &signalNameByCol](uint8_t msgType, const char *payload, int, const APMDataFlashUtility::MessageFormat &fmt) {
448 const QMap<QString, QVariant> values = APMDataFlashUtility::parseMessage(payload, fmt);
449 const double timestampSecs = _extractTimestampSeconds(values);
450 if (timestampSecs >= 0.0) {
451 if (minTimestampSecs < 0.0 || timestampSecs < minTimestampSecs) {
452 minTimestampSecs = timestampSecs;
453 }
454 maxTimestampSecs = std::max(maxTimestampSecs, timestampSecs);
455 }
456
457 if (fmt.name == kPARM) {
458 const QString paramName = values.value(QStringLiteral("Name")).toString();
459 const QVariant paramValue = values.contains(QStringLiteral("Value")) ? values.value(QStringLiteral("Value")) : values.value(QStringLiteral("Val"));
460 if (!paramName.isEmpty()) {
461 QVariantMap row;
462 row[QStringLiteral("name")] = paramName;
463 row[QStringLiteral("value")] = paramValue;
464 result.parameters.append(row);
465 }
466 } else if (fmt.name == kMSG) {
467 const QString text = values.value(QStringLiteral("Message")).toString();
468 const QString detected = _vehicleTypeFromMessageText(text);
469 if (result.detectedVehicleType.isEmpty() && !detected.isEmpty()) {
470 result.detectedVehicleType = detected;
471 }
472 if (!text.isEmpty()) {
473 QVariantMap row;
474 row[QStringLiteral("time")] = timestampSecs;
475 row[QStringLiteral("text")] = text;
476 result.messages.append(row);
477 }
478 } else if (fmt.name == kMODE) {
479 QString modeName = values.value(QStringLiteral("Mode")).toString();
480 bool isNumericMode = false;
481 const int modeNumber = modeName.toInt(&isNumericMode);
482 if (isNumericMode) {
483 modeName = _ardupilotModeName(result.detectedVehicleType, modeNumber);
484 } else if (modeName.isEmpty()) {
485 modeName = APMDataFlashLogParser::tr("Unknown");
486 }
487 _appendEvent(result.events, timestampSecs, QStringLiteral("mode"), APMDataFlashLogParser::tr("Mode: %1").arg(modeName));
488 if (timestampSecs >= 0.0) {
489 if (hasOpenModeSegment && (timestampSecs > modeSegmentStartSecs)) {
490 QVariantMap segment;
491 segment[QStringLiteral("mode")] = currentModeName;
492 segment[QStringLiteral("start")] = modeSegmentStartSecs;
493 segment[QStringLiteral("end")] = timestampSecs;
494 result.modeSegments.append(segment);
495 }
496 hasOpenModeSegment = true;
497 modeSegmentStartSecs = timestampSecs;
498 currentModeName = modeName;
499 }
500 } else if (fmt.name == kERR) {
501 const int subsystem = values.value(QStringLiteral("Subsys")).toInt();
502 const int ecode = values.value(QStringLiteral("ECode")).toInt();
503 _appendEvent(result.events, timestampSecs, QStringLiteral("error"), _ardupilotErrDescription(subsystem, ecode));
504 } else if (fmt.name == kEV) {
505 const int eventId = values.value(QStringLiteral("Id"), values.value(QStringLiteral("Event"))).toInt();
506 _appendEvent(result.events, timestampSecs, QStringLiteral("event"), _ardupilotEventDescription(eventId));
507 }
508
509 result.sampleCount++;
510
511 // Single pass: lookup precomputed signal names, populate signal/plottable
512 // sets, and append numeric samples in one walk over the values map.
513 const QHash<QString, QString> &perCol = signalNameByCol[msgType];
514 const bool haveTimestamp = (timestampSecs >= 0.0);
515 for (auto it = values.cbegin(); it != values.cend(); ++it) {
516 const auto nameIt = perCol.constFind(it.key());
517 if (nameIt == perCol.constEnd()) {
518 continue;
519 }
520 const QString &signalName = nameIt.value();
521 signalSet.insert(signalName);
522
523 if (!haveTimestamp) {
524 continue;
525 }
526 const int typeId = it.value().metaType().id();
527 const bool numeric = (typeId == QMetaType::Int) || (typeId == QMetaType::UInt) ||
528 (typeId == QMetaType::LongLong) || (typeId == QMetaType::ULongLong) ||
529 (typeId == QMetaType::Float) || (typeId == QMetaType::Double);
530 if (numeric) {
531 result.fieldSamples[signalName].append(QPointF(timestampSecs, it.value().toDouble()));
532 plottableSet.insert(signalName);
533 }
534 }
535
536 return true;
537 });
538
539 if (hasOpenModeSegment && (maxTimestampSecs >= modeSegmentStartSecs)) {
540 QVariantMap segment;
541 segment[QStringLiteral("mode")] = currentModeName;
542 segment[QStringLiteral("start")] = modeSegmentStartSecs;
543 segment[QStringLiteral("end")] = maxTimestampSecs;
544 result.modeSegments.append(segment);
545 }
546
547 result.availableFields = signalSet.values();
548 std::sort(result.availableFields.begin(), result.availableFields.end());
549 result.plottableFields = plottableSet.values();
550 std::sort(result.plottableFields.begin(), result.plottableFields.end());
551 result.minTimestamp = minTimestampSecs;
552 result.maxTimestamp = maxTimestampSecs;
553 result.ok = true;
554 return result;
555}
556} // namespace
557
558APMDataFlashLogParser::APMDataFlashLogParser(QObject *parent)
559 : QObject(parent)
560{
561 qCDebug(APMDataFlashLogParserLog) << this;
562}
563
564APMDataFlashLogParser::~APMDataFlashLogParser()
565{
566 qCDebug(APMDataFlashLogParserLog) << this;
567}
568
569bool APMDataFlashLogParser::parseFile(const QString &filePath)
570{
571 ++_parseRequestId; // Invalidate any in-flight async parse results.
572 clear();
573 const ParseResult result = _parseDataFlashFile(filePath);
574 if (!result.ok) {
575 _setParseError(result.errorMessage);
576 return false;
577 }
578
579 _availableFields = result.availableFields;
580 _plottableFields = result.plottableFields;
581 _parameters = result.parameters;
582 _events = result.events;
583 _messages = result.messages;
584 _modeSegments = result.modeSegments;
585 _fieldSamples = result.fieldSamples;
586 _sampleCount = result.sampleCount;
587 _detectedVehicleType = result.detectedVehicleType;
590 emit parametersChanged();
591 emit eventsChanged();
592 emit messagesChanged();
593 emit modeSegmentsChanged();
595 if (_minTimestamp != result.minTimestamp || _maxTimestamp != result.maxTimestamp) {
596 _minTimestamp = result.minTimestamp;
597 _maxTimestamp = result.maxTimestamp;
598 emit timeRangeChanged();
599 }
600 emit sampleCountChanged();
601
602 _parsed = true;
603 emit parsedChanged();
604 qCDebug(APMDataFlashLogParserLog) << "Parsed fields" << _availableFields.count() << "parameters" << _parameters.count() << "events" << _events.count();
605 return true;
606}
607
608void APMDataFlashLogParser::parseFileAsync(const QString &filePath)
609{
610 const quint64 requestId = ++_parseRequestId;
611 clear();
612
613 auto *watcher = new QFutureWatcher<ParseResult>(this);
614 (void) connect(watcher, &QFutureWatcher<ParseResult>::finished, this, [this, watcher, filePath, requestId]() {
615 const ParseResult result = watcher->result();
616 watcher->deleteLater();
617
618 if (requestId != _parseRequestId) {
619 // A newer parse request has superseded this result.
620 return;
621 }
622
623 if (!result.ok) {
624 _setParseError(result.errorMessage);
625 emit parseFileFinished(filePath, false, result.errorMessage);
626 return;
627 }
628
629 _availableFields = result.availableFields;
630 _plottableFields = result.plottableFields;
631 _parameters = result.parameters;
632 _events = result.events;
633 _messages = result.messages;
634 _modeSegments = result.modeSegments;
635 _fieldSamples = result.fieldSamples;
636 _sampleCount = result.sampleCount;
637 _detectedVehicleType = result.detectedVehicleType;
640 emit parametersChanged();
641 emit eventsChanged();
642 emit messagesChanged();
643 emit modeSegmentsChanged();
645 if (_minTimestamp != result.minTimestamp || _maxTimestamp != result.maxTimestamp) {
646 _minTimestamp = result.minTimestamp;
647 _maxTimestamp = result.maxTimestamp;
648 emit timeRangeChanged();
649 }
650 emit sampleCountChanged();
651
652 _parsed = true;
653 emit parsedChanged();
654 emit parseFileFinished(filePath, true, QString());
655 });
656
657 watcher->setFuture(QtConcurrent::run([filePath]() {
658 return _parseDataFlashFile(filePath);
659 }));
660}
661
662void APMDataFlashLogParser::clear()
663{
664 const bool oldParsed = _parsed;
665 _parsed = false;
666 if (oldParsed) {
667 emit parsedChanged();
668 }
669
670 if (!_parseError.isEmpty()) {
671 _parseError.clear();
672 emit parseErrorChanged();
673 }
674
675 if (!_availableFields.isEmpty()) {
676 _availableFields.clear();
678 }
679
680 if (!_parameters.isEmpty()) {
681 _parameters.clear();
682 emit parametersChanged();
683 }
684
685 if (!_events.isEmpty()) {
686 _events.clear();
687 emit eventsChanged();
688 }
689
690 if (!_messages.isEmpty()) {
691 _messages.clear();
692 emit messagesChanged();
693 }
694
695 if (!_modeSegments.isEmpty()) {
696 _modeSegments.clear();
697 emit modeSegmentsChanged();
698 }
699
700 if (!_detectedVehicleType.isEmpty()) {
701 _detectedVehicleType.clear();
703 }
704
705 if (!_plottableFields.isEmpty()) {
706 _plottableFields.clear();
708 }
709
710 _fieldSamples.clear();
711 if (_minTimestamp != -1.0 || _maxTimestamp != -1.0) {
712 _minTimestamp = -1.0;
713 _maxTimestamp = -1.0;
714 emit timeRangeChanged();
715 }
716
717 if (_sampleCount != 0) {
718 _sampleCount = 0;
719 emit sampleCountChanged();
720 }
721}
722
723QVariantList APMDataFlashLogParser::fieldSamples(const QString &fieldName) const
724{
725 QVariantList output;
726 const auto fieldIt = _fieldSamples.constFind(fieldName);
727 if (fieldIt == _fieldSamples.cend()) {
728 return output;
729 }
730
731 const QVector<QPointF> &points = fieldIt.value();
732 output.reserve(points.size());
733 for (const QPointF &point : points) {
734 output.append(point);
735 }
736
737 return output;
738}
739
740double APMDataFlashLogParser::fieldValueAt(const QString &fieldName, double timestampSeconds) const
741{
742 const auto fieldIt = _fieldSamples.constFind(fieldName);
743 if ((fieldIt == _fieldSamples.cend()) || fieldIt->isEmpty()) {
744 return std::numeric_limits<double>::quiet_NaN();
745 }
746
747 const QVector<QPointF> &points = fieldIt.value();
748 const auto lower = std::lower_bound(points.cbegin(), points.cend(), timestampSeconds,
749 [](const QPointF &point, double timestamp) {
750 return point.x() < timestamp;
751 });
752
753 if (lower == points.cbegin()) {
754 return lower->y();
755 }
756
757 if (lower == points.cend()) {
758 return points.constLast().y();
759 }
760
761 const auto previous = std::prev(lower);
762 const double lowerDistance = std::fabs(lower->x() - timestampSeconds);
763 const double previousDistance = std::fabs(previous->x() - timestampSeconds);
764
765 return (previousDistance <= lowerDistance)
766 ? previous->y()
767 : lower->y();
768}
769
770QString APMDataFlashLogParser::modeAt(double timestampSeconds) const
771{
772 for (const QVariant &variant : _modeSegments) {
773 const QVariantMap segment = variant.toMap();
774 const double start = segment.value(QStringLiteral("start")).toDouble();
775 const double end = segment.value(QStringLiteral("end")).toDouble();
776 if (timestampSeconds >= start && timestampSeconds <= end) {
777 return segment.value(QStringLiteral("mode")).toString();
778 }
779 }
780
781 return QString();
782}
783
784QVariantList APMDataFlashLogParser::eventsNear(double timestampSeconds, double thresholdSeconds) const
785{
786 QVariantList matches;
787 const double threshold = std::max(0.0, thresholdSeconds);
788
789 const auto lower = std::lower_bound(_events.cbegin(), _events.cend(), timestampSeconds - threshold,
790 [](const QVariant &v, double t) {
791 return v.toMap().value(QStringLiteral("time")).toDouble() < t;
792 });
793 for (auto it = lower; it != _events.cend(); ++it) {
794 const QVariantMap eventItem = it->toMap();
795 const double eventTime = eventItem.value(QStringLiteral("time")).toDouble();
796 if (eventTime > timestampSeconds + threshold) {
797 break;
798 }
799 matches.append(eventItem);
800 }
801
802 return matches;
803}
804
805void APMDataFlashLogParser::_setParseError(const QString &error)
806{
807 if (_parseError != error) {
808 _parseError = error;
809 emit parseErrorChanged();
810 }
811 qCWarning(APMDataFlashLogParserLog) << error;
812}
Error error
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void detectedVehicleTypeChanged()
void parseFileFinished(const QString &filePath, bool ok, const QString &errorMessage)
int iterateMessages(const char *data, qint64 size, const QMap< uint8_t, MessageFormat > &formats, const MessageCallback &callback)
bool parseFmtMessages(const char *data, qint64 size, QMap< uint8_t, MessageFormat > &formats)
QString errorMessage(const QNetworkReply *reply)