QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
FactMetaData.cc
Go to the documentation of this file.
1#include "FactMetaData.h"
2#include "JsonHelper.h"
3#include "MAVLinkLib.h"
5#include "SettingsManager.h"
6#include "UnitsSettings.h"
7
8#include <QtCore/QtMath>
9
10QGC_LOGGING_CATEGORY(FactMetaDataLog, "FactSystem.FactMetaData")
11
12// Built in translations for all Facts
13const FactMetaData::BuiltInTranslation_s FactMetaData::_rgBuiltInTranslations[] = {
14 { "centi-degrees", "deg", FactMetaData::_centiDegreesToDegrees, FactMetaData::_degreesToCentiDegrees },
15 { "radians", "deg", FactMetaData::_radiansToDegrees, FactMetaData::_degreesToRadians },
16 { "rad", "deg", FactMetaData::_radiansToDegrees, FactMetaData::_degreesToRadians },
17 { "gimbal-degrees", "deg", FactMetaData::_mavlinkGimbalDegreesToUserGimbalDegrees, FactMetaData::_userGimbalDegreesToMavlinkGimbalDegrees },
18 { "norm", "%", FactMetaData::_normToPercent, FactMetaData::_percentToNorm },
19 { "centi-celsius", "C", FactMetaData::_centiCelsiusToCelsius, FactMetaData::_celsiusToCentiCelsius },
20};
21
22// Translations driven by app settings
23const FactMetaData::AppSettingsTranslation_s FactMetaData::_rgAppSettingsTranslations[] = {
24 { "m", "m", FactMetaData::UnitHorizontalDistance, UnitsSettings::HorizontalDistanceUnitsMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
25 { "meter", "meter", FactMetaData::UnitHorizontalDistance, UnitsSettings::HorizontalDistanceUnitsMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
26 { "meters", "meters", FactMetaData::UnitHorizontalDistance, UnitsSettings::HorizontalDistanceUnitsMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
27 // NOTE: we've coined an artificial "raw unit" of "vertical metre" to separate it from the horizontal metre - a bit awkward but this is all the design permits
28 { "vertical m", "m", FactMetaData::UnitVerticalDistance, UnitsSettings::VerticalDistanceUnitsMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
29 { "cm/px", "cm/px", FactMetaData::UnitHorizontalDistance, UnitsSettings::HorizontalDistanceUnitsMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
30 { "m/s", "m/s", FactMetaData::UnitSpeed, UnitsSettings::SpeedUnitsMetersPerSecond, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
31 { "C", "C", FactMetaData::UnitTemperature, UnitsSettings::TemperatureUnitsCelsius, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
32 { "m^2", "m^2", FactMetaData::UnitArea, UnitsSettings::AreaUnitsSquareMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
33 { "m", "ft", FactMetaData::UnitHorizontalDistance, UnitsSettings::HorizontalDistanceUnitsFeet, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters },
34 { "meter", "ft", FactMetaData::UnitHorizontalDistance, UnitsSettings::HorizontalDistanceUnitsFeet, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters },
35 { "meters", "ft", FactMetaData::UnitHorizontalDistance, UnitsSettings::HorizontalDistanceUnitsFeet, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters },
36 { "vertical m", "ft", FactMetaData::UnitVerticalDistance, UnitsSettings::VerticalDistanceUnitsFeet, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters },
37 { "cm/px", "in/px", FactMetaData::UnitHorizontalDistance, UnitsSettings::HorizontalDistanceUnitsFeet, FactMetaData::_centimetersToInches, FactMetaData::_inchesToCentimeters },
38 { "m^2", "km^2", FactMetaData::UnitArea, UnitsSettings::AreaUnitsSquareKilometers, FactMetaData::_squareMetersToSquareKilometers, FactMetaData::_squareKilometersToSquareMeters },
39 { "m^2", "ha", FactMetaData::UnitArea, UnitsSettings::AreaUnitsHectares, FactMetaData::_squareMetersToHectares, FactMetaData::_hectaresToSquareMeters },
40 { "m^2", "ft^2", FactMetaData::UnitArea, UnitsSettings::AreaUnitsSquareFeet, FactMetaData::_squareMetersToSquareFeet, FactMetaData::_squareFeetToSquareMeters },
41 { "m^2", "ac", FactMetaData::UnitArea, UnitsSettings::AreaUnitsAcres, FactMetaData::_squareMetersToAcres, FactMetaData::_acresToSquareMeters },
42 { "m^2", "mi^2", FactMetaData::UnitArea, UnitsSettings::AreaUnitsSquareMiles, FactMetaData::_squareMetersToSquareMiles, FactMetaData::_squareMilesToSquareMeters },
43 { "m/s", "ft/s", FactMetaData::UnitSpeed, UnitsSettings::SpeedUnitsFeetPerSecond, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters },
44 { "m/s", "mph", FactMetaData::UnitSpeed, UnitsSettings::SpeedUnitsMilesPerHour, FactMetaData::_metersPerSecondToMilesPerHour, FactMetaData::_milesPerHourToMetersPerSecond },
45 { "m/s", "km/h", FactMetaData::UnitSpeed, UnitsSettings::SpeedUnitsKilometersPerHour, FactMetaData::_metersPerSecondToKilometersPerHour, FactMetaData::_kilometersPerHourToMetersPerSecond },
46 { "m/s", "kn", FactMetaData::UnitSpeed, UnitsSettings::SpeedUnitsKnots, FactMetaData::_metersPerSecondToKnots, FactMetaData::_knotsToMetersPerSecond },
47 { "C", "F", FactMetaData::UnitTemperature, UnitsSettings::TemperatureUnitsFarenheit, FactMetaData::_celsiusToFarenheit, FactMetaData::_farenheitToCelsius },
48 { "g", "g", FactMetaData::UnitWeight, UnitsSettings::WeightUnitsGrams, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
49 { "g", "kg", FactMetaData::UnitWeight, UnitsSettings::WeightUnitsKg, FactMetaData::_gramsToKilograms, FactMetaData::_kilogramsToGrams },
50 { "g", "oz", FactMetaData::UnitWeight, UnitsSettings::WeightUnitsOz, FactMetaData::_gramsToOunces, FactMetaData::_ouncesToGrams },
51 { "g", "lbs", FactMetaData::UnitWeight, UnitsSettings::WeightUnitsLbs, FactMetaData::_gramsToPunds, FactMetaData::_poundsToGrams },
52};
53
55 : QObject(parent)
56{
57 // qCDebug(FactMetaDataLog) << Q_FUNC_INFO << this;
58}
59
61 : QObject(parent)
62 , _type(type)
63{
64 // qCDebug(FactMetaDataLog) << Q_FUNC_INFO << this;
65}
66
67FactMetaData::FactMetaData(const FactMetaData &other, QObject *parent)
68 : QObject(parent)
69{
70 // qCDebug(FactMetaDataLog) << Q_FUNC_INFO << this;
71 *this = other;
72}
73
74FactMetaData::FactMetaData(ValueType_t type, const QString &name, QObject *parent)
75 : QObject(parent)
76 , _type(type)
77 , _name(name)
78{
79 // qCDebug(FactMetaDataLog) << Q_FUNC_INFO << this;
80}
81
83{
84 // qCDebug(FactMetaDataLog) << Q_FUNC_INFO << this;
85}
86
88{
89 _decimalPlaces = other._decimalPlaces;
90 _rawDefaultValue = other._rawDefaultValue;
91 _defaultValueAvailable = other._defaultValueAvailable;
92 _bitmaskStrings = other._bitmaskStrings;
93 _bitmaskValues = other._bitmaskValues;
94 _enumStrings = other._enumStrings;
95 _enumValues = other._enumValues;
96 _category = other._category;
97 _group = other._group;
98 _longDescription = other._longDescription;
99 _rawMax = other._rawMax;
100 _rawMin = other._rawMin;
101 _rawUserMin = other._rawUserMin;
102 _rawUserMax = other._rawUserMax;
103 _name = other._name;
104 _shortDescription = other._shortDescription;
105 _type = other._type;
106 _rawUnits = other._rawUnits;
107 _cookedUnits = other._cookedUnits;
108 _rawTranslator = other._rawTranslator;
109 _cookedTranslator = other._cookedTranslator;
110 _vehicleRebootRequired = other._vehicleRebootRequired;
111 _qgcRebootRequired = other._qgcRebootRequired;
112 _rawIncrement = other._rawIncrement;
113 _hasControl = other._hasControl;
114 _readOnly = other._readOnly;
115 _writeOnly = other._writeOnly;
116 _volatile = other._volatile;
117
118 return *this;
119}
120
122{
123 if (_defaultValueAvailable) {
124 return _rawDefaultValue;
125 } else {
126 qWarning(FactMetaDataLog) << "Attempt to access unavailable default value";
127 return QVariant(0);
128 }
129}
130
131void FactMetaData::setRawDefaultValue(const QVariant &rawDefaultValue)
132{
133 if ((_type == valueTypeString) || (isInRawMinLimit(rawDefaultValue) && isInRawMaxLimit(rawDefaultValue))) {
134 _rawDefaultValue = rawDefaultValue;
135 _defaultValueAvailable = true;
136 } else {
137 qWarning(FactMetaDataLog) << "Attempt to set default value which is outside min/max range";
138 }
139}
140
141void FactMetaData::setRawMin(const QVariant &rawMin)
142{
143 if (isInRawMinLimit(rawMin)) {
144 _rawMin = rawMin;
145 if (_rawUserMin.isValid() && !isInRawMinLimit(_rawUserMin)) {
146 _rawUserMin = _rawMin;
147 }
148 } else {
149 qWarning(FactMetaDataLog) << "Attempt to set min below allowable value for fact:" << name()
150 << ", value attempted:" << rawMin
151 << ", type:" << type()
152 << ", min for type:" << _minForType();
153 _rawMin = _minForType();
154 _rawUserMin = _rawMin;
155 }
156}
157
158void FactMetaData::setRawMax(const QVariant &rawMax)
159{
160 if (isInRawMaxLimit(rawMax)) {
161 _rawMax = rawMax;
162 if (_rawUserMax.isValid() && !isInRawMaxLimit(_rawUserMax)) {
163 _rawUserMax = _rawMax;
164 }
165 } else {
166 qWarning(FactMetaDataLog) << "Attempt to set max above allowable value for fact:" << name()
167 << ", value attempted:" << rawMax
168 << ", type:" << type()
169 << ", max for type:" << _maxForType();
170 _rawMax = _maxForType();
171 _rawUserMax = _rawMax;
172 }
173}
174
175void FactMetaData::setRawUserMin(const QVariant &rawUserMin)
176{
177 if (isInRawMinLimit(rawUserMin)) {
178 _rawUserMin = rawUserMin;
179 } else {
180 qWarning(FactMetaDataLog) << "Attempt to set user min below allowable value for fact:" << name()
181 << ", value attempted:" << rawUserMin
182 << ", type:" << type()
183 << ", min:" << _rawMin;
184 _rawUserMin = _rawMin;
185 }
186}
187
188void FactMetaData::setRawUserMax(const QVariant &rawUserMax)
189{
190 if (isInRawMaxLimit(rawUserMax)) {
191 _rawUserMax = rawUserMax;
192 } else {
193 qWarning(FactMetaDataLog) << "Attempt to set user max above allowable value for fact:" << name()
194 << ", value attempted:" << rawUserMax
195 << ", type:" << type()
196 << ", max:" << _rawMax;
197 _rawUserMax = _rawMax;
198 }
199}
200
201bool FactMetaData::isInRawMinLimit(const QVariant &variantValue) const
202{
203 switch (_type) {
204 case valueTypeUint8:
205 return (_rawMin.value<unsigned char>() <= variantValue.value<unsigned char>());
206 case valueTypeInt8:
207 return (_rawMin.value<signed char>() <= variantValue.value<signed char>());
208 case valueTypeUint16:
209 return (_rawMin.value<unsigned short int>() <= variantValue.value<unsigned short int>());
210 case valueTypeInt16:
211 return (_rawMin.value<short int>() <= variantValue.value<short int>());
212 case valueTypeUint32:
213 return (_rawMin.value<uint32_t>() <= variantValue.value<uint32_t>());
214 case valueTypeInt32:
215 return (_rawMin.value<int32_t>() <= variantValue.value<int32_t>());
216 case valueTypeUint64:
217 return (_rawMin.value<uint64_t>() <= variantValue.value<uint64_t>());
218 case valueTypeInt64:
219 return (_rawMin.value<int64_t>() <= variantValue.value<int64_t>());
220 case valueTypeFloat:
221 return ((qIsNaN(variantValue.toFloat())) || (_rawMin.value<float>() <= variantValue.value<float>()));
222 case valueTypeDouble:
223 return ((qIsNaN(variantValue.toDouble())) || (_rawMin.value<double>() <= variantValue.value<double>()));
224 default:
225 return true;
226 }
227}
228
229bool FactMetaData::isInRawMaxLimit(const QVariant &variantValue) const
230{
231 switch (_type) {
232 case valueTypeUint8:
233 return (_rawMax.value<unsigned char>() >= variantValue.value<unsigned char>());
234 case valueTypeInt8:
235 return (_rawMax.value<signed char>() >= variantValue.value<signed char>());
236 case valueTypeUint16:
237 return (_rawMax.value<unsigned short int>() >= variantValue.value<unsigned short int>());
238 case valueTypeInt16:
239 return (_rawMax.value<short int>() >= variantValue.value<short int>());
240 case valueTypeUint32:
241 return (_rawMax.value<uint32_t>() >= variantValue.value<uint32_t>());
242 case valueTypeInt32:
243 return (_rawMax.value<int32_t>() >= variantValue.value<int32_t>());
244 case valueTypeUint64:
245 return (_rawMax.value<uint64_t>() >= variantValue.value<uint64_t>());
246 case valueTypeInt64:
247 return (_rawMax.value<int64_t>() >= variantValue.value<int64_t>());
248 case valueTypeFloat:
249 return (qIsNaN(variantValue.toFloat()) || (_rawMax.value<float>() >= variantValue.value<float>()));
250 case valueTypeDouble:
251 return (qIsNaN(variantValue.toDouble()) || (_rawMax.value<double>() >= variantValue.value<double>()));
252 default:
253 return true;
254 }
255}
256
258{
259 switch (type) {
260 case valueTypeUint8:
261 return QVariant(std::numeric_limits<unsigned char>::min());
262 case valueTypeInt8:
263 return QVariant(std::numeric_limits<signed char>::min());
264 case valueTypeUint16:
265 return QVariant(std::numeric_limits<unsigned short int>::min());
266 case valueTypeInt16:
267 return QVariant(std::numeric_limits<short int>::min());
268 case valueTypeUint32:
269 return QVariant(std::numeric_limits<uint32_t>::min());
270 case valueTypeInt32:
271 return QVariant(std::numeric_limits<int32_t>::min());
272 case valueTypeUint64:
273 return QVariant((qulonglong)std::numeric_limits<uint64_t>::min());
274 case valueTypeInt64:
275 return QVariant((qlonglong)std::numeric_limits<int64_t>::min());
276 case valueTypeFloat:
277 return QVariant(-std::numeric_limits<float>::max());
278 case valueTypeDouble:
279 return QVariant(-std::numeric_limits<double>::max());
280 case valueTypeString:
281 return QVariant();
282 case valueTypeBool:
283 return QVariant(0);
285 return QVariant(0.0);
286 case valueTypeCustom:
287 default:
288 return QVariant();
289 }
290}
291
293{
294 switch (type) {
295 case valueTypeUint8:
296 return QVariant(std::numeric_limits<unsigned char>::max());
297 case valueTypeInt8:
298 return QVariant(std::numeric_limits<signed char>::max());
299 case valueTypeUint16:
300 return QVariant(std::numeric_limits<unsigned short int>::max());
301 case valueTypeInt16:
302 return QVariant(std::numeric_limits<short int>::max());
303 case valueTypeUint32:
304 return QVariant(std::numeric_limits<uint32_t>::max());
305 case valueTypeInt32:
306 return QVariant(std::numeric_limits<int32_t>::max());
307 case valueTypeUint64:
308 return QVariant((qulonglong)std::numeric_limits<uint64_t>::max());
309 case valueTypeInt64:
310 return QVariant((qlonglong)std::numeric_limits<int64_t>::max());
311 case valueTypeFloat:
312 return QVariant(std::numeric_limits<float>::max());
314 case valueTypeDouble:
315 return QVariant(std::numeric_limits<double>::max());
316 case valueTypeString:
317 return QVariant();
318 case valueTypeBool:
319 return QVariant(1);
320 case valueTypeCustom:
321 default:
322 return QVariant();
323 }
324}
325
326bool FactMetaData::convertAndValidateRaw(const QVariant &rawValue, bool convertOnly, QVariant &typedValue, QString &errorString) const
327{
328 bool convertOk = false;
329
330 errorString.clear();
331
332 switch (type()) {
336 typedValue = QVariant(rawValue.toInt(&convertOk));
337 if (!convertOnly && convertOk) {
338 if (!isInRawLimit<int32_t>(typedValue)) {
339 errorString = tr("Value must be within %1 and %2").arg(rawMin().toInt()).arg(rawMax().toInt());
340 }
341 }
342 break;
344 typedValue = QVariant(rawValue.toLongLong(&convertOk));
345 if (!convertOnly && convertOk) {
346 if (!isInRawLimit<int64_t>(typedValue)) {
347 errorString = tr("Value must be within %1 and %2").arg(rawMin().toInt()).arg(rawMax().toInt());
348 }
349 }
350 break;
354 typedValue = QVariant(rawValue.toUInt(&convertOk));
355 if (!convertOnly && convertOk) {
356 if (!isInRawLimit<uint32_t>(typedValue)) {
357 errorString = tr("Value must be within %1 and %2").arg(rawMin().toUInt()).arg(rawMax().toUInt());
358 }
359 }
360 break;
362 typedValue = QVariant(rawValue.toULongLong(&convertOk));
363 if (!convertOnly && convertOk) {
364 if (!isInRawLimit<uint64_t>(typedValue)) {
365 errorString = tr("Value must be within %1 and %2").arg(rawMin().toUInt()).arg(rawMax().toUInt());
366 }
367 }
368 break;
370 typedValue = QVariant(rawValue.toFloat(&convertOk));
371 if (!convertOnly && convertOk) {
372 if (!isInRawLimit<float>(typedValue)) {
373 errorString = tr("Value must be within %1 and %2").arg(rawMin().toDouble()).arg(rawMax().toDouble());
374 }
375 }
376 break;
379 typedValue = QVariant(rawValue.toDouble(&convertOk));
380 if (!convertOnly && convertOk) {
381 if (!isInRawLimit<double>(typedValue)) {
382 errorString = tr("Value must be within %1 and %2").arg(rawMin().toDouble()).arg(rawMax().toDouble());
383 }
384 }
385 break;
387 convertOk = true;
388 typedValue = QVariant(rawValue.toString());
389 break;
391 convertOk = true;
392 typedValue = QVariant(rawValue.toBool());
393 break;
395 convertOk = true;
396 typedValue = QVariant(rawValue.toByteArray());
397 break;
398 }
399
400 if (!convertOk) {
401 errorString += tr("Invalid number");
402 }
403
404 return (convertOk && errorString.isEmpty());
405}
406
407bool FactMetaData::convertAndValidateCooked(const QVariant &cookedValue, bool convertOnly, QVariant &typedValue, QString &errorString) const
408{
409 bool convertOk = false;
410
411 errorString.clear();
412
413 if (!convertOnly && _customCookedValidator) {
414 errorString = _customCookedValidator(cookedValue);
415 if (!errorString.isEmpty()) {
416 return false;
417 }
418 }
419
420 switch (type()) {
424 typedValue = QVariant(cookedValue.toInt(&convertOk));
425 if (!convertOnly && convertOk) {
426 if (!isInCookedLimit<int32_t>(typedValue)) {
427 errorString = tr("Value must be within %1 and %2").arg(cookedMin().toInt()).arg(cookedMax().toInt());
428 }
429 }
430 break;
432 typedValue = QVariant(cookedValue.toLongLong(&convertOk));
433 if (!convertOnly && convertOk) {
434 if (!isInCookedLimit<int64_t>(typedValue)) {
435 errorString = tr("Value must be within %1 and %2").arg(cookedMin().toInt()).arg(cookedMax().toInt());
436 }
437 }
438 break;
442 typedValue = QVariant(cookedValue.toUInt(&convertOk));
443 if (!convertOnly && convertOk) {
444 if (!isInCookedLimit<uint32_t>(typedValue)) {
445 errorString = tr("Value must be within %1 and %2").arg(cookedMin().toUInt()).arg(cookedMax().toUInt());
446 }
447 }
448 break;
450 typedValue = QVariant(cookedValue.toULongLong(&convertOk));
451 if (!convertOnly && convertOk) {
452 if (!isInCookedLimit<uint64_t>(typedValue)) {
453 errorString = tr("Value must be within %1 and %2").arg(cookedMin().toUInt()).arg(cookedMax().toUInt());
454 }
455 }
456 break;
458 typedValue = QVariant(cookedValue.toFloat(&convertOk));
459 if (!convertOnly && convertOk) {
460 if (!isInCookedLimit<float>(typedValue)) {
461 errorString = tr("Value must be within %1 and %2").arg(cookedMin().toFloat()).arg(cookedMax().toFloat());
462 }
463 }
464 break;
467 typedValue = QVariant(cookedValue.toDouble(&convertOk));
468 if (!convertOnly && convertOk) {
469 if (!isInCookedLimit<double>(typedValue)) {
470 errorString = tr("Value must be within %1 and %2").arg(cookedMin().toDouble()).arg(cookedMax().toDouble());
471 }
472 }
473 break;
475 convertOk = true;
476 typedValue = QVariant(cookedValue.toString());
477 break;
479 convertOk = true;
480 typedValue = QVariant(cookedValue.toBool());
481 break;
483 convertOk = true;
484 typedValue = QVariant(cookedValue.toByteArray());
485 break;
486 }
487
488 if (!convertOk) {
489 errorString += tr("Invalid number");
490 }
491
492 return (convertOk && errorString.isEmpty());
493}
494
495bool FactMetaData::clampValue(const QVariant &cookedValue, QVariant &typedValue) const
496{
497 bool convertOk = false;
498
499 switch (type()) {
503 typedValue = QVariant(cookedValue.toInt(&convertOk));
504 if (convertOk) {
505 clamp<int32_t>(typedValue);
506 }
507 break;
509 typedValue = QVariant(cookedValue.toLongLong(&convertOk));
510 if (convertOk) {
511 clamp<int64_t>(typedValue);
512 }
513 break;
517 typedValue = QVariant(cookedValue.toUInt(&convertOk));
518 if (convertOk) {
519 clamp<uint32_t>(typedValue);
520 }
521 break;
523 typedValue = QVariant(cookedValue.toULongLong(&convertOk));
524 if (convertOk) {
525 clamp<uint64_t>(typedValue);
526 }
527 break;
529 typedValue = QVariant(cookedValue.toFloat(&convertOk));
530 if (convertOk) {
531 clamp<float>(typedValue);
532 }
533 break;
536 typedValue = QVariant(cookedValue.toDouble(&convertOk));
537 if (convertOk) {
538 clamp<double>(typedValue);
539 }
540 break;
542 convertOk = true;
543 typedValue = QVariant(cookedValue.toString());
544 break;
546 convertOk = true;
547 typedValue = QVariant(cookedValue.toBool());
548 break;
550 convertOk = true;
551 typedValue = QVariant(cookedValue.toByteArray());
552 break;
553 }
554
555 return convertOk;
556}
557
558void FactMetaData::setBitmaskInfo(const QStringList &strings, const QVariantList &values)
559{
560 if (strings.count() != values.count()) {
561 qWarning(FactMetaDataLog) << "Count mismatch strings:values" << strings.count() << values.count();
562 return;
563 }
564
565 _bitmaskStrings = strings;
566 _bitmaskValues = values;
568}
569
570void FactMetaData::addBitmaskInfo(const QString &name, const QVariant &value)
571{
572 _bitmaskStrings << name;
573 _bitmaskValues << value;
574}
575
576void FactMetaData::setEnumInfo(const QStringList &strings, const QVariantList &values)
577{
578 if (strings.count() != values.count()) {
579 qWarning(FactMetaDataLog) << "Count mismatch strings:values" << strings.count() << values.count();
580 return;
581 }
582
583 _enumStrings = strings;
584 _enumValues = values;
586}
587
588void FactMetaData::addEnumInfo(const QString &name, const QVariant &value)
589{
590 _enumStrings << name;
591 _enumValues << value;
592}
593
594void FactMetaData::removeEnumInfo(const QVariant &value)
595{
596 const int index = _enumValues.indexOf(value);
597 if (index < 0) {
598 qWarning(FactMetaDataLog) << "Value does not exist in fact:" << value;
599 return;
600 }
601
602 _enumValues.removeAt(index);
603 _enumStrings.removeAt(index);
604}
605
606void FactMetaData::setTranslators(Translator rawTranslator_, Translator cookedTranslator_)
607{
608 _rawTranslator = rawTranslator_;
609 _cookedTranslator = cookedTranslator_;
610}
611
613{
614 if (_enumStrings.count() || _bitmaskStrings.count()) {
615 // No translation if enum
616 setTranslators(_defaultTranslator, _defaultTranslator);
617 _cookedUnits = _rawUnits;
618 return;
619 } else {
620 for (size_t i = 0; i < std::size(_rgBuiltInTranslations); i++) {
621 const BuiltInTranslation_s *pBuiltInTranslation = &_rgBuiltInTranslations[i];
622
623 if (pBuiltInTranslation->rawUnits.toLower() == _rawUnits.toLower()) {
624 _cookedUnits = pBuiltInTranslation->cookedUnits;
625 setTranslators(pBuiltInTranslation->rawTranslator, pBuiltInTranslation->cookedTranslator);
626 return;
627 }
628 }
629 }
630
631 // Translator not yet set, try app settings translators
632 _setAppSettingsTranslators();
633}
634
635QVariant FactMetaData::_degreesToRadians(const QVariant &degrees)
636{
637 return QVariant(qDegreesToRadians(degrees.toDouble()));
638}
639
640QVariant FactMetaData::_radiansToDegrees(const QVariant &radians)
641{
642 return QVariant(qRadiansToDegrees(radians.toDouble()));
643}
644
645QVariant FactMetaData::_centiDegreesToDegrees(const QVariant &centiDegrees)
646{
647 return QVariant(centiDegrees.toReal() / 100.0);
648}
649
650QVariant FactMetaData::_degreesToCentiDegrees(const QVariant &degrees)
651{
652 return QVariant(qRound(degrees.toReal() * 100.0));
653}
654
655QVariant FactMetaData::_centiCelsiusToCelsius(const QVariant &centiCelsius)
656{
657 return QVariant(centiCelsius.toReal() / 100.0);
658}
659
660QVariant FactMetaData::_celsiusToCentiCelsius(const QVariant &celsius)
661{
662 return QVariant(qRound(celsius.toReal() * 100.0));
663}
664
665QVariant FactMetaData::_userGimbalDegreesToMavlinkGimbalDegrees(const QVariant &userGimbalDegrees)
666{
667 // User facing gimbal degree values are from 0 (level) to 90 (straight down)
668 // Mavlink gimbal degree values are from 0 (level) to -90 (straight down)
669 return (userGimbalDegrees.toDouble() * -1.0);
670}
671
672QVariant FactMetaData::_mavlinkGimbalDegreesToUserGimbalDegrees(const QVariant& mavlinkGimbalDegrees)
673{
674 // User facing gimbal degree values are from 0 (level) to 90 (straight down)
675 // Mavlink gimbal degree values are from 0 (level) to -90 (straight down)
676 return (mavlinkGimbalDegrees.toDouble() * -1.0);
677}
678
679QVariant FactMetaData::_metersToFeet(const QVariant &meters)
680{
681 return QVariant((meters.toDouble() * 1.0) / constants.feetToMeters);
682}
683
684QVariant FactMetaData::_feetToMeters(const QVariant &feet)
685{
686 return QVariant(feet.toDouble() * constants.feetToMeters);
687}
688
689QVariant FactMetaData::_squareMetersToSquareKilometers(const QVariant &squareMeters)
690{
691 return QVariant(squareMeters.toDouble() * 0.000001);
692}
693
694QVariant FactMetaData::_squareKilometersToSquareMeters(const QVariant &squareKilometers)
695{
696 return QVariant(squareKilometers.toDouble() * 1000000.0);
697}
698
699QVariant FactMetaData::_squareMetersToHectares(const QVariant &squareMeters)
700{
701 return QVariant(squareMeters.toDouble() * 0.0001);
702}
703
704QVariant FactMetaData::_hectaresToSquareMeters(const QVariant &hectares)
705{
706 return QVariant(hectares.toDouble() * 1000.0);
707}
708
709QVariant FactMetaData::_squareMetersToSquareFeet(const QVariant &squareMeters)
710{
711 return QVariant(squareMeters.toDouble() * constants.squareMetersToSquareFeet);
712}
713
714QVariant FactMetaData::_squareFeetToSquareMeters(const QVariant &squareFeet)
715{
716 return QVariant(squareFeet.toDouble() * constants.feetToSquareMeters);
717}
718
719QVariant FactMetaData::_squareMetersToAcres(const QVariant &squareMeters)
720{
721 return QVariant(squareMeters.toDouble() * constants.squareMetersToAcres);
722}
723
724QVariant FactMetaData::_acresToSquareMeters(const QVariant &acres)
725{
726 return QVariant(acres.toDouble() * constants.acresToSquareMeters);
727}
728
729QVariant FactMetaData::_squareMetersToSquareMiles(const QVariant &squareMeters)
730{
731 return QVariant(squareMeters.toDouble() * constants.squareMetersToSquareMiles);
732}
733
734QVariant FactMetaData::_squareMilesToSquareMeters(const QVariant &squareMiles)
735{
736 return QVariant(squareMiles.toDouble() * constants.squareMilesToSquareMeters);
737}
738
739QVariant FactMetaData::_metersPerSecondToMilesPerHour(const QVariant &metersPerSecond)
740{
741 return QVariant(((metersPerSecond.toDouble() * 1.0) / constants.milesToMeters) * constants.secondsPerHour);
742}
743
744QVariant FactMetaData::_milesPerHourToMetersPerSecond(const QVariant &milesPerHour)
745{
746 return QVariant((milesPerHour.toDouble() * constants.milesToMeters) / constants.secondsPerHour);
747}
748
749QVariant FactMetaData::_metersPerSecondToKilometersPerHour(const QVariant &metersPerSecond)
750{
751 return QVariant((metersPerSecond.toDouble() / 1000.0) * constants.secondsPerHour);
752}
753
754QVariant FactMetaData::_kilometersPerHourToMetersPerSecond(const QVariant &kilometersPerHour)
755{
756 return QVariant((kilometersPerHour.toDouble() * 1000.0) / constants.secondsPerHour);
757}
758
759QVariant FactMetaData::_metersPerSecondToKnots(const QVariant &metersPerSecond)
760{
761 return QVariant((metersPerSecond.toDouble() * constants.secondsPerHour) / (1000.0 * constants.knotsToKPH));
762}
763
764QVariant FactMetaData::_knotsToMetersPerSecond(const QVariant& knots)
765{
766 return QVariant(knots.toDouble() * (1000.0 * constants.knotsToKPH / constants.secondsPerHour));
767}
768
769QVariant FactMetaData::_percentToNorm(const QVariant &percent)
770{
771 return QVariant(percent.toDouble() / 100.0);
772}
773
774QVariant FactMetaData::_normToPercent(const QVariant &normalized)
775{
776 return QVariant(normalized.toDouble() * 100.0);
777}
778
779QVariant FactMetaData::_centimetersToInches(const QVariant &centimeters)
780{
781 return QVariant((centimeters.toDouble() * 1.0) / constants.inchesToCentimeters);
782}
783
784QVariant FactMetaData::_inchesToCentimeters(const QVariant &inches)
785{
786 return QVariant(inches.toDouble() * constants.inchesToCentimeters);
787}
788
789QVariant FactMetaData::_celsiusToFarenheit(const QVariant &celsius)
790{
791 return QVariant((celsius.toDouble() * (9.0 / 5.0)) + 32);
792}
793
794QVariant FactMetaData::_farenheitToCelsius(const QVariant &farenheit)
795{
796 return QVariant((farenheit.toDouble() - 32) * (5.0 / 9.0));
797}
798
799QVariant FactMetaData::_kilogramsToGrams(const QVariant &kg)
800{
801 return QVariant(kg.toDouble() * 1000);
802}
803
804QVariant FactMetaData::_ouncesToGrams(const QVariant &oz)
805{
806 return QVariant(oz.toDouble() * constants.ouncesToGrams);
807}
808
809QVariant FactMetaData::_poundsToGrams(const QVariant &lbs)
810{
811 return QVariant(lbs.toDouble() * constants.poundsToGrams);
812}
813
814QVariant FactMetaData::_gramsToKilograms(const QVariant &g)
815{
816 return QVariant(g.toDouble() / 1000);
817}
818
819QVariant FactMetaData::_gramsToOunces(const QVariant &g)
820{
821 return QVariant(g.toDouble() / constants.ouncesToGrams);
822}
823
824QVariant FactMetaData::_gramsToPunds(const QVariant &g)
825{
826 return QVariant(g.toDouble() / constants.poundsToGrams);
827}
828
829void FactMetaData::setRawUnits(const QString &rawUnits)
830{
831 _rawUnits = rawUnits;
832 _cookedUnits = rawUnits;
833
835}
836
837FactMetaData::ValueType_t FactMetaData::stringToType(const QString &typeString, bool &unknownType)
838{
839 unknownType = false;
840
841 for (size_t i = 0; i < std::size(_rgKnownTypeStrings); i++) {
842 if (typeString.compare(_rgKnownTypeStrings[i], Qt::CaseInsensitive) == 0) {
843 return _rgKnownValueTypes[i];
844 }
845 }
846
847 unknownType = true;
848
849 return valueTypeDouble;
850}
851
853{
854 for (size_t i = 0; i < std::size(_rgKnownTypeStrings); i++) {
855 if (type == _rgKnownValueTypes[i]) {
856 return _rgKnownTypeStrings[i];
857 }
858 }
859
860 return QStringLiteral("UnknownType%1").arg(type);
861}
862
864{
865 switch (type) {
866 case valueTypeUint8:
867 case valueTypeInt8:
868 return 1;
869 case valueTypeUint16:
870 case valueTypeInt16:
871 return 2;
872 case valueTypeUint32:
873 case valueTypeInt32:
874 case valueTypeFloat:
875 return 4;
876 case valueTypeUint64:
877 case valueTypeInt64:
878 case valueTypeDouble:
879 return 8;
880 case valueTypeCustom:
881 return MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN;
882 default:
883 qWarning(FactMetaDataLog) << "Unsupported fact value type" << type;
884 return 0;
885 }
886}
887
888void FactMetaData::_setAppSettingsTranslators()
889{
890 // We can only translate between real numbers
891 if (_enumStrings.isEmpty() && ((type() == valueTypeDouble) || (type() == valueTypeFloat))) {
892 for (size_t i = 0; i < std::size(_rgAppSettingsTranslations); i++) {
893 const AppSettingsTranslation_s *pAppSettingsTranslation = &_rgAppSettingsTranslations[i];
894
895 if (_rawUnits.toLower() != pAppSettingsTranslation->rawUnits.toLower()) {
896 continue;
897 }
898
899 UnitsSettings *const settings = SettingsManager::instance()->unitsSettings();
900 uint settingsUnits = 0;
901
902 switch (pAppSettingsTranslation->unitType) {
903 case UnitHorizontalDistance:
904 settingsUnits = settings->horizontalDistanceUnits()->rawValue().toUInt();
905 break;
906 case UnitVerticalDistance:
907 settingsUnits = settings->verticalDistanceUnits()->rawValue().toUInt();
908 break;
909 case UnitSpeed:
910 settingsUnits = settings->speedUnits()->rawValue().toUInt();
911 break;
912 case UnitArea:
913 settingsUnits = settings->areaUnits()->rawValue().toUInt();
914 break;
915 case UnitTemperature:
916 settingsUnits = settings->temperatureUnits()->rawValue().toUInt();
917 break;
918 case UnitWeight:
919 settingsUnits = settings->weightUnits()->rawValue().toUInt();
920 break;
921 default:
922 break;
923 }
924
925 if (settingsUnits == pAppSettingsTranslation->unitOption) {
926 _cookedUnits = pAppSettingsTranslation->cookedUnits;
927 setTranslators(pAppSettingsTranslation->rawTranslator, pAppSettingsTranslation->cookedTranslator);
928 return;
929 }
930 }
931 }
932}
933
934const FactMetaData::AppSettingsTranslation_s* FactMetaData::_findAppSettingsUnitsTranslation(const QString &rawUnits, UnitTypes type)
935{
936 for (size_t i = 0; i < std::size(_rgAppSettingsTranslations); i++) {
937 const AppSettingsTranslation_s *const pAppSettingsTranslation = &_rgAppSettingsTranslations[i];
938
939 if (rawUnits.toLower() != pAppSettingsTranslation->rawUnits.toLower()) {
940 continue;
941 }
942
943 uint unitOption = 0;
944 UnitsSettings *unitsSettings = SettingsManager::instance()->unitsSettings();
945 switch (type) {
946 case UnitHorizontalDistance:
947 unitOption = unitsSettings->horizontalDistanceUnits()->rawValue().toUInt();
948 break;
949 case UnitVerticalDistance:
950 unitOption = unitsSettings->verticalDistanceUnits()->rawValue().toUInt();
951 break;
952 case UnitArea:
953 unitOption = unitsSettings->areaUnits()->rawValue().toUInt();
954 break;
955 case UnitSpeed:
956 unitOption = unitsSettings->speedUnits()->rawValue().toUInt();
957 break;
958 case UnitTemperature:
959 unitOption = unitsSettings->temperatureUnits()->rawValue().toUInt();
960 break;
961 case UnitWeight:
962 unitOption = unitsSettings->weightUnits()->rawValue().toUInt();
963 break;
964 }
965
966 if ((pAppSettingsTranslation->unitType == type) && (pAppSettingsTranslation->unitOption == unitOption)) {
967 return pAppSettingsTranslation;
968 }
969 }
970
971 return nullptr;
972}
973
975{
976 const AppSettingsTranslation_s *const pAppSettingsTranslation = _findAppSettingsUnitsTranslation("m", UnitHorizontalDistance);
977 if (pAppSettingsTranslation) {
978 return pAppSettingsTranslation->rawTranslator(meters);
979 } else {
980 return meters;
981 }
982}
983
985{
986 const AppSettingsTranslation_s *const pAppSettingsTranslation = _findAppSettingsUnitsTranslation("vertical m", UnitVerticalDistance);
987 if (pAppSettingsTranslation) {
988 return pAppSettingsTranslation->rawTranslator(meters);
989 } else {
990 return meters;
991 }
992}
993
995{
996 const AppSettingsTranslation_s *const pAppSettingsTranslation = _findAppSettingsUnitsTranslation("m", UnitHorizontalDistance);
997 if (pAppSettingsTranslation) {
998 return pAppSettingsTranslation->cookedTranslator(distance);
999 } else {
1000 return distance;
1001 }
1002}
1003
1005{
1006 const AppSettingsTranslation_s *const pAppSettingsTranslation = _findAppSettingsUnitsTranslation("vertical m", UnitVerticalDistance);
1007 if (pAppSettingsTranslation) {
1008 return pAppSettingsTranslation->cookedTranslator(distance);
1009 } else {
1010 return distance;
1011 }
1012}
1013
1015{
1016 const AppSettingsTranslation_s *const pAppSettingsTranslation = _findAppSettingsUnitsTranslation("m", UnitHorizontalDistance);
1017 if (pAppSettingsTranslation) {
1018 return pAppSettingsTranslation->cookedUnits;
1019 } else {
1020 return QStringLiteral("m");
1021 }
1022}
1023
1025{
1026 const AppSettingsTranslation_s *const pAppSettingsTranslation = _findAppSettingsUnitsTranslation("vertical m", UnitVerticalDistance);
1027 if (pAppSettingsTranslation) {
1028 return pAppSettingsTranslation->cookedUnits;
1029 } else {
1030 return QStringLiteral("m");
1031 }
1032}
1033
1035{
1036 const AppSettingsTranslation_s *const pAppSettingsTranslation = _findAppSettingsUnitsTranslation("g", UnitWeight);
1037 if (pAppSettingsTranslation) {
1038 return pAppSettingsTranslation->cookedUnits;
1039 } else {
1040 return QStringLiteral("g");
1041 }
1042}
1043
1044QVariant FactMetaData::squareMetersToAppSettingsAreaUnits(const QVariant &squareMeters)
1045{
1046 const AppSettingsTranslation_s *const pAppSettingsTranslation = _findAppSettingsUnitsTranslation("m^2", UnitArea);
1047 if (pAppSettingsTranslation) {
1048 return pAppSettingsTranslation->rawTranslator(squareMeters);
1049 } else {
1050 return squareMeters;
1051 }
1052}
1053
1055{
1056 const AppSettingsTranslation_s *const pAppSettingsTranslation = _findAppSettingsUnitsTranslation("m^2", UnitArea);
1057 if (pAppSettingsTranslation) {
1058 return pAppSettingsTranslation->cookedTranslator(area);
1059 } else {
1060 return area;
1061 }
1062}
1063
1065{
1066 const AppSettingsTranslation_s *const pAppSettingsTranslation = _findAppSettingsUnitsTranslation("m^2", UnitArea);
1067 if (pAppSettingsTranslation) {
1068 return pAppSettingsTranslation->cookedUnits;
1069 } else {
1070 return QStringLiteral("m^2");
1071 }
1072}
1073
1074QVariant FactMetaData::gramsToAppSettingsWeightUnits(const QVariant &grams) {
1075 const AppSettingsTranslation_s *const pAppSettingsTranslation = _findAppSettingsUnitsTranslation("g", UnitWeight);
1076 if (pAppSettingsTranslation) {
1077 return pAppSettingsTranslation->rawTranslator(grams);
1078 } else {
1079 return grams;
1080 }
1081}
1082
1083QVariant FactMetaData::appSettingsWeightUnitsToGrams(const QVariant &weight) {
1084 const AppSettingsTranslation_s *const pAppSettingsTranslation = _findAppSettingsUnitsTranslation("g", UnitWeight);
1085 if (pAppSettingsTranslation) {
1086 return pAppSettingsTranslation->cookedTranslator(weight);
1087 } else {
1088 return weight;
1089 }
1090}
1091
1092QVariant FactMetaData::metersSecondToAppSettingsSpeedUnits(const QVariant &metersSecond)
1093{
1094 const AppSettingsTranslation_s *const pAppSettingsTranslation = _findAppSettingsUnitsTranslation("m/s", UnitSpeed);
1095 if (pAppSettingsTranslation) {
1096 return pAppSettingsTranslation->rawTranslator(metersSecond);
1097 } else {
1098 return metersSecond;
1099 }
1100}
1101
1103{
1104 const AppSettingsTranslation_s *const pAppSettingsTranslation = _findAppSettingsUnitsTranslation("m/s", UnitSpeed);
1105 if (pAppSettingsTranslation) {
1106 return pAppSettingsTranslation->cookedTranslator(speed);
1107 } else {
1108 return speed;
1109 }
1110}
1111
1113{
1114 const AppSettingsTranslation_s *const pAppSettingsTranslation = _findAppSettingsUnitsTranslation("m/s", UnitSpeed);
1115 if (pAppSettingsTranslation) {
1116 return pAppSettingsTranslation->cookedUnits;
1117 } else {
1118 return QStringLiteral("m/s");
1119 }
1120}
1121
1123{
1124 return _rawTranslator(this->rawIncrement()).toDouble();
1125}
1126
1128{
1129 int actualDecimalPlaces = kDefaultDecimalPlaces;
1130 int incrementDecimalPlaces = kUnknownDecimalPlaces;
1131
1132 // First determine decimal places from increment
1133 double increment = _rawTranslator(this->rawIncrement()).toDouble();
1134 if (!qIsNaN(increment)) {
1135 double integralPart;
1136
1137 // Get the fractional part only
1138 increment = fabs(modf(increment, &integralPart));
1139 if (increment == 0.0) {
1140 // No fractional part, so no decimal places
1141 incrementDecimalPlaces = 0;
1142 } else {
1143 incrementDecimalPlaces = -ceil(log10(increment));
1144 }
1145 }
1146
1147 if (_decimalPlaces == kUnknownDecimalPlaces) {
1148 if (incrementDecimalPlaces != kUnknownDecimalPlaces) {
1149 actualDecimalPlaces = incrementDecimalPlaces;
1150 } else {
1151 // Adjust decimal places for cooked translation
1152 int settingsDecimalPlaces = (_decimalPlaces == kUnknownDecimalPlaces) ? kDefaultDecimalPlaces : _decimalPlaces;
1153 const double ctest = _rawTranslator(1.0).toDouble();
1154
1155 settingsDecimalPlaces += -log10(ctest);
1156
1157 settingsDecimalPlaces = qMin(25, settingsDecimalPlaces);
1158 settingsDecimalPlaces = qMax(0, settingsDecimalPlaces);
1159
1160 actualDecimalPlaces = settingsDecimalPlaces;
1161 }
1162 } else {
1163 actualDecimalPlaces = _decimalPlaces;
1164 }
1165
1166 return actualDecimalPlaces;
1167}
1168
1169FactMetaData *FactMetaData::createFromJsonObject(const QJsonObject &json, const QMap<QString, QString> &defineMap, QObject *metaDataParent)
1170{
1171 QString errorString;
1172
1173 static const QList<JsonHelper::KeyValidateInfo> keyInfoList = {
1174 { _nameJsonKey, QJsonValue::String, true },
1175 { _typeJsonKey, QJsonValue::String, true },
1176 { _shortDescriptionJsonKey, QJsonValue::String, false },
1177 { _longDescriptionJsonKey, QJsonValue::String, false },
1178 { _unitsJsonKey, QJsonValue::String, false },
1179 { _decimalPlacesJsonKey, QJsonValue::Double, false },
1180 { _minJsonKey, QJsonValue::Double, false },
1181 { _maxJsonKey, QJsonValue::Double, false },
1182 { _userMinJsonKey, QJsonValue::Double, false },
1183 { _userMaxJsonKey, QJsonValue::Double, false },
1184 { _hasControlJsonKey, QJsonValue::Bool, false },
1185 { _qgcRebootRequiredJsonKey, QJsonValue::Bool, false },
1186 { _rebootRequiredJsonKey, QJsonValue::Bool, false },
1187 { _categoryJsonKey, QJsonValue::String, false },
1188 { _groupJsonKey, QJsonValue::String, false },
1189 { _volatileJsonKey, QJsonValue::Bool, false },
1190 { _enumBitmaskArrayJsonKey, QJsonValue::Array, false },
1191 { _enumValuesArrayJsonKey, QJsonValue::Array, false },
1192 { _enumValuesJsonKey, QJsonValue::String, false },
1193 { _enumStringsJsonKey, QJsonValue::String, false },
1194 };
1195
1196 if (!JsonHelper::validateKeys(json, keyInfoList, errorString)) {
1197 qWarning(FactMetaDataLog) << errorString;
1198 return new FactMetaData(valueTypeUint32, metaDataParent);
1199 }
1200
1201 bool unknownType;
1202 const FactMetaData::ValueType_t type = FactMetaData::stringToType(json[_typeJsonKey].toString(), unknownType);
1203 if (unknownType) {
1204 qWarning(FactMetaDataLog) << "Unknown type" << json[_typeJsonKey].toString();
1205 return new FactMetaData(valueTypeUint32, metaDataParent);
1206 }
1207
1208 FactMetaData *const metaData = new FactMetaData(type, metaDataParent);
1209
1210 metaData->_name = json[_nameJsonKey].toString();
1211
1212 QStringList rgDescriptions;
1213 QList<double> rgDoubleValues;
1214 QList<int> rgIntValues;
1215 QStringList rgStringValues;
1216
1217 bool foundBitmask = false;
1218 if (!_parseValuesArray(json, rgDescriptions, rgDoubleValues, errorString)) {
1219 qWarning(FactMetaDataLog) << QStringLiteral("FactMetaData::createFromJsonObject _parseValueDescriptionArray for '%1' failed. %2").arg(metaData->name(), errorString);
1220 }
1221 if (rgDescriptions.isEmpty()) {
1222 if (!_parseBitmaskArray(json, rgDescriptions, rgIntValues, errorString)) {
1223 qWarning(FactMetaDataLog) << QStringLiteral("FactMetaData::createFromJsonObject _parseBitmaskArray for '%1' failed. %2").arg(metaData->name(), errorString);
1224 }
1225 foundBitmask = rgDescriptions.count() != 0;
1226 }
1227 if (rgDescriptions.isEmpty()) {
1228 if (!_parseEnum(metaData->_name, json, defineMap, rgDescriptions, rgStringValues, errorString)) {
1229 qWarning(FactMetaDataLog) << QStringLiteral("FactMetaData::createFromJsonObject _parseEnum for '%1' failed. %2").arg(metaData->name(), errorString);
1230 }
1231 }
1232
1233 if (errorString.isEmpty() && !rgDescriptions.isEmpty()) {
1234 for (qsizetype i = 0; i < rgDescriptions.count(); i++) {
1235 if (foundBitmask) {
1236 metaData->addBitmaskInfo(rgDescriptions[i], 1 << rgIntValues[i]);
1237 } else {
1238 const QVariant rawValueVariant = !rgDoubleValues.isEmpty() ? QVariant(rgDoubleValues[i]) : QVariant(rgStringValues[i]);
1239 QVariant convertedValueVariant;
1240 QString enumErrorString;
1241 if (metaData->convertAndValidateRaw(rawValueVariant, false /* validate */, convertedValueVariant, enumErrorString)) {
1242 metaData->addEnumInfo(rgDescriptions[i], convertedValueVariant);
1243 } else {
1244 qWarning(FactMetaDataLog) << QStringLiteral("FactMetaData::createFromJsonObject convertAndValidateRaw on enum value for %1 failed.").arg(metaData->name())
1245 << "type:" << metaData->type()
1246 << "value:" << rawValueVariant
1247 << "error:" << enumErrorString;
1248 }
1249 }
1250 }
1251 }
1252
1253 metaData->setDecimalPlaces(json[_decimalPlacesJsonKey].toInt(kUnknownDecimalPlaces));
1254 metaData->setShortDescription(json[_shortDescriptionJsonKey].toString());
1255 metaData->setLongDescription(json[_longDescriptionJsonKey].toString());
1256
1257 if (json.contains(_unitsJsonKey)) {
1258 metaData->setRawUnits(json[_unitsJsonKey].toString());
1259 }
1260
1261 QString defaultValueJsonKey = _defaultValueJsonKey;
1262#if defined(Q_OS_ANDROID) || defined(Q_OS_IOS)
1263 if (json.contains(_mobileDefaultValueJsonKey)) {
1264 defaultValueJsonKey = _mobileDefaultValueJsonKey;
1265 }
1266#endif
1267
1268 if (json.contains(defaultValueJsonKey)) {
1269 const QJsonValue jsonValue = json[defaultValueJsonKey];
1270
1271 if ((jsonValue.type() == QJsonValue::Null) && (type == valueTypeFloat || type == valueTypeDouble)) {
1272 metaData->setRawDefaultValue((type == valueTypeFloat) ? std::numeric_limits<float>::quiet_NaN() : std::numeric_limits<double>::quiet_NaN());
1273 } else {
1274 QVariant typedValue;
1275 QString defaultValueErrorString;
1276 const QVariant initialValue = jsonValue.toVariant();
1277
1278 if (metaData->convertAndValidateRaw(initialValue, true /* convertOnly */, typedValue, defaultValueErrorString)) {
1279 metaData->setRawDefaultValue(typedValue);
1280 } else {
1281 qWarning(FactMetaDataLog) << "Invalid default value,"
1282 << "name:" << metaData->name()
1283 << "type:" << metaData->type()
1284 << "value:" << initialValue
1285 << "error:" << defaultValueErrorString;
1286 }
1287 }
1288 }
1289
1290 if (json.contains(_incrementJsonKey)) {
1291 QVariant typedValue;
1292 QString incrementErrorString;
1293 const QVariant initialValue = json[_incrementJsonKey].toVariant();
1294 if (metaData->convertAndValidateRaw(initialValue, true /* convertOnly */, typedValue, incrementErrorString)) {
1295 metaData->setRawIncrement(typedValue.toDouble());
1296 } else {
1297 qWarning(FactMetaDataLog) << "Invalid increment value,"
1298 << "name:" << metaData->name()
1299 << "type:" << metaData->type()
1300 << "value:" << initialValue
1301 << "error:" << incrementErrorString;
1302 }
1303 }
1304
1305 if (json.contains(_minJsonKey)) {
1306 QVariant typedValue;
1307 QString minErrorString;
1308 const QVariant initialValue = json[_minJsonKey].toVariant();
1309 if (metaData->convertAndValidateRaw(initialValue, true /* convertOnly */, typedValue, minErrorString)) {
1310 metaData->setRawMin(typedValue);
1311 } else {
1312 qWarning(FactMetaDataLog) << "Invalid min value,"
1313 << "name:" << metaData->name()
1314 << "type:" << metaData->type()
1315 << "value:" << initialValue
1316 << "error:" << minErrorString;
1317 }
1318 }
1319
1320 if (json.contains(_maxJsonKey)) {
1321 QVariant typedValue;
1322 QString maxErrorString;
1323 const QVariant initialValue = json[_maxJsonKey].toVariant();
1324 if (metaData->convertAndValidateRaw(initialValue, true /* convertOnly */, typedValue, maxErrorString)) {
1325 metaData->setRawMax(typedValue);
1326 } else {
1327 qWarning(FactMetaDataLog) << "Invalid max value,"
1328 << "name:" << metaData->name()
1329 << "type:" << metaData->type()
1330 << "value:" << initialValue
1331 << "error:" << maxErrorString;
1332 }
1333 }
1334
1335 // If userMin/Max not specified, we leave at invalid so the ui can decide what to do
1336
1337 if (json.contains(_userMinJsonKey)) {
1338 QVariant typedValue;
1339 QString userMinErrorString;
1340 const QVariant initialValue = json[_userMinJsonKey].toVariant();
1341 if (metaData->convertAndValidateRaw(initialValue, true /* convertOnly */, typedValue, userMinErrorString)) {
1342 metaData->setRawUserMin(typedValue);
1343 } else {
1344 qWarning(FactMetaDataLog) << "Invalid userMin value,"
1345 << "name:" << metaData->name()
1346 << "type:" << metaData->type()
1347 << "value:" << initialValue
1348 << "error:" << userMinErrorString;
1349 }
1350 }
1351
1352 if (json.contains(_userMaxJsonKey)) {
1353 QVariant typedValue;
1354 QString userMaxErrorString;
1355 const QVariant initialValue = json[_userMaxJsonKey].toVariant();
1356 if (metaData->convertAndValidateRaw(initialValue, true /* convertOnly */, typedValue, userMaxErrorString)) {
1357 metaData->setRawUserMax(typedValue);
1358 } else {
1359 qWarning(FactMetaDataLog) << "Invalid userMax value,"
1360 << "name:" << metaData->name()
1361 << "type:" << metaData->type()
1362 << "value:" << initialValue
1363 << "error:" << userMaxErrorString;
1364 }
1365 }
1366
1367 bool hasControlJsonKey = true;
1368 if (json.contains(_hasControlJsonKey)) {
1369 hasControlJsonKey = json[_hasControlJsonKey].toBool();
1370 }
1371 metaData->setHasControl(hasControlJsonKey);
1372
1373 bool qgcRebootRequired = false;
1374 if (json.contains(_qgcRebootRequiredJsonKey)) {
1375 qgcRebootRequired = json[_qgcRebootRequiredJsonKey].toBool();
1376 }
1378
1379 bool rebootRequired = false;
1380 if (json.contains(_rebootRequiredJsonKey)) {
1381 rebootRequired = json[_rebootRequiredJsonKey].toBool();
1382 }
1383 metaData->setVehicleRebootRequired(rebootRequired);
1384
1385 bool volatileValue = false;
1386 if (json.contains(_volatileJsonKey)) {
1387 volatileValue = json[_volatileJsonKey].toBool();
1388 }
1390
1391 if (json.contains(_groupJsonKey)) {
1392 metaData->setGroup(json[_groupJsonKey].toString());
1393 }
1394
1395 if (json.contains(_categoryJsonKey)) {
1396 metaData->setCategory(json[_categoryJsonKey].toString());
1397 }
1398
1399 return metaData;
1400}
1401
1402void FactMetaData::_loadJsonDefines(const QJsonObject &jsonDefinesObject, QMap<QString, QString> &defineMap)
1403{
1404 for (const QString &defineName: jsonDefinesObject.keys()) {
1405 const QString mapKey = _jsonMetaDataDefinesName + QStringLiteral(".") + defineName;
1406 defineMap[mapKey] = jsonDefinesObject[defineName].toString();
1407 }
1408}
1409
1410QMap<QString, FactMetaData*> FactMetaData::createMapFromJsonFile(const QString &jsonFilename, QObject *metaDataParent)
1411{
1412 QMap<QString, FactMetaData*> metaDataMap;
1413
1414 QString errorString;
1415 int version;
1416 const QJsonObject jsonObject = JsonHelper::openInternalQGCJsonFile(jsonFilename, qgcFileType, 1, 1, version, errorString);
1417 if (!errorString.isEmpty()) {
1418 qWarning(FactMetaDataLog) << "Internal Error:" << errorString;
1419 return metaDataMap;
1420 }
1421
1422 static const QList<JsonHelper::KeyValidateInfo> keyInfoList = {
1423 { FactMetaData::_jsonMetaDataDefinesName, QJsonValue::Object, false },
1424 { FactMetaData::_jsonMetaDataFactsName, QJsonValue::Array, true },
1425 };
1426 if (!JsonHelper::validateKeys(jsonObject, keyInfoList, errorString)) {
1427 qWarning(FactMetaDataLog) << "Json document incorrect format:" << errorString;
1428 return metaDataMap;
1429 }
1430
1431 QMap<QString /* define name */, QString /* define value */> defineMap;
1432 _loadJsonDefines(jsonObject[FactMetaData::_jsonMetaDataDefinesName].toObject(), defineMap);
1433 const QJsonArray factArray = jsonObject[FactMetaData::_jsonMetaDataFactsName].toArray();
1434
1435 return createMapFromJsonArray(factArray, defineMap, metaDataParent);
1436}
1437
1438QMap<QString, FactMetaData*> FactMetaData::createMapFromJsonArray(const QJsonArray &jsonArray, const QMap<QString, QString> &defineMap, QObject *metaDataParent)
1439{
1440 QMap<QString, FactMetaData*> metaDataMap;
1441 for (const QJsonValue &jsonValue : jsonArray) {
1442 if (!jsonValue.isObject()) {
1443 qWarning(FactMetaDataLog) << "JsonValue is not an object";
1444 continue;
1445 }
1446
1447 const QJsonObject jsonObject = jsonValue.toObject();
1448 FactMetaData *const metaData = createFromJsonObject(jsonObject, defineMap, metaDataParent);
1449 if (metaDataMap.contains(metaData->name())) {
1450 qWarning(FactMetaDataLog) << "Duplicate fact name:" << metaData->name();
1451 delete metaData;
1452 } else {
1453 metaDataMap[metaData->name()] = metaData;
1454 }
1455 }
1456
1457 return metaDataMap;
1458}
1459
1461{
1462 // We have to be careful with cooked min/max. Running the raw values through the translator could flip min and max.
1463 return qMax(_rawTranslator(_rawMax).toDouble(), _rawTranslator(_rawMin).toDouble());
1464}
1465
1467{
1468 // We have to be careful with cooked min/max. Running the raw values through the translator could flip min and max.
1469 return qMin(_rawTranslator(_rawMax).toDouble(), _rawTranslator(_rawMin).toDouble());
1470}
1471
1473{
1474 _volatile = bValue;
1475 if (_volatile) {
1476 _readOnly = true;
1477 }
1478}
1479
1480QStringList FactMetaData::splitTranslatedList(const QString &translatedList)
1481{
1482 const QRegularExpression splitRegex("[,,、]"); // Note chinese commas for translations which have modified the english comma
1483 QStringList valueList = translatedList.split(splitRegex, Qt::SkipEmptyParts);
1484 for (QString &value: valueList) {
1485 value = value.trimmed();
1486 }
1487 return valueList;
1488}
1489
1490bool FactMetaData::_parseEnum(const QString& name, const QJsonObject &jsonObject, const DefineMap_t &defineMap, QStringList &rgDescriptions, QStringList &rgValues, QString &errorString)
1491{
1492 rgDescriptions.clear();
1493 rgValues.clear();
1494 errorString.clear();
1495
1496 if (!jsonObject.contains(_enumStringsJsonKey)) {
1497 return true;
1498 }
1499
1500 const QString jsonStrings = jsonObject.value(_enumStringsJsonKey).toString();
1501 const QString defineMapStrings = defineMap.value(jsonStrings, jsonStrings);
1502 rgDescriptions = splitTranslatedList(defineMapStrings);
1503
1504 const QString jsonValues = jsonObject.value(_enumValuesJsonKey).toString();
1505 const QString defineMapValues = defineMap.value(jsonValues, jsonValues);
1506 rgValues = splitTranslatedList(defineMapValues); // Never translated but still useful to use common string splitting code
1507
1508 if (rgDescriptions.count() != rgValues.count()) {
1509 errorString = QStringLiteral("Enum strings/values count mismatch - name: '%1' strings: '%2'[%3] values: '%4'[%5]").arg(name).arg(defineMapStrings).arg(rgDescriptions.count()).arg(defineMapValues).arg(rgValues.count());
1510 return false;
1511 }
1512
1513 return true;
1514}
1515
1516bool FactMetaData::_parseValuesArray(const QJsonObject &jsonObject, QStringList &rgDescriptions, QList<double> &rgValues, QString &errorString)
1517{
1518 rgDescriptions.clear();
1519 rgValues.clear();
1520 errorString.clear();
1521
1522 if (!jsonObject.contains(_enumValuesArrayJsonKey)) {
1523 return true;
1524 }
1525
1526 static const QList<JsonHelper::KeyValidateInfo> keyInfoList = {
1527 { _enumValuesArrayDescriptionJsonKey, QJsonValue::String, true },
1528 { _enumValuesArrayValueJsonKey, QJsonValue::Double, true },
1529 };
1530
1531 const QJsonArray &rgValueDescription = jsonObject[_enumValuesArrayJsonKey].toArray();
1532 for (const QJsonValue& jsonValue : rgValueDescription) {
1533 if (jsonValue.type() != QJsonValue::Object) {
1534 errorString = QStringLiteral("Value in \"values\" array is not an object.");
1535 return false;
1536 }
1537
1538 const QJsonObject &valueDescriptionObject = jsonValue.toObject();
1539 if (!JsonHelper::validateKeys(valueDescriptionObject, keyInfoList, errorString)) {
1540 errorString = QStringLiteral("Object in \"values\" array failed validation '%2'.").arg(errorString);
1541 return false;
1542 }
1543
1544 rgDescriptions.append(valueDescriptionObject[_enumValuesArrayDescriptionJsonKey].toString());
1545 rgValues.append(valueDescriptionObject[_enumValuesArrayValueJsonKey].toDouble());
1546 }
1547
1548 return true;
1549}
1550
1551bool FactMetaData::_parseBitmaskArray(const QJsonObject &jsonObject, QStringList &rgDescriptions, QList<int> &rgValues, QString &errorString)
1552{
1553 rgDescriptions.clear();
1554 rgValues.clear();
1555 errorString.clear();
1556
1557 if (!jsonObject.contains(_enumBitmaskArrayJsonKey)) {
1558 return true;
1559 }
1560
1561 static const QList<JsonHelper::KeyValidateInfo> keyInfoList = {
1562 { _enumBitmaskArrayDescriptionJsonKey, QJsonValue::String, true },
1563 { _enumBitmaskArrayIndexJsonKey, QJsonValue::Double, true },
1564 };
1565
1566 const QJsonArray &rgValueDescription = jsonObject[_enumBitmaskArrayJsonKey].toArray();
1567 for (const QJsonValue &jsonValue : rgValueDescription) {
1568 if (jsonValue.type() != QJsonValue::Object) {
1569 errorString = QStringLiteral("Value in \"values\" array is not an object.");
1570 return false;
1571 }
1572
1573 const QJsonObject &valueDescriptionObject = jsonValue.toObject();
1574 if (!JsonHelper::validateKeys(valueDescriptionObject, keyInfoList, errorString)) {
1575 errorString = QStringLiteral("Object in \"values\" array failed validation '%2'.").arg(errorString);
1576 return false;
1577 }
1578
1579 rgDescriptions.append(valueDescriptionObject[_enumBitmaskArrayDescriptionJsonKey].toString());
1580 rgValues.append(valueDescriptionObject[_enumBitmaskArrayIndexJsonKey].toInt());
1581 }
1582
1583 return true;
1584}
1585
1587{
1588 if (!_rawUserMin.isValid()) {
1589 return QVariant();
1590 }
1591
1592 return _rawTranslator(_rawUserMin);
1593}
1594
1596{
1597 if (!_rawUserMax.isValid()) {
1598 return QVariant();
1599 }
1600
1601 return _rawTranslator(_rawUserMax);
1602}
QString errorString
#define QGC_LOGGING_CATEGORY(name, categoryStr)
static FactMetaData * createFromJsonObject(const QJsonObject &json, const QMap< QString, QString > &defineMap, QObject *metaDataParent)
void setRawUnits(const QString &rawUnits)
void setDecimalPlaces(int decimalPlaces)
void setHasControl(bool bValue)
static constexpr const char * qgcFileType
void setRawUserMin(const QVariant &rawUserMin)
static QVariant appSettingsAreaUnitsToSquareMeters(const QVariant &area)
Converts from user specified distance unit to meters.
static QVariant metersToAppSettingsVerticalDistanceUnits(const QVariant &meters)
Converts from meters to the user specified vertical distance unit.
void setShortDescription(const QString &shortDescription)
QVariant cookedMin() const
static QVariant metersToAppSettingsHorizontalDistanceUnits(const QVariant &meters)
Converts from meters to the user specified horizontal distance unit.
static QVariant metersSecondToAppSettingsSpeedUnits(const QVariant &metersSecond)
Converts from meters/second to the user specified speed unit.
bool clampValue(const QVariant &cookedValue, QVariant &typedValue) const
bool qgcRebootRequired() const
bool convertAndValidateCooked(const QVariant &cookedValue, bool convertOnly, QVariant &typedValue, QString &errorString) const
Same as convertAndValidateRaw except for cookedValue input.
QVariant cookedUserMax() const
void setQGCRebootRequired(bool rebootRequired)
static size_t typeToSize(ValueType_t type)
QVariant cookedMax() const
static QStringList splitTranslatedList(const QString &translatedList)
static QString typeToString(ValueType_t type)
static QMap< QString, FactMetaData * > createMapFromJsonFile(const QString &jsonFilename, QObject *metaDataParent)
QVariant rawMin() const
@ valueTypeElapsedTimeInSeconds
void addBitmaskInfo(const QString &name, const QVariant &value)
Used to add new values to the bitmask lists after the meta data has been loaded.
void setLongDescription(const QString &longDescription)
static QMap< QString, FactMetaData * > createMapFromJsonArray(const QJsonArray &jsonArray, const DefineMap_t &defineMap, QObject *metaDataParent)
static QString appSettingsVerticalDistanceUnitsString()
Returns the string for vertical distance units which has configued by user.
void setRawUserMax(const QVariant &rawUserMax)
static constexpr int kUnknownDecimalPlaces
Number of decimal places to specify is not known.
int decimalPlaces() const
void setVehicleRebootRequired(bool rebootRequired)
static constexpr int kDefaultDecimalPlaces
Default value for decimal places if not specified/known.
static QString appSettingsWeightUnitsString()
Returns the string for weight units which has configued by user.
void setTranslators(Translator rawTranslator_, Translator cookedTranslator_)
void setRawMin(const QVariant &rawMin)
QVariant cookedUserMin() const
QVariant rawUserMin() const
void setCategory(const QString &category)
bool convertAndValidateRaw(const QVariant &rawValue, bool convertOnly, QVariant &typedValue, QString &errorString) const
QString rawUnits() const
QVariant rawUserMax() const
FactMetaData(QObject *parent=nullptr)
static QString appSettingsAreaUnitsString()
Returns the string for distance units which has configued by user.
static QVariant maxForType(ValueType_t type)
void setRawDefaultValue(const QVariant &rawDefaultValue)
static QVariant gramsToAppSettingsWeightUnits(const QVariant &grams)
Converts from grams to the user specified weight unit.
static QString appSettingsHorizontalDistanceUnitsString()
Returns the string for horizontal distance units which has configued by user.
double rawIncrement() const
void setEnumInfo(const QStringList &strings, const QVariantList &values)
void setBitmaskInfo(const QStringList &strings, const QVariantList &values)
void setRawMax(const QVariant &rawMax)
static QVariant squareMetersToAppSettingsAreaUnits(const QVariant &squareMeters)
Converts from meters to the user specified distance unit.
void removeEnumInfo(const QVariant &value)
Used to remove values from the enum lists after the meta data has been loaded.
static QVariant minForType(ValueType_t type)
static QVariant appSettingsVerticalDistanceUnitsToMeters(const QVariant &distance)
Converts from user specified vertical distance unit to meters.
void setRawIncrement(double increment)
void addEnumInfo(const QString &name, const QVariant &value)
Used to add new values to the enum lists after the meta data has been loaded.
void setVolatileValue(bool bValue)
QString name() const
static QVariant appSettingsHorizontalDistanceUnitsToMeters(const QVariant &distance)
Converts from user specified horizontal distance unit to meters.
const FactMetaData & operator=(const FactMetaData &other)
void setGroup(const QString &group)
QVariant rawDefaultValue() const
ValueType_t type() const
static ValueType_t stringToType(const QString &typeString, bool &unknownType)
static QVariant appSettingsSpeedUnitsToMetersSecond(const QVariant &speed)
Converts from user specified speed unit to meters/second.
static QVariant appSettingsWeightUnitsToGrams(const QVariant &weight)
Converts from user specified weight unit to grams.
bool volatileValue() const
QVariant rawMax() const
double cookedIncrement() const
void setBuiltInTranslator()
Set the translators to the standard built in versions.
static QString appSettingsSpeedUnitsString()
Returns the string for speed units which has configued by user.
@ VerticalDistanceUnitsMeters
Fact *weightUnits READ weightUnits CONSTANT Fact * weightUnits()
Fact *speedUnits READ speedUnits CONSTANT Fact * speedUnits()
@ SpeedUnitsKilometersPerHour
Fact *horizontalDistanceUnits READ horizontalDistanceUnits CONSTANT Fact * horizontalDistanceUnits()
Fact *temperatureUnits READ temperatureUnits CONSTANT Fact * temperatureUnits()
@ HorizontalDistanceUnitsFeet
@ HorizontalDistanceUnitsMeters
Fact *verticalDistanceUnits READ verticalDistanceUnits CONSTANT Fact * verticalDistanceUnits()
Fact *areaUnits READ areaUnits CONSTANT Fact * areaUnits()
QJsonObject openInternalQGCJsonFile(const QString &jsonFilename, const QString &expectedFileType, int minSupportedVersion, int maxSupportedVersion, int &version, QString &errorString)
returned error string if validation fails
bool validateKeys(const QJsonObject &jsonObject, const QList< KeyValidateInfo > &keyInfo, QString &errorString)