6#include <QtConcurrent/QtConcurrent>
8#include <QtCore/QFutureWatcher>
22 QStringList availableFields;
23 QStringList plottableFields;
24 QVariantList parameters;
26 QVariantList messages;
27 QVariantList modeSegments;
28 QHash<QString, QVector<QPointF>> fieldSamples;
29 double minTimestamp = -1.0;
30 double maxTimestamp = -1.0;
32 QString detectedVehicleType;
35QString _vehicleTypeFromMessageText(
const QString &messageText)
37 const QString text = messageText.toLower();
38 if (text.contains(QStringLiteral(
"arducopter"))) {
39 return QStringLiteral(
"ArduCopter");
41 if (text.contains(QStringLiteral(
"arduplane"))) {
42 return QStringLiteral(
"ArduPlane");
44 if (text.contains(QStringLiteral(
"ardurover"))) {
45 return QStringLiteral(
"ArduRover");
47 if (text.contains(QStringLiteral(
"ardusub"))) {
48 return QStringLiteral(
"ArduSub");
54QString _ardupilotModeName(
const QString &vehicleType,
int modeNumber)
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")},
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")},
112 if (vehicleType == QStringLiteral(
"ArduPlane")) {
113 return planeModes.value(modeNumber, QStringLiteral(
"Mode %1").arg(modeNumber));
115 if (vehicleType == QStringLiteral(
"ArduCopter")) {
116 return copterModes.value(modeNumber, QStringLiteral(
"Mode %1").arg(modeNumber));
121 return QStringLiteral(
"Mode %1").arg(modeNumber);
124QString _ardupilotErrDescription(
int subsystem,
int ecode)
126 QString subsystemName;
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;
165 if (ecode == 1) { ecodeText = APMDataFlashLogParser::tr(
"INS delay"); }
168 if (ecode == 0) { ecodeText = APMDataFlashLogParser::tr(
"Errors Resolved"); }
169 else if (ecode == 2) { ecodeText = APMDataFlashLogParser::tr(
"Late Frame"); }
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"); }
187 if (ecode == 0) { ecodeText = APMDataFlashLogParser::tr(
"Failsafe Resolved"); }
188 else if (ecode == 1) { ecodeText = APMDataFlashLogParser::tr(
"Failsafe Triggered"); }
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"); }
198 if (ecode == 0) { ecodeText = APMDataFlashLogParser::tr(
"Flight mode change failure"); }
201 if (ecode == 0) { ecodeText = APMDataFlashLogParser::tr(
"Glitch cleared"); }
202 else if (ecode == 2) { ecodeText = APMDataFlashLogParser::tr(
"GPS glitch occurred"); }
205 if (ecode == 1) { ecodeText = APMDataFlashLogParser::tr(
"Crash into ground detected"); }
206 else if (ecode == 2) { ecodeText = APMDataFlashLogParser::tr(
"Loss of control detected"); }
209 if (ecode == 2) { ecodeText = APMDataFlashLogParser::tr(
"Flip abandoned"); }
212 if (ecode == 2) { ecodeText = APMDataFlashLogParser::tr(
"Parachute not deployed (too low)"); }
213 else if (ecode == 3) { ecodeText = APMDataFlashLogParser::tr(
"Parachute not deployed (landed)"); }
216 if (ecode == 0) { ecodeText = APMDataFlashLogParser::tr(
"Variance cleared"); }
217 else if (ecode == 2) { ecodeText = APMDataFlashLogParser::tr(
"Bad variance"); }
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"); }
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"); }
234 if (ecode == 2) { ecodeText = APMDataFlashLogParser::tr(
"Missing terrain data"); }
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"); }
244 if (ecode == 0) { ecodeText = APMDataFlashLogParser::tr(
"1st EKF became primary"); }
245 else if (ecode == 1) { ecodeText = APMDataFlashLogParser::tr(
"2nd EKF became primary"); }
248 if (ecode == 0) { ecodeText = APMDataFlashLogParser::tr(
"Thrust restored"); }
249 else if (ecode == 1) { ecodeText = APMDataFlashLogParser::tr(
"Thrust loss detected"); }
252 if (ecode == 0) { ecodeText = APMDataFlashLogParser::tr(
"Excessive vibration compensation de-activated"); }
253 else if (ecode == 1) { ecodeText = APMDataFlashLogParser::tr(
"Excessive vibration compensation activated"); }
256 if (ecode == 1) { ecodeText = APMDataFlashLogParser::tr(
"Internal errors detected"); }
262 if (ecodeText.isEmpty()) {
263 ecodeText = APMDataFlashLogParser::tr(
"Code %1").arg(ecode);
266 return QStringLiteral(
"%1 (%2): %3 (%4)").arg(subsystemName).arg(subsystem).arg(ecodeText).arg(ecode);
269QString _ardupilotEventDescription(
int 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);
346double _extractTimestampSeconds(
const QMap<QString, QVariant> &values)
348 if (values.contains(QStringLiteral(
"TimeUS"))) {
349 return values.value(QStringLiteral(
"TimeUS")).toDouble() / 1000000.0;
351 if (values.contains(QStringLiteral(
"TimeMS"))) {
352 return values.value(QStringLiteral(
"TimeMS")).toDouble() / 1000.0;
354 if (values.contains(QStringLiteral(
"Time"))) {
355 return values.value(QStringLiteral(
"Time")).toDouble() / 1000.0;
361void _appendEvent(QVariantList &
events,
double timestampSecs,
const QString &type,
const QString &description)
363 if ((timestampSecs < 0.0) || description.isEmpty()) {
367 QVariantMap eventRow;
368 eventRow[QStringLiteral(
"time")] = timestampSecs;
369 eventRow[QStringLiteral(
"type")] = type;
370 eventRow[QStringLiteral(
"description")] = description;
374ParseResult _parseDataFlashFile(
const QString &filePath)
378 QFile file(filePath);
379 if (!file.open(QIODevice::ReadOnly)) {
380 result.errorMessage = APMDataFlashLogParser::tr(
"Failed to open DataFlash file");
384 const qint64 fileSize = file.size();
386 result.errorMessage = APMDataFlashLogParser::tr(
"DataFlash file is empty");
389 if (fileSize > std::numeric_limits<qsizetype>::max()) {
390 result.errorMessage = APMDataFlashLogParser::tr(
"DataFlash file is too large to parse");
394 uchar *
const mappedData = file.map(0, fileSize);
395 if (mappedData ==
nullptr) {
396 result.errorMessage = APMDataFlashLogParser::tr(
"Failed to memory-map DataFlash file");
400 struct ScopedFileUnmap {
402 uchar *data =
nullptr;
405 if (data !=
nullptr) {
409 } scopedFileUnmap{file, mappedData};
411 const QByteArray bytes = QByteArray::fromRawData(
reinterpret_cast<const char *
>(mappedData),
static_cast<qsizetype
>(fileSize));
413 QMap<uint8_t, APMDataFlashUtility::MessageFormat> formats;
415 result.errorMessage = APMDataFlashLogParser::tr(
"No valid FMT messages were found");
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;
430 QHash<uint8_t, QHash<QString, QString>> signalNameByCol;
431 signalNameByCol.reserve(formats.size());
432 for (
auto fmtIt = formats.cbegin(); fmtIt != formats.cend(); ++fmtIt) {
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);
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");
447 APMDataFlashUtility::iterateMessages(bytes.constData(), bytes.size(), formats, [&result, &signalSet, &plottableSet, &minTimestampSecs, &maxTimestampSecs, &hasOpenModeSegment, &modeSegmentStartSecs, ¤tModeName, &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;
454 maxTimestampSecs = std::max(maxTimestampSecs, timestampSecs);
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()) {
462 row[QStringLiteral(
"name")] = paramName;
463 row[QStringLiteral(
"value")] = paramValue;
464 result.parameters.append(row);
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;
472 if (!text.isEmpty()) {
474 row[QStringLiteral(
"time")] = timestampSecs;
475 row[QStringLiteral(
"text")] = text;
476 result.messages.append(row);
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);
483 modeName = _ardupilotModeName(result.detectedVehicleType, modeNumber);
484 }
else if (modeName.isEmpty()) {
485 modeName = APMDataFlashLogParser::tr(
"Unknown");
487 _appendEvent(result.events, timestampSecs, QStringLiteral(
"mode"), APMDataFlashLogParser::tr(
"Mode: %1").arg(modeName));
488 if (timestampSecs >= 0.0) {
489 if (hasOpenModeSegment && (timestampSecs > modeSegmentStartSecs)) {
491 segment[QStringLiteral(
"mode")] = currentModeName;
492 segment[QStringLiteral(
"start")] = modeSegmentStartSecs;
493 segment[QStringLiteral(
"end")] = timestampSecs;
494 result.modeSegments.append(segment);
496 hasOpenModeSegment =
true;
497 modeSegmentStartSecs = timestampSecs;
498 currentModeName = modeName;
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));
509 result.sampleCount++;
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()) {
520 const QString &signalName = nameIt.value();
521 signalSet.insert(signalName);
523 if (!haveTimestamp) {
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);
531 result.fieldSamples[signalName].append(QPointF(timestampSecs, it.value().toDouble()));
532 plottableSet.insert(signalName);
539 if (hasOpenModeSegment && (maxTimestampSecs >= modeSegmentStartSecs)) {
541 segment[QStringLiteral(
"mode")] = currentModeName;
542 segment[QStringLiteral(
"start")] = modeSegmentStartSecs;
543 segment[QStringLiteral(
"end")] = maxTimestampSecs;
544 result.modeSegments.append(segment);
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;
558APMDataFlashLogParser::APMDataFlashLogParser(QObject *parent)
561 qCDebug(APMDataFlashLogParserLog) <<
this;
564APMDataFlashLogParser::~APMDataFlashLogParser()
566 qCDebug(APMDataFlashLogParserLog) <<
this;
569bool APMDataFlashLogParser::parseFile(
const QString &filePath)
573 const ParseResult result = _parseDataFlashFile(filePath);
575 _setParseError(result.errorMessage);
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;
595 if (_minTimestamp != result.minTimestamp || _maxTimestamp != result.maxTimestamp) {
596 _minTimestamp = result.minTimestamp;
597 _maxTimestamp = result.maxTimestamp;
604 qCDebug(APMDataFlashLogParserLog) <<
"Parsed fields" << _availableFields.count() <<
"parameters" << _parameters.count() <<
"events" << _events.count();
608void APMDataFlashLogParser::parseFileAsync(
const QString &filePath)
610 const quint64 requestId = ++_parseRequestId;
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();
618 if (requestId != _parseRequestId) {
624 _setParseError(result.errorMessage);
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;
645 if (_minTimestamp != result.minTimestamp || _maxTimestamp != result.maxTimestamp) {
646 _minTimestamp = result.minTimestamp;
647 _maxTimestamp = result.maxTimestamp;
657 watcher->setFuture(QtConcurrent::run([filePath]() {
658 return _parseDataFlashFile(filePath);
662void APMDataFlashLogParser::clear()
664 const bool oldParsed = _parsed;
670 if (!_parseError.isEmpty()) {
675 if (!_availableFields.isEmpty()) {
676 _availableFields.clear();
680 if (!_parameters.isEmpty()) {
685 if (!_events.isEmpty()) {
690 if (!_messages.isEmpty()) {
695 if (!_modeSegments.isEmpty()) {
696 _modeSegments.clear();
700 if (!_detectedVehicleType.isEmpty()) {
701 _detectedVehicleType.clear();
705 if (!_plottableFields.isEmpty()) {
706 _plottableFields.clear();
710 _fieldSamples.clear();
711 if (_minTimestamp != -1.0 || _maxTimestamp != -1.0) {
712 _minTimestamp = -1.0;
713 _maxTimestamp = -1.0;
717 if (_sampleCount != 0) {
723QVariantList APMDataFlashLogParser::fieldSamples(
const QString &fieldName)
const
726 const auto fieldIt = _fieldSamples.constFind(fieldName);
727 if (fieldIt == _fieldSamples.cend()) {
731 const QVector<QPointF> &points = fieldIt.value();
732 output.reserve(points.size());
733 for (
const QPointF &point : points) {
734 output.append(point);
740double APMDataFlashLogParser::fieldValueAt(
const QString &fieldName,
double timestampSeconds)
const
742 const auto fieldIt = _fieldSamples.constFind(fieldName);
743 if ((fieldIt == _fieldSamples.cend()) || fieldIt->isEmpty()) {
744 return std::numeric_limits<double>::quiet_NaN();
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;
753 if (lower == points.cbegin()) {
757 if (lower == points.cend()) {
758 return points.constLast().y();
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);
765 return (previousDistance <= lowerDistance)
770QString APMDataFlashLogParser::modeAt(
double timestampSeconds)
const
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();
784QVariantList APMDataFlashLogParser::eventsNear(
double timestampSeconds,
double thresholdSeconds)
const
786 QVariantList matches;
787 const double threshold = std::max(0.0, thresholdSeconds);
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;
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) {
799 matches.append(eventItem);
805void APMDataFlashLogParser::_setParseError(
const QString &
error)
807 if (_parseError !=
error) {
811 qCWarning(APMDataFlashLogParserLog) <<
error;
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void detectedVehicleTypeChanged()
void modeSegmentsChanged()
void plottableFieldsChanged()
void parseFileFinished(const QString &filePath, bool ok, const QString &errorMessage)
void sampleCountChanged()
void availableFieldsChanged()
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)