QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
APMParameterMetaData.cc
Go to the documentation of this file.
3
4#include <QtCore/QFile>
5#include <QtCore/QRegularExpression>
6#include <QtCore/QRegularExpressionMatch>
7#include <QtCore/QStack>
8
9QGC_LOGGING_CATEGORY(APMParameterMetaDataLog, "FirmwarePlugin.APMParameterMetaData")
10QGC_LOGGING_CATEGORY(APMParameterMetaDataVerboseLog, "FirmwarePlugin.APMParameterMetaData:verbose")
11
13 : QObject(parent)
14{
15 qCDebug(APMParameterMetaDataLog) << this;
16}
17
19{
20 qCDebug(APMParameterMetaDataLog) << this;
21}
22
23QString APMParameterMetaData::_mavTypeToString(MAV_TYPE vehicleTypeEnum)
24{
25 QString vehicleName;
26
27 switch(vehicleTypeEnum) {
28 case MAV_TYPE_FIXED_WING:
29 case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
30 case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
31 case MAV_TYPE_VTOL_TILTROTOR:
32 case MAV_TYPE_VTOL_FIXEDROTOR:
33 case MAV_TYPE_VTOL_TAILSITTER:
34 case MAV_TYPE_VTOL_TILTWING:
35 case MAV_TYPE_VTOL_RESERVED5:
36 vehicleName = "ArduPlane";
37 break;
38 case MAV_TYPE_QUADROTOR:
39 case MAV_TYPE_COAXIAL:
40 case MAV_TYPE_HELICOPTER:
41 case MAV_TYPE_HEXAROTOR:
42 case MAV_TYPE_OCTOROTOR:
43 case MAV_TYPE_TRICOPTER:
44 vehicleName = "ArduCopter";
45 break;
46 case MAV_TYPE_ANTENNA_TRACKER:
47 vehicleName = "Antenna Tracker";
48 break;
49 case MAV_TYPE_GENERIC:
50 case MAV_TYPE_GCS:
51 case MAV_TYPE_AIRSHIP:
52 case MAV_TYPE_FREE_BALLOON:
53 case MAV_TYPE_ROCKET:
54 break;
55 case MAV_TYPE_GROUND_ROVER:
56 case MAV_TYPE_SURFACE_BOAT:
57 vehicleName = "Rover";
58 break;
59 case MAV_TYPE_SUBMARINE:
60 vehicleName = "ArduSub";
61 break;
62 case MAV_TYPE_FLAPPING_WING:
63 case MAV_TYPE_KITE:
64 case MAV_TYPE_ONBOARD_CONTROLLER:
65 case MAV_TYPE_GIMBAL:
66 case MAV_TYPE_ENUM_END:
67 default:
68 break;
69 }
70 return vehicleName;
71}
72
73QString APMParameterMetaData::_groupFromParameterName(const QString &name)
74{
75 static const QRegularExpression regex = QRegularExpression("[0-9]*$");
76 QString group = name.split('_').first();
77 return group.remove(regex); // remove any numbers from the end
78}
79
81{
82 if (_parameterMetaDataLoaded) {
83 return;
84 }
85 _parameterMetaDataLoaded = true;
86
87 qCDebug(APMParameterMetaDataLog) << "Loading parameter meta data:" << metaDataFile;
88
89 QFile xmlFile(metaDataFile);
90 Q_ASSERT(xmlFile.exists());
91
92 const bool success = xmlFile.open(QIODevice::ReadOnly);
93 Q_UNUSED(success);
94 Q_ASSERT(success);
95
96 QXmlStreamReader xml(xmlFile.readAll());
97 xmlFile.close();
98 if (xml.hasError()) {
99 qCWarning(APMParameterMetaDataLog) << "Badly formed XML, reading failed:" << xml.errorString();
100 return;
101 }
102
103 bool badMetaData = true;
104 APMFactMetaDataRaw *rawMetaData = nullptr;
105 QString currentCategory;
106
107 QStack<int> xmlState;
108 xmlState.push(XmlState::None);
109
110 QMap<QString,QStringList> groupMembers; //used to remove groups with single item
111
112 while (!xml.atEnd()) {
113 if (xml.isStartElement()) {
114 const QString elementName = xml.name().toString();
115
116 if (elementName.isEmpty()) {
117 // skip empty elements
118 } else if (elementName == "paramfile") {
119 if (xmlState.top() != XmlState::None) {
120 qCWarning(APMParameterMetaDataLog) << "Badly formed XML, paramfile matched";
121 }
122 xmlState.push(XmlState::ParamFileFound);
123 // we don't really do anything with this element
124 } else if (elementName == "vehicles") {
125 if (xmlState.top() != XmlState::ParamFileFound) {
126 qCWarning(APMParameterMetaDataLog) << "Badly formed XML, vehicles matched";
127 return;
128 }
129 xmlState.push(XmlState::FoundVehicles);
130 } else if (elementName == "libraries") {
131 if (xmlState.top() != XmlState::ParamFileFound) {
132 qCWarning(APMParameterMetaDataLog) << "Badly formed XML, libraries matched";
133 return;
134 }
135 currentCategory = "libraries";
136 xmlState.push(XmlState::FoundLibraries);
137 } else if (elementName == "parameters") {
138 if (xmlState.top() != XmlState::FoundVehicles && xmlState.top() != XmlState::FoundLibraries) {
139 qCWarning(APMParameterMetaDataLog) << "Badly formed XML, parameters matched"
140 << "but we don't have proper vehicle or libraries yet";
141 return;
142 }
143
144 if (xml.attributes().hasAttribute("name")) {
145 // we will handle metadata only for specific MAV_TYPEs and libraries
146 const QString nameValue = xml.attributes().value("name").toString();
147 static const QRegularExpression parameterCategories = QRegularExpression("ArduCopter|ArduPlane|APMrover2|Rover|ArduSub|AntennaTracker");
148 if (nameValue.contains(parameterCategories)) {
149 xmlState.push(XmlState::FoundParameters);
150 currentCategory = nameValue;
151 } else if(xmlState.top() == XmlState::FoundLibraries) {
152 // we handle all libraries section under the same category libraries
153 // so not setting currentCategory
154 xmlState.push(XmlState::FoundParameters);
155 } else {
156 qCDebug(APMParameterMetaDataVerboseLog) << "not interested in this block of parameters, skipping:" << nameValue;
157 if (_skipXMLBlock(xml, "parameters")) {
158 qCWarning(APMParameterMetaDataLog) << "something wrong with the xml, skip of the xml failed";
159 return;
160 }
161 (void) xml.readNext();
162 continue;
163 }
164 }
165 } else if (elementName == "param") {
166 if (xmlState.top() != XmlState::FoundParameters) {
167 qCWarning(APMParameterMetaDataLog) << "Badly formed XML, element param matched"
168 << "while we are not yet in parameters";
169 return;
170 }
171 xmlState.push(XmlState::FoundParameter);
172
173 if (!xml.attributes().hasAttribute("name")) {
174 qCWarning(APMParameterMetaDataLog) << "Badly formed XML, parameter attribute name missing";
175 return;
176 }
177
178 QString name = xml.attributes().value("name").toString();
179 if (name.contains(':')) {
180 name = name.split(':').last();
181 }
182 const QString group = _groupFromParameterName(name);
183
184 const QString category = xml.attributes().value("user").toString();
185
186 const QString shortDescription = xml.attributes().value("humanName").toString();
187 const QString longDescription = xml.attributes().value("documentation").toString();
188
189 qCDebug(APMParameterMetaDataVerboseLog) << "Found parameter name:" << name
190 << "short Desc:" << shortDescription
191 << "longDescription:" << longDescription
192 << "category:" << category
193 << "group:" << group;
194
195 Q_ASSERT(!rawMetaData);
196 if (_vehicleTypeToParametersMap[currentCategory].contains(name)) {
197 qCDebug(APMParameterMetaDataLog) << "Duplicate parameter found:" << name;
198 rawMetaData = _vehicleTypeToParametersMap[currentCategory][name];
199 } else {
200 rawMetaData = new APMFactMetaDataRaw(this);
201 _vehicleTypeToParametersMap[currentCategory][name] = rawMetaData;
202 groupMembers[group] << name;
203 }
204 qCDebug(APMParameterMetaDataVerboseLog) << "inserting metadata for field" << name;
205 rawMetaData->name = name;
206 if (!category.isEmpty()) {
207 rawMetaData->category = category;
208 }
209 rawMetaData->group = group;
210 rawMetaData->shortDescription = shortDescription;
211 rawMetaData->longDescription = longDescription;
212 } else {
213 // We should be getting meta data now
214 if (xmlState.top() != XmlState::FoundParameter) {
215 qCWarning(APMParameterMetaDataLog) << "Badly formed XML, while reading parameter fields wrong state";
216 return;
217 }
218 if (!badMetaData) {
219 if (!_parseParameterAttributes(xml, rawMetaData)) {
220 qCDebug(APMParameterMetaDataLog) << "Badly formed XML, failed to read parameter attributes";
221 return;
222 }
223 continue;
224 }
225 }
226 } else if (xml.isEndElement()) {
227 const QString elementName = xml.name().toString();
228
229 if ((elementName == "param") && (xmlState.top() == XmlState::FoundParameter)) {
230 // Done loading this parameter
231 // Reset for next parameter
232 qCDebug(APMParameterMetaDataVerboseLog) << "done loading parameter";
233 rawMetaData = nullptr;
234 badMetaData = false;
235 xmlState.pop();
236 } else if (elementName == "parameters") {
237 qCDebug(APMParameterMetaDataVerboseLog) << "end of parameters for category: " << currentCategory;
238 _correctGroupMemberships(_vehicleTypeToParametersMap[currentCategory], groupMembers);
239 groupMembers.clear();
240 xmlState.pop();
241 } else if (elementName == "vehicles") {
242 qCDebug(APMParameterMetaDataVerboseLog) << "vehicles end here, libraries will follow";
243 xmlState.pop();
244 }
245 }
246 (void) xml.readNext();
247 }
248}
249
250void APMParameterMetaData::_correctGroupMemberships(ParameterNametoFactMetaDataMap &parameterToFactMetaDataMap, QMap<QString,QStringList> &groupMembers)
251{
252 for (const QString &groupName : groupMembers.keys()) {
253 if (groupMembers[groupName].count() == 1) {
254 for (const QString &parameter : groupMembers.value(groupName)) {
255 parameterToFactMetaDataMap[parameter]->group = FactMetaData::defaultGroup();
256 }
257 }
258 }
259}
260
261bool APMParameterMetaData::_skipXMLBlock(QXmlStreamReader &xml, const QString &blockName)
262{
263 QString elementName;
264 do {
265 (void) xml.readNext();
266 elementName = xml.name().toString();
267 } while ((elementName != blockName) && (xml.isEndElement()));
268 return !xml.isEndDocument();
269}
270
271bool APMParameterMetaData::_parseParameterAttributes(QXmlStreamReader &xml, APMFactMetaDataRaw *rawMetaData)
272{
273 QString elementName = xml.name().toString();
274 QList<QPair<QString,QString>> values;
275 bool bitmaskElementSeen = false; // parse legacy <field name="Bitmask"> only if no <bitmask> was found
276
277 // as long as param doesn't end
278 while (!((elementName == "param") && xml.isEndElement())) {
279 if (elementName.isEmpty()) {
280 // skip empty elements
281 } else if (elementName == "field") {
282 const QString attributeName = xml.attributes().value("name").toString();
283
284 if (attributeName == "Range") {
285 const QString range = xml.readElementText().trimmed();
286 QStringList rangeList = range.split(' ');
287 if (rangeList.count() != 2) {
288 qCDebug(APMParameterMetaDataVerboseLog) << "space separator didn't work, trying 'to' separator";
289 rangeList = range.split("to");
290 if (rangeList.count() != 2) {
291 qCDebug(APMParameterMetaDataVerboseLog) << "'to' separator didn't work, trying '-' as separator";
292 rangeList = range.split('-');
293 if (rangeList.count() != 2) {
294 qCDebug(APMParameterMetaDataLog) << "something wrong with range, all three separators have failed" << range;
295 }
296 }
297 }
298
299 // everything should be good. let's collect min and max
300 if (rangeList.count() == 2) {
301 rawMetaData->min = rangeList.first().trimmed();
302 rawMetaData->max = rangeList.last().trimmed();
303
304 // sanitize min and max off any comments that they may have
305 if (rawMetaData->min.contains(' ')) {
306 rawMetaData->min = rawMetaData->min.split(' ').first();
307 }
308 if (rawMetaData->max.contains(' ')) {
309 rawMetaData->max = rawMetaData->max.split(' ').first();
310 }
311 qCDebug(APMParameterMetaDataVerboseLog) << "read field parameter"
312 << "min:" << rawMetaData->min
313 << "max:" << rawMetaData->max;
314 }
315 } else if (attributeName == "Increment") {
316 const QString increment = xml.readElementText();
317 qCDebug(APMParameterMetaDataVerboseLog) << "read Increment:" << increment;
318 rawMetaData->incrementSize = increment;
319 } else if (attributeName == "Units") {
320 const QString units = xml.readElementText();
321 qCDebug(APMParameterMetaDataVerboseLog) << "read Units:" << units;
322 rawMetaData->units = units;
323 } else if (attributeName == "ReadOnly") {
324 const QString strValue = xml.readElementText().trimmed();
325 if (strValue.compare("true", Qt::CaseInsensitive) == 0) {
326 rawMetaData->readOnly = true;
327 }
328 qCDebug(APMParameterMetaDataVerboseLog) << "read ReadOnly:" << rawMetaData->readOnly;
329 } else if (attributeName == "Bitmask") {
330 if (bitmaskElementSeen) {
331 // A <bitmask> block was already parsed; ignore legacy field to avoid duplicates
332 (void) xml.readElementText();
333 } else {
334 bool parseError = false;
335
336 const QString bitmaskString = xml.readElementText();
337 qCDebug(APMParameterMetaDataVerboseLog) << "read Bitmask:" << bitmaskString;
338 const QStringList bitmaskList = bitmaskString.split(",");
339 if (!bitmaskList.isEmpty()) {
340 for (const QString &bitmask : bitmaskList) {
341 const QStringList pair = bitmask.split(":");
342 if (pair.count() == 2) {
343 rawMetaData->bitmask << QPair<QString, QString>(pair[0].trimmed(), pair[1].trimmed());
344 } else {
345 qCDebug(APMParameterMetaDataLog) << "parse error: bitmask:" << bitmaskString << "pair count:" << pair.count();
346 parseError = true;
347 break;
348 }
349 }
350 }
351
352 if (parseError) {
353 rawMetaData->bitmask.clear();
354 }
355 }
356 } else if (attributeName == "RebootRequired") {
357 const QString strValue = xml.readElementText().trimmed();
358 if (strValue.compare("true", Qt::CaseInsensitive) == 0) {
359 rawMetaData->rebootRequired = true;
360 }
361 }
362 } else if (elementName == "values") {
363 // doing nothing individual value will follow anyway. May be used for sanity checking.
364 } else if (elementName == "value") {
365 const QString valueValue = xml.attributes().value("code").toString();
366 const QString valueName = xml.readElementText();
367 qCDebug(APMParameterMetaDataVerboseLog) << "read value parameter" << "value desc:"
368 << valueName << "code:" << valueValue;
369 values << QPair<QString,QString>(valueValue, valueName);
370 rawMetaData->values = values;
371 } else if (elementName == "bitmask") {
372 QList<QPair<QString,QString>> parsed;
373 bool parseError = false;
374
375 while (!(xml.isEndElement() && (xml.name() == QStringLiteral("bitmask")))) {
376 (void) xml.readNext();
377 if (xml.isStartElement()) {
378 if (xml.name() == QStringLiteral("bit")) {
379 const QString code = xml.attributes().value("code").toString().trimmed();
380 const QString desc = xml.readElementText().trimmed();
381 if (code.isEmpty()) {
382 parseError = true;
383 qCDebug(APMParameterMetaDataLog) << "parse error: <bit> missing code attribute";
384 break;
385 }
386 parsed << qMakePair(code, desc);
387 } else {
388 qCWarning(APMParameterMetaDataLog) << "Unknown element inside <bitmask>:" << xml.name().toString();
389 }
390 } else if (xml.hasError() || xml.atEnd()) {
391 parseError = true;
392 break;
393 }
394 }
395
396 if (!parseError && !parsed.isEmpty()) {
397 rawMetaData->bitmask = parsed;
398 bitmaskElementSeen = true;
399 qCDebug(APMParameterMetaDataVerboseLog) << "parsed bitmask from <bitmask> tag with" << parsed.size() << "entries";
400 } else if (parseError) {
401 qCDebug(APMParameterMetaDataLog) << "parse error while reading <bitmask> block";
402 }
403 } else {
404 qCWarning(APMParameterMetaDataLog) << "Unknown parameter element in XML: " << elementName;
405 }
406
407 (void) xml.readNext();
408 elementName = xml.name().toString();
409 }
410 return true;
411}
412
414{
415 bool keepTrying = true;
416 QString mavTypeString = _mavTypeToString(vehicleType);
417 APMFactMetaDataRaw *rawMetaData = nullptr;
418
419 // check if we have metadata for fact, use generic otherwise
420 while (keepTrying) {
421 if (_vehicleTypeToParametersMap[mavTypeString].contains(name)) {
422 rawMetaData = _vehicleTypeToParametersMap[mavTypeString][name];
423 } else if (_vehicleTypeToParametersMap["libraries"].contains(name)) {
424 rawMetaData = _vehicleTypeToParametersMap["libraries"][name];
425 }
426 if (!rawMetaData && (mavTypeString == "Rover")) {
427 // Hack city: Older versions of Rover have different name
428 mavTypeString = "APMrover2";
429 } else {
430 keepTrying = false;
431 }
432 }
433
434 FactMetaData *const metaData = new FactMetaData(type, this);
435
436 // we don't have data for this fact
437 if (!rawMetaData) {
438 metaData->setCategory(QStringLiteral("Advanced"));
439 metaData->setGroup(_groupFromParameterName(name));
440 qCDebug(APMParameterMetaDataLog) << "No metaData for" << name << "using generic metadata";
441 return metaData;
442 }
443
444 metaData->setName(rawMetaData->name);
445 if (!rawMetaData->category.isEmpty()) {
446 metaData->setCategory(rawMetaData->category);
447 }
448 metaData->setGroup(rawMetaData->group);
449 metaData->setVehicleRebootRequired(rawMetaData->rebootRequired);
450 metaData->setReadOnly(rawMetaData->readOnly);
451
452 if (!rawMetaData->shortDescription.isEmpty()) {
453 metaData->setShortDescription(rawMetaData->shortDescription);
454 }
455
456 if (!rawMetaData->longDescription.isEmpty()) {
457 metaData->setLongDescription(rawMetaData->longDescription);
458 }
459
460 if (!rawMetaData->units.isEmpty()) {
461 metaData->setRawUnits(rawMetaData->units);
462 }
463
464 if (!rawMetaData->min.isEmpty()) {
465 QVariant varMin;
466 QString errorString;
467 if (metaData->convertAndValidateRaw(rawMetaData->min, false /* validate as well */, varMin, errorString)) {
468 metaData->setRawMin(varMin);
469 } else {
470 qCDebug(APMParameterMetaDataLog) << "Invalid min value, name:" << metaData->name()
471 << "type:" << metaData->type()
472 << "min:" << rawMetaData->min
473 << "error:" << errorString;
474 }
475 }
476
477 if (!rawMetaData->max.isEmpty()) {
478 QVariant varMax;
479 QString errorString;
480 if (metaData->convertAndValidateRaw(rawMetaData->max, false /* validate as well */, varMax, errorString)) {
481 metaData->setRawMax(varMax);
482 } else {
483 qCDebug(APMParameterMetaDataLog) << "Invalid max value, name:" << metaData->name()
484 << "type:" << metaData->type()
485 << "max:" << rawMetaData->max
486 << "error:" << errorString;
487 }
488 }
489
490 if (!rawMetaData->min.isEmpty() && !rawMetaData->max.isEmpty()) {
491 metaData->setRawUserMin(metaData->rawMin());
492 metaData->setRawUserMax(metaData->rawMax());
493 }
494
495 if (!rawMetaData->values.isEmpty()) {
496 QStringList enumStrings;
497 QVariantList enumValues;
498
499 for (int i = 0; i < rawMetaData->values.count(); i++) {
500 QVariant enumValue;
501 QString errorString;
502 const QPair<QString, QString> enumPair = rawMetaData->values[i];
503
504 if (metaData->convertAndValidateRaw(enumPair.first, false /* validate */, enumValue, errorString)) {
505 enumValues << enumValue;
506 enumStrings << enumPair.second;
507 } else {
508 qCDebug(APMParameterMetaDataLog) << "Invalid enum value, name:" << metaData->name()
509 << "type:" << metaData->type()
510 << "value:" << enumPair.first
511 << "error:" << errorString;
512 enumStrings.clear();
513 enumValues.clear();
514 break;
515 }
516 }
517
518 if (!enumStrings.isEmpty()) {
519 metaData->setEnumInfo(enumStrings, enumValues);
520 }
521 }
522
523 if (!rawMetaData->bitmask.isEmpty()) {
524 QStringList bitmaskStrings;
525 QVariantList bitmaskValues;
526
527 for (int i = 0; i < rawMetaData->bitmask.count(); i++) {
528 QString errorString;
529 const QPair<QString, QString> bitmaskPair = rawMetaData->bitmask[i];
530
531 bool ok = false;
532 const unsigned int bitIndex = bitmaskPair.first.toUInt(&ok);
533 const quint64 bitSet = ok ? (1ull << bitIndex) : 0ull;
534
535 QVariant typedBitSet;
536
537 switch (type) {
539 typedBitSet = QVariant(static_cast<qint8>(bitSet));
540 break;
542 typedBitSet = QVariant(static_cast<qint16>(bitSet));
543 break;
545 typedBitSet = QVariant(static_cast<qint32>(bitSet));
546 break;
548 typedBitSet = QVariant(static_cast<qint64>(bitSet));
549 break;
551 typedBitSet = QVariant(static_cast<quint8>(bitSet));
552 break;
554 typedBitSet = QVariant(static_cast<quint16>(bitSet));
555 break;
557 typedBitSet = QVariant(static_cast<quint32>(bitSet));
558 break;
560 typedBitSet = QVariant(static_cast<quint64>(bitSet));
561 break;
562 default:
563 break;
564 }
565
566 if (typedBitSet.isNull()) {
567 qCDebug(APMParameterMetaDataLog) << "Invalid type for bitmask, name:" << metaData->name()
568 << "type:" << metaData->type();
569 }
570
571 if (!ok) {
572 qCDebug(APMParameterMetaDataLog) << "Invalid bitmask value, name:" << metaData->name()
573 << "type:" << metaData->type()
574 << "value:" << bitmaskPair.first
575 << "error: toUInt failed";
576 bitmaskStrings.clear();
577 bitmaskValues.clear();
578 break;
579 }
580
581 QVariant bitmaskValue;
582 if (metaData->convertAndValidateRaw(typedBitSet, false /* validate */, bitmaskValue, errorString)) {
583 bitmaskValues << bitmaskValue;
584 bitmaskStrings << bitmaskPair.second;
585 } else {
586 qCDebug(APMParameterMetaDataLog) << "Invalid bitmask value, name:" << metaData->name()
587 << "type:" << metaData->type()
588 << "value:" << typedBitSet
589 << "error:" << errorString;
590 bitmaskStrings.clear();
591 bitmaskValues.clear();
592 break;
593 }
594 }
595
596 if (!bitmaskStrings.isEmpty()) {
597 metaData->setBitmaskInfo(bitmaskStrings, bitmaskValues);
598 }
599 }
600
601 if (!rawMetaData->incrementSize.isEmpty()) {
602 bool ok;
603 const double increment = rawMetaData->incrementSize.toDouble(&ok);
604 if (ok) {
605 metaData->setRawIncrement(increment);
606 } else {
607 qCDebug(APMParameterMetaDataLog) << "Invalid value for increment, name:" << metaData->name() << "increment:" << rawMetaData->incrementSize;
608 }
609 }
610
611 // ArduPilot does not yet support decimal places meta data. So for P/I/D parameters we force to 6 places
612 if ((name.endsWith(QStringLiteral("_P")) || name.endsWith(QStringLiteral("_I")) || name.endsWith(QStringLiteral("_D"))) &&
614 metaData->setDecimalPlaces(6);
615 }
616
617 return metaData;
618}
619
620void APMParameterMetaData::getParameterMetaDataVersionInfo(const QString &metaDataFile, int &majorVersion, int &minorVersion)
621{
622 static const QRegularExpression regex(".*\\.(\\d)\\.(\\d)\\.xml$");
623 const QRegularExpressionMatch match = regex.match(metaDataFile);
624 if (match.hasMatch() && (match.lastCapturedIndex() == 2)) {
625 majorVersion = match.captured(1).toInt();
626 minorVersion = match.captured(2).toInt();
627 } else {
628 majorVersion = -1;
629 minorVersion = -1;
630 qCWarning(APMParameterMetaDataLog) << "Unable to parse version from parameter meta data file name:" << metaDataFile;
631 }
632}
QMap< QString, APMFactMetaDataRaw * > ParameterNametoFactMetaDataMap
QString errorString
#define QGC_LOGGING_CATEGORY(name, categoryStr)
QList< QPair< QString, QString > > values
QList< QPair< QString, QString > > bitmask
Collection of Parameter Facts for ArduPilot.
void loadParameterFactMetaDataFile(const QString &metaDataFile)
static void getParameterMetaDataVersionInfo(const QString &metaDataFile, int &majorVersion, int &minorVersion)
FactMetaData * getMetaDataForFact(const QString &name, MAV_TYPE vehicleType, FactMetaData::ValueType_t type)
void setRawUnits(const QString &rawUnits)
void setDecimalPlaces(int decimalPlaces)
void setRawUserMin(const QVariant &rawUserMin)
void setShortDescription(const QString &shortDescription)
QVariant rawMin() const
void setName(const QString &name)
void setLongDescription(const QString &longDescription)
void setRawUserMax(const QVariant &rawUserMax)
void setVehicleRebootRequired(bool rebootRequired)
void setRawMin(const QVariant &rawMin)
void setCategory(const QString &category)
bool convertAndValidateRaw(const QVariant &rawValue, bool convertOnly, QVariant &typedValue, QString &errorString) const
static const QString defaultGroup()
void setEnumInfo(const QStringList &strings, const QVariantList &values)
void setBitmaskInfo(const QStringList &strings, const QVariantList &values)
void setRawMax(const QVariant &rawMax)
void setRawIncrement(double increment)
QString name() const
void setGroup(const QString &group)
ValueType_t type() const
QVariant rawMax() const
void setReadOnly(bool bValue)