Newer
Older
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
/****************************************************************************
*
* (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "CompInfoParam.h"
#include "JsonHelper.h"
#include "FactMetaData.h"
#include "FirmwarePlugin.h"
#include "FirmwarePluginManager.h"
#include "QGCApplication.h"
#include <QStandardPaths>
#include <QJsonDocument>
#include <QJsonArray>
QGC_LOGGING_CATEGORY(CompInfoParamLog, "CompInfoParamLog")
const char* CompInfoParam::_jsonScopeKey = "scope";
const char* CompInfoParam::_jsonParametersKey = "parameters";
const char* CompInfoParam::_cachedMetaDataFilePrefix = "ParameterFactMetaData";
CompInfoParam::CompInfoParam(uint8_t compId, Vehicle* vehicle, QObject* parent)
: CompInfo(COMP_METADATA_TYPE_PARAMETER, compId, vehicle, parent)
{
}
void CompInfoParam::setJson(const QString& metadataJsonFileName, const QString& /*translationJsonFileName*/)
{
if (metadataJsonFileName.isEmpty()) {
// This will fall back to using the old FirmwarePlugin mechanism for parameter meta data.
// In this case paramter metadata is loaded through the _parameterMajorVersionKnown call which happens after parameter are downloaded
return;
}
QString errorString;
QJsonDocument jsonDoc;
_noJsonMetadata = false;
if (!JsonHelper::isJsonFile(metadataJsonFileName, jsonDoc, errorString)) {
qCWarning(CompInfoParamLog) << "Metadata json file open failed: compid:" << compId << errorString;
return;
}
QJsonObject jsonObj = jsonDoc.object();
QList<JsonHelper::KeyValidateInfo> keyInfoList = {
{ JsonHelper::jsonVersionKey, QJsonValue::Double, true },
{ _jsonScopeKey, QJsonValue::String, true },
{ _jsonParametersKey, QJsonValue::Array, true },
};
if (!JsonHelper::validateKeys(jsonObj, keyInfoList, errorString)) {
qCWarning(CompInfoParamLog) << "Metadata json validation failed: compid:" << compId << errorString;
return;
}
int version = jsonObj[JsonHelper::jsonVersionKey].toInt();
if (version != 1) {
qCWarning(CompInfoParamLog) << "Metadata json unsupported version" << version;
return;
}
QJsonArray rgParameters = jsonObj[_jsonParametersKey].toArray();
for (const QJsonValue& parameterValue: rgParameters) {
QMap<QString, QString> emptyDefineMap;
if (!parameterValue.isObject()) {
qCWarning(CompInfoParamLog) << "Metadata json read failed: compid:" << compId << "parameters array contains non-object";
return;
}
FactMetaData* newMetaData = FactMetaData::createFromJsonObject(parameterValue.toObject(), emptyDefineMap, this);
_nameToMetaDataMap[newMetaData->name()] = newMetaData;
}
}
FactMetaData* CompInfoParam::factMetaDataForName(const QString& name, FactMetaData::ValueType_t type)
{
if (_opaqueParameterMetaData) {
return vehicle->firmwarePlugin()->_getMetaDataForFact(_opaqueParameterMetaData, name, type, vehicle->vehicleType());
} else {
if (!_nameToMetaDataMap.contains(name)) {
_nameToMetaDataMap[name] = new FactMetaData(type, this);
}
return _nameToMetaDataMap[name];
}
}
bool CompInfoParam::_isParameterVolatile(const QString& name)
{
if (_opaqueParameterMetaData) {
return vehicle->firmwarePlugin()->_isParameterVolatile(_opaqueParameterMetaData, name, vehicle->vehicleType());
} else {
return _nameToMetaDataMap.contains(name) ? _nameToMetaDataMap[name]->volatileValue() : false;
}
}
FirmwarePlugin* CompInfoParam::_anyVehicleTypeFirmwarePlugin(MAV_AUTOPILOT firmwareType)
{
FirmwarePluginManager* pluginMgr = qgcApp()->toolbox()->firmwarePluginManager();
MAV_TYPE anySupportedVehicleType = pluginMgr->supportedVehicleTypes(firmwareType)[0];
return pluginMgr->firmwarePluginForAutopilot(firmwareType, anySupportedVehicleType);
}
QString CompInfoParam::_parameterMetaDataFile(Vehicle* vehicle, MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion)
{
bool cacheHit = false;
FirmwarePlugin* plugin = _anyVehicleTypeFirmwarePlugin(firmwareType);
if (firmwareType != MAV_AUTOPILOT_PX4) {
return plugin->_internalParameterMetaDataFile(vehicle);
} else {
// Only PX4 support the old style cached metadata
QSettings settings;
QDir cacheDir = QFileInfo(settings.fileName()).dir();
// First look for a direct cache hit
int cacheMinorVersion, cacheMajorVersion;
QFile cacheFile(cacheDir.filePath(QString("%1.%2.%3.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType).arg(wantedMajorVersion)));
if (cacheFile.exists()) {
plugin->_getParameterMetaDataVersionInfo(cacheFile.fileName(), cacheMajorVersion, cacheMinorVersion);
if (wantedMajorVersion != cacheMajorVersion) {
qWarning() << "Parameter meta data cache corruption:" << cacheFile.fileName() << "major version does not match file name" << "actual:excepted" << cacheMajorVersion << wantedMajorVersion;
} else {
qCDebug(CompInfoParamLog) << "Direct cache hit on file:major:minor" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion;
cacheHit = true;
}
}
if (!cacheHit) {
// No direct hit, look for lower param set version
QString wildcard = QString("%1.%2.*.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType);
QStringList cacheHits = cacheDir.entryList(QStringList(wildcard), QDir::Files, QDir::Name);
// Find the highest major version number which is below the vehicles major version number
int cacheHitIndex = -1;
cacheMajorVersion = -1;
QRegExp regExp(QString("%1\\.%2\\.(\\d*)\\.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType));
for (int i=0; i< cacheHits.count(); i++) {
if (regExp.exactMatch(cacheHits[i]) && regExp.captureCount() == 1) {
int majorVersion = regExp.capturedTexts()[0].toInt();
if (majorVersion > cacheMajorVersion && majorVersion < wantedMajorVersion) {
cacheMajorVersion = majorVersion;
cacheHitIndex = i;
}
}
}
if (cacheHitIndex != -1) {
// We have a cache hit on a lower major version, read minor version as well
int majorVersion;
cacheFile.setFileName(cacheDir.filePath(cacheHits[cacheHitIndex]));
plugin->_getParameterMetaDataVersionInfo(cacheFile.fileName(), majorVersion, cacheMinorVersion);
if (majorVersion != cacheMajorVersion) {
qWarning() << "Parameter meta data cache corruption:" << cacheFile.fileName() << "major version does not match file name" << "actual:excepted" << majorVersion << cacheMajorVersion;
cacheHit = false;
} else {
qCDebug(CompInfoParamLog) << "Indirect cache hit on file:major:minor:want" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion << wantedMajorVersion;
cacheHit = true;
}
}
}
int internalMinorVersion, internalMajorVersion;
QString internalMetaDataFile = plugin->_internalParameterMetaDataFile(vehicle);
plugin->_getParameterMetaDataVersionInfo(internalMetaDataFile, internalMajorVersion, internalMinorVersion);
qCDebug(CompInfoParamLog) << "Internal metadata file:major:minor" << internalMetaDataFile << internalMajorVersion << internalMinorVersion;
if (cacheHit) {
// Cache hit is available, we need to check if internal meta data is a better match, if so use internal version
if (internalMajorVersion == wantedMajorVersion) {
if (cacheMajorVersion == wantedMajorVersion) {
// Both internal and cache are direct hit on major version, Use higher minor version number
cacheHit = cacheMinorVersion > internalMinorVersion;
} else {
// Direct internal hit, but not direct hit in cache, use internal
cacheHit = false;
}
} else {
if (cacheMajorVersion == wantedMajorVersion) {
// Direct hit on cache, no direct hit on internal, use cache
cacheHit = true;
} else {
// No direct hit anywhere, use internal
cacheHit = false;
}
}
}
QString metaDataFile;
if (cacheHit && !qgcApp()->runningUnitTests()) {
majorVersion = cacheMajorVersion;
minorVersion = cacheMinorVersion;
metaDataFile = cacheFile.fileName();
} else {
majorVersion = internalMajorVersion;
minorVersion = internalMinorVersion;
metaDataFile = internalMetaDataFile;
}
qCDebug(CompInfoParamLog) << "_parameterMetaDataFile returning file:major:minor" << metaDataFile << majorVersion << minorVersion;
return metaDataFile;
}
}
void CompInfoParam::_cachePX4MetaDataFile(const QString& metaDataFile)
{
FirmwarePlugin* plugin = _anyVehicleTypeFirmwarePlugin(MAV_AUTOPILOT_PX4);
int newMajorVersion, newMinorVersion;
plugin->_getParameterMetaDataVersionInfo(metaDataFile, newMajorVersion, newMinorVersion);
qCDebug(CompInfoParamLog) << "ParameterManager::cacheMetaDataFile file:major;minor" << metaDataFile << newMajorVersion << newMinorVersion;
// Find the cache hit closest to this new file
int cacheMajorVersion, cacheMinorVersion;
QString cacheHit = _parameterMetaDataFile(nullptr, MAV_AUTOPILOT_PX4, newMajorVersion, cacheMajorVersion, cacheMinorVersion);
qCDebug(CompInfoParamLog) << "ParameterManager::cacheMetaDataFile cacheHit file:firmware:major;minor" << cacheHit << cacheMajorVersion << cacheMinorVersion;
bool cacheNewFile = false;
if (cacheHit.isEmpty()) {
// No cache hits, store the new file
cacheNewFile = true;
} else if (cacheMajorVersion == newMajorVersion) {
// Direct hit on major version in cache:
// Cache new file if newer/equal minor version. We cache if equal to allow flashing test builds with new parameter metadata.
// Also delete older cache file.
if (newMinorVersion >= cacheMinorVersion) {
cacheNewFile = true;
QFile::remove(cacheHit);
}
} else {
// Indirect hit in cache, store new file
cacheNewFile = true;
}
if (cacheNewFile) {
// Cached files are stored in settings location. Copy from current file to cache naming.
QSettings settings;
QDir cacheDir = QFileInfo(settings.fileName()).dir();
QFile cacheFile(cacheDir.filePath(QString("%1.%2.%3.xml").arg(_cachedMetaDataFilePrefix).arg(MAV_AUTOPILOT_PX4).arg(newMajorVersion)));
qCDebug(CompInfoParamLog) << "ParameterManager::cacheMetaDataFile caching file:" << cacheFile.fileName();
QFile newFile(metaDataFile);
newFile.copy(cacheFile.fileName());
}
}
void CompInfoParam::_parameterMajorVersionKnown(int wantedMajorVersion)
{
if (_noJsonMetadata) {
if (_opaqueParameterMetaData) {
return;
}
QString metaDataFile;
int majorVersion, minorVersion;
// Load best parameter meta data set
metaDataFile = _parameterMetaDataFile(vehicle, vehicle->firmwareType(), wantedMajorVersion, majorVersion, minorVersion);
qCDebug(CompInfoParamLog) << "Loading meta data the old way file:major:minor" << metaDataFile << majorVersion << minorVersion;
_opaqueParameterMetaData = vehicle->firmwarePlugin()->_loadParameterMetaData(metaDataFile);
}
}
void CompInfoParam::_clearPX4ParameterMetaData (void)
{
if (_opaqueParameterMetaData) {
qCDebug(CompInfoParamLog) << "_clearPX4ParameterMetaData";
_opaqueParameterMetaData->deleteLater();
_opaqueParameterMetaData = nullptr;
}
}