QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
LogViewerParamMetaData.cc
Go to the documentation of this file.
2
3#ifndef QGC_NO_ARDUPILOT_DIALECT
5#endif
6#include "FactMetaData.h"
9
10#include <QtCore/QFileInfo>
11
12QGC_LOGGING_CATEGORY(LogViewerParamMetaDataLog, "AnalyzeView.LogViewerParamMetaData")
13
14namespace {
15
16#ifndef QGC_NO_ARDUPILOT_DIALECT
17
18// Map the APM vehicle name as stored in detectedVehicleType to the file-path
19// component used in :/FirmwarePlugin/APM/APMParameterFactMetaData.{X}.major.minor.json
20QString _apmFileVehicleName(const QString &vehicleType)
21{
22 if (vehicleType == QStringLiteral("ArduCopter")) { return QStringLiteral("Copter"); }
23 if (vehicleType == QStringLiteral("ArduPlane")) { return QStringLiteral("Plane"); }
24 if (vehicleType == QStringLiteral("ArduRover")) { return QStringLiteral("Rover"); }
25 if (vehicleType == QStringLiteral("ArduSub")) { return QStringLiteral("Sub"); }
26 return QString();
27}
28
29// Walk down from (major, minor) to find the best available bundled JSON file,
30// mirroring APMFirmwarePlugin::_internalParameterMetaDataFile logic.
31QString _findAPMMetaDataFile(const QString &fileVehicleName, int major, int minor)
32{
33 int currMajor = major;
34 int currMinor = minor;
35
36 while (currMajor >= 4 && currMinor > 0) {
37 const QString file = QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.%1.%2.%3.json")
38 .arg(fileVehicleName).arg(currMajor).arg(currMinor);
39 if (QFileInfo::exists(file)) {
40 return file;
41 }
42 currMinor--;
43 if (currMinor == 0) {
44 currMinor = 10;
45 currMajor--;
46 }
47 }
48
49 // Fallback: oldest available in the 4.x series
50 for (int i = 0; i < 10; i++) {
51 const QString file = QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.%1.4.%2.json")
52 .arg(fileVehicleName).arg(i);
53 if (QFileInfo::exists(file)) {
54 return file;
55 }
56 }
57
58 return QString();
59}
60
61#endif // QGC_NO_ARDUPILOT_DIALECT
62
63void _enrichRows(QVariantList &parameters, ParameterMetaData *metaData)
64{
65 for (int i = 0; i < parameters.size(); i++) {
66 QVariantMap row = parameters[i].toMap();
67
68 const QString name = row.value(QStringLiteral("name")).toString();
69 const bool isFloat = row.value(QStringLiteral("isFloat"), false).toBool();
70 const FactMetaData::ValueType_t type = isFloat
73
74 FactMetaData *factMeta = metaData->getMetaDataForFact(name, type);
75 if (!factMeta) {
76 parameters[i] = row;
77 continue;
78 }
79
80 row[QStringLiteral("decimalPlaces")] = factMeta->decimalPlaces();
81 row[QStringLiteral("units")] = factMeta->rawUnits();
82 row[QStringLiteral("shortDescription")] = factMeta->shortDescription();
83 row[QStringLiteral("enumStrings")] = QVariant::fromValue(factMeta->enumStrings());
84 row[QStringLiteral("enumValues")] = QVariant::fromValue(factMeta->enumValues());
85
86 parameters[i] = row;
87 }
88}
89
90} // namespace
91
92void LogViewerParamMetaData::enrichForPX4(QVariantList &parameters)
93{
94 if (parameters.isEmpty()) {
95 return;
96 }
97
98 auto *metaData = new PX4ParameterMetaData(nullptr);
100 QStringLiteral(":/FirmwarePlugin/PX4/PX4ParameterFactMetaData.json"));
101
102 _enrichRows(parameters, metaData);
103
104 delete metaData;
105}
106
107#ifndef QGC_NO_ARDUPILOT_DIALECT
108void LogViewerParamMetaData::enrichForAPM(QVariantList &parameters,
109 const QString &vehicleType,
110 int major,
111 int minor)
112{
113 if (parameters.isEmpty()) {
114 return;
115 }
116
117 const QString fileVehicleName = _apmFileVehicleName(vehicleType);
118 if (fileVehicleName.isEmpty()) {
119 qCDebug(LogViewerParamMetaDataLog) << "Unknown APM vehicle type:" << vehicleType;
120 return;
121 }
122
123 // If no version was detected in the log, start from a high version so the
124 // walk-down finds the newest available file.
125 const int startMajor = (major >= 4) ? major : 9;
126 const int startMinor = (minor >= 0) ? minor : 99;
127
128 const QString metaDataFile = _findAPMMetaDataFile(fileVehicleName, startMajor, startMinor);
129 if (metaDataFile.isEmpty()) {
130 qCDebug(LogViewerParamMetaDataLog) << "No APM metadata file found for" << vehicleType
131 << major << "." << minor;
132 return;
133 }
134
135 qCDebug(LogViewerParamMetaDataLog) << "Loading APM metadata:" << metaDataFile;
136
137 auto *metaData = new APMParameterMetaData(nullptr);
138 metaData->loadParameterFactMetaDataFile(metaDataFile);
139
140 _enrichRows(parameters, metaData);
141
142 delete metaData;
143}
144
145#endif // QGC_NO_ARDUPILOT_DIALECT
#define QGC_LOGGING_CATEGORY(name, categoryStr)
Holds the meta data associated with a Fact.
QStringList enumStrings() const
QVariantList enumValues() const
QString shortDescription() const
int decimalPlaces() const
QString rawUnits() const
static void enrichForAPM(QVariantList &parameters, const QString &vehicleType, int major, int minor)
static void enrichForPX4(QVariantList &parameters)
FactMetaData * getMetaDataForFact(const QString &name, FactMetaData::ValueType_t type)
void loadParameterFactMetaDataFile(const QString &metaDataFile)