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