8#include <QtCore/QJsonArray>
9#include <QtCore/QJsonObject>
10#include <QtCore/QtMath>
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 },
25const FactMetaData::AppSettingsTranslation_s FactMetaData::_rgAppSettingsTranslations[] = {
43 {
"m^2",
"ac", FactMetaData::UnitArea,
UnitsSettings::AreaUnitsAcres, FactMetaData::_squareMetersToAcres, FactMetaData::_acresToSquareMeters },
48 {
"m/s",
"kn", FactMetaData::UnitSpeed,
UnitsSettings::SpeedUnitsKnots, FactMetaData::_metersPerSecondToKnots, FactMetaData::_knotsToMetersPerSecond },
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;
106 _shortDescription = other._shortDescription;
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;
125 if (_defaultValueAvailable) {
126 return _rawDefaultValue;
128 qWarning(FactMetaDataLog) <<
"Attempt to access unavailable default value";
137 _defaultValueAvailable =
true;
139 qWarning(FactMetaDataLog) <<
"Attempt to set default value which is outside min/max range. Name:" <<
name()
141 <<
", type:" <<
type()
142 <<
", min:" << _rawMin
143 <<
", max:" << _rawMax;
149 if (isInRawMinLimit(
rawMin)) {
151 if (_rawUserMin.isValid() && !isInRawMinLimit(_rawUserMin)) {
152 _rawUserMin = _rawMin;
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;
166 if (isInRawMaxLimit(
rawMax)) {
168 if (_rawUserMax.isValid() && !isInRawMaxLimit(_rawUserMax)) {
169 _rawUserMax = _rawMax;
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;
186 qWarning(FactMetaDataLog) <<
"Attempt to set user min below allowable value for fact:" <<
name()
188 <<
", type:" <<
type()
189 <<
", min:" << _rawMin;
190 _rawUserMin = _rawMin;
199 qWarning(FactMetaDataLog) <<
"Attempt to set user max above allowable value for fact:" <<
name()
201 <<
", type:" <<
type()
202 <<
", max:" << _rawMax;
203 _rawUserMax = _rawMax;
207bool FactMetaData::isInRawMinLimit(
const QVariant &variantValue)
const
211 return (_rawMin.value<
unsigned char>() <= variantValue.value<
unsigned char>());
213 return (_rawMin.value<
signed char>() <= variantValue.value<
signed char>());
215 return (_rawMin.value<
unsigned short int>() <= variantValue.value<
unsigned short int>());
217 return (_rawMin.value<
short int>() <= variantValue.value<
short int>());
219 return (_rawMin.value<uint32_t>() <= variantValue.value<uint32_t>());
221 return (_rawMin.value<int32_t>() <= variantValue.value<int32_t>());
223 return (_rawMin.value<uint64_t>() <= variantValue.value<uint64_t>());
225 return (_rawMin.value<int64_t>() <= variantValue.value<int64_t>());
227 return ((qIsNaN(variantValue.toFloat())) || (_rawMin.value<
float>() <= variantValue.value<
float>()));
229 return ((qIsNaN(variantValue.toDouble())) || (_rawMin.value<
double>() <= variantValue.value<
double>()));
235bool FactMetaData::isInRawMaxLimit(
const QVariant &variantValue)
const
239 return (_rawMax.value<
unsigned char>() >= variantValue.value<
unsigned char>());
241 return (_rawMax.value<
signed char>() >= variantValue.value<
signed char>());
243 return (_rawMax.value<
unsigned short int>() >= variantValue.value<
unsigned short int>());
245 return (_rawMax.value<
short int>() >= variantValue.value<
short int>());
247 return (_rawMax.value<uint32_t>() >= variantValue.value<uint32_t>());
249 return (_rawMax.value<int32_t>() >= variantValue.value<int32_t>());
251 return (_rawMax.value<uint64_t>() >= variantValue.value<uint64_t>());
253 return (_rawMax.value<int64_t>() >= variantValue.value<int64_t>());
255 return (qIsNaN(variantValue.toFloat()) || (_rawMax.value<
float>() >= variantValue.value<
float>()));
257 return (qIsNaN(variantValue.toDouble()) || (_rawMax.value<
double>() >= variantValue.value<
double>()));
267 return QVariant(std::numeric_limits<unsigned char>::min());
269 return QVariant(std::numeric_limits<signed char>::min());
271 return QVariant(std::numeric_limits<unsigned short int>::min());
273 return QVariant(std::numeric_limits<short int>::min());
275 return QVariant(std::numeric_limits<uint32_t>::min());
277 return QVariant(std::numeric_limits<int32_t>::min());
279 return QVariant((qulonglong)std::numeric_limits<uint64_t>::min());
281 return QVariant((qlonglong)std::numeric_limits<int64_t>::min());
283 return QVariant(-std::numeric_limits<float>::max());
285 return QVariant(-std::numeric_limits<double>::max());
291 return QVariant(0.0);
302 return QVariant(std::numeric_limits<unsigned char>::max());
304 return QVariant(std::numeric_limits<signed char>::max());
306 return QVariant(std::numeric_limits<unsigned short int>::max());
308 return QVariant(std::numeric_limits<short int>::max());
310 return QVariant(std::numeric_limits<uint32_t>::max());
312 return QVariant(std::numeric_limits<int32_t>::max());
314 return QVariant((qulonglong)std::numeric_limits<uint64_t>::max());
316 return QVariant((qlonglong)std::numeric_limits<int64_t>::max());
318 return QVariant(std::numeric_limits<float>::max());
321 return QVariant(std::numeric_limits<double>::max());
334 bool convertOk =
false;
342 typedValue = QVariant(rawValue.toInt(&convertOk));
343 if (!convertOnly && convertOk) {
344 if (!isInRawLimit<int32_t>(typedValue)) {
350 typedValue = QVariant(rawValue.toLongLong(&convertOk));
351 if (!convertOnly && convertOk) {
352 if (!isInRawLimit<int64_t>(typedValue)) {
360 typedValue = QVariant(rawValue.toUInt(&convertOk));
361 if (!convertOnly && convertOk) {
362 if (!isInRawLimit<uint32_t>(typedValue)) {
368 typedValue = QVariant(rawValue.toULongLong(&convertOk));
369 if (!convertOnly && convertOk) {
370 if (!isInRawLimit<uint64_t>(typedValue)) {
376 typedValue = QVariant(rawValue.toFloat(&convertOk));
377 if (!convertOnly && convertOk) {
378 if (!isInRawLimit<float>(typedValue)) {
385 typedValue = QVariant(rawValue.toDouble(&convertOk));
386 if (!convertOnly && convertOk) {
387 if (!isInRawLimit<double>(typedValue)) {
394 typedValue = QVariant(rawValue.toString());
398 typedValue = QVariant(rawValue.toBool());
402 typedValue = QVariant(rawValue.toByteArray());
415 bool convertOk =
false;
419 if (!convertOnly && _customCookedValidator) {
430 typedValue = QVariant(cookedValue.toInt(&convertOk));
431 if (!convertOnly && convertOk) {
432 if (!isInCookedLimit<int32_t>(typedValue)) {
438 typedValue = QVariant(cookedValue.toLongLong(&convertOk));
439 if (!convertOnly && convertOk) {
440 if (!isInCookedLimit<int64_t>(typedValue)) {
448 typedValue = QVariant(cookedValue.toUInt(&convertOk));
449 if (!convertOnly && convertOk) {
450 if (!isInCookedLimit<uint32_t>(typedValue)) {
456 typedValue = QVariant(cookedValue.toULongLong(&convertOk));
457 if (!convertOnly && convertOk) {
458 if (!isInCookedLimit<uint64_t>(typedValue)) {
464 typedValue = QVariant(cookedValue.toFloat(&convertOk));
465 if (!convertOnly && convertOk) {
466 if (!isInCookedLimit<float>(typedValue)) {
473 typedValue = QVariant(cookedValue.toDouble(&convertOk));
474 if (!convertOnly && convertOk) {
475 if (!isInCookedLimit<double>(typedValue)) {
482 typedValue = QVariant(cookedValue.toString());
486 typedValue = QVariant(cookedValue.toBool());
490 typedValue = QVariant(cookedValue.toByteArray());
503 bool convertOk =
false;
509 typedValue = QVariant(cookedValue.toInt(&convertOk));
511 clamp<int32_t>(typedValue);
515 typedValue = QVariant(cookedValue.toLongLong(&convertOk));
517 clamp<int64_t>(typedValue);
523 typedValue = QVariant(cookedValue.toUInt(&convertOk));
525 clamp<uint32_t>(typedValue);
529 typedValue = QVariant(cookedValue.toULongLong(&convertOk));
531 clamp<uint64_t>(typedValue);
535 typedValue = QVariant(cookedValue.toFloat(&convertOk));
537 clamp<float>(typedValue);
542 typedValue = QVariant(cookedValue.toDouble(&convertOk));
544 clamp<double>(typedValue);
549 typedValue = QVariant(cookedValue.toString());
553 typedValue = QVariant(cookedValue.toBool());
557 typedValue = QVariant(cookedValue.toByteArray());
566 if (strings.count() != values.count()) {
567 qWarning(FactMetaDataLog) <<
"Count mismatch strings:values" << strings.count() << values.count();
571 _bitmaskStrings = strings;
572 _bitmaskValues = values;
578 _bitmaskStrings <<
name;
579 _bitmaskValues << value;
584 if (strings.count() != values.count()) {
585 qWarning(FactMetaDataLog) <<
"Count mismatch strings:values" << strings.count() << values.count();
589 _enumStrings = strings;
590 _enumValues = values;
596 _enumStrings <<
name;
597 _enumValues << value;
602 const int index = _enumValues.indexOf(value);
604 qWarning(FactMetaDataLog) <<
"Value does not exist in fact:" << value;
608 _enumValues.removeAt(index);
609 _enumStrings.removeAt(index);
614 _rawTranslator = rawTranslator_;
615 _cookedTranslator = cookedTranslator_;
620 if (_enumStrings.count() || _bitmaskStrings.count()) {
623 _cookedUnits = _rawUnits;
626 for (
size_t i = 0; i < std::size(_rgBuiltInTranslations); i++) {
627 const BuiltInTranslation_s *pBuiltInTranslation = &_rgBuiltInTranslations[i];
629 if (pBuiltInTranslation->rawUnits.toLower() == _rawUnits.toLower()) {
630 _cookedUnits = pBuiltInTranslation->cookedUnits;
631 setTranslators(pBuiltInTranslation->rawTranslator, pBuiltInTranslation->cookedTranslator);
638 _setAppSettingsTranslators();
641QVariant FactMetaData::_degreesToRadians(
const QVariant °rees)
643 return QVariant(qDegreesToRadians(degrees.toDouble()));
646QVariant FactMetaData::_radiansToDegrees(
const QVariant &radians)
648 return QVariant(qRadiansToDegrees(radians.toDouble()));
651QVariant FactMetaData::_centiDegreesToDegrees(
const QVariant ¢iDegrees)
653 return QVariant(centiDegrees.toReal() / 100.0);
656QVariant FactMetaData::_degreesToCentiDegrees(
const QVariant °rees)
658 return QVariant(qRound(degrees.toReal() * 100.0));
661QVariant FactMetaData::_centiCelsiusToCelsius(
const QVariant ¢iCelsius)
663 return QVariant(centiCelsius.toReal() / 100.0);
666QVariant FactMetaData::_celsiusToCentiCelsius(
const QVariant &celsius)
668 return QVariant(qRound(celsius.toReal() * 100.0));
671QVariant FactMetaData::_userGimbalDegreesToMavlinkGimbalDegrees(
const QVariant &userGimbalDegrees)
675 return (userGimbalDegrees.toDouble() * -1.0);
678QVariant FactMetaData::_mavlinkGimbalDegreesToUserGimbalDegrees(
const QVariant& mavlinkGimbalDegrees)
682 return (mavlinkGimbalDegrees.toDouble() * -1.0);
685QVariant FactMetaData::_metersToFeet(
const QVariant &meters)
687 return QVariant((meters.toDouble() * 1.0) / constants.feetToMeters);
690QVariant FactMetaData::_feetToMeters(
const QVariant &feet)
692 return QVariant(feet.toDouble() * constants.feetToMeters);
695QVariant FactMetaData::_squareMetersToSquareKilometers(
const QVariant &squareMeters)
697 return QVariant(squareMeters.toDouble() * 0.000001);
700QVariant FactMetaData::_squareKilometersToSquareMeters(
const QVariant &squareKilometers)
702 return QVariant(squareKilometers.toDouble() * 1000000.0);
705QVariant FactMetaData::_squareMetersToHectares(
const QVariant &squareMeters)
707 return QVariant(squareMeters.toDouble() * 0.0001);
710QVariant FactMetaData::_hectaresToSquareMeters(
const QVariant &hectares)
712 return QVariant(hectares.toDouble() * 1000.0);
715QVariant FactMetaData::_squareMetersToSquareFeet(
const QVariant &squareMeters)
717 return QVariant(squareMeters.toDouble() * constants.squareMetersToSquareFeet);
720QVariant FactMetaData::_squareFeetToSquareMeters(
const QVariant &squareFeet)
722 return QVariant(squareFeet.toDouble() * constants.feetToSquareMeters);
725QVariant FactMetaData::_squareMetersToAcres(
const QVariant &squareMeters)
727 return QVariant(squareMeters.toDouble() * constants.squareMetersToAcres);
730QVariant FactMetaData::_acresToSquareMeters(
const QVariant &acres)
732 return QVariant(acres.toDouble() * constants.acresToSquareMeters);
735QVariant FactMetaData::_squareMetersToSquareMiles(
const QVariant &squareMeters)
737 return QVariant(squareMeters.toDouble() * constants.squareMetersToSquareMiles);
740QVariant FactMetaData::_squareMilesToSquareMeters(
const QVariant &squareMiles)
742 return QVariant(squareMiles.toDouble() * constants.squareMilesToSquareMeters);
745QVariant FactMetaData::_metersPerSecondToMilesPerHour(
const QVariant &metersPerSecond)
747 return QVariant(((metersPerSecond.toDouble() * 1.0) / constants.milesToMeters) * constants.secondsPerHour);
750QVariant FactMetaData::_milesPerHourToMetersPerSecond(
const QVariant &milesPerHour)
752 return QVariant((milesPerHour.toDouble() * constants.milesToMeters) / constants.secondsPerHour);
755QVariant FactMetaData::_metersPerSecondToKilometersPerHour(
const QVariant &metersPerSecond)
757 return QVariant((metersPerSecond.toDouble() / 1000.0) * constants.secondsPerHour);
760QVariant FactMetaData::_kilometersPerHourToMetersPerSecond(
const QVariant &kilometersPerHour)
762 return QVariant((kilometersPerHour.toDouble() * 1000.0) / constants.secondsPerHour);
765QVariant FactMetaData::_metersPerSecondToKnots(
const QVariant &metersPerSecond)
767 return QVariant((metersPerSecond.toDouble() * constants.secondsPerHour) / (1000.0 * constants.knotsToKPH));
770QVariant FactMetaData::_knotsToMetersPerSecond(
const QVariant& knots)
772 return QVariant(knots.toDouble() * (1000.0 * constants.knotsToKPH / constants.secondsPerHour));
775QVariant FactMetaData::_percentToNorm(
const QVariant &percent)
777 return QVariant(percent.toDouble() / 100.0);
780QVariant FactMetaData::_normToPercent(
const QVariant &normalized)
782 return QVariant(normalized.toDouble() * 100.0);
785QVariant FactMetaData::_centimetersToInches(
const QVariant ¢imeters)
787 return QVariant((centimeters.toDouble() * 1.0) / constants.inchesToCentimeters);
790QVariant FactMetaData::_inchesToCentimeters(
const QVariant &inches)
792 return QVariant(inches.toDouble() * constants.inchesToCentimeters);
795QVariant FactMetaData::_celsiusToFarenheit(
const QVariant &celsius)
797 return QVariant((celsius.toDouble() * (9.0 / 5.0)) + 32);
800QVariant FactMetaData::_farenheitToCelsius(
const QVariant &farenheit)
802 return QVariant((farenheit.toDouble() - 32) * (5.0 / 9.0));
805QVariant FactMetaData::_kilogramsToGrams(
const QVariant &kg)
807 return QVariant(kg.toDouble() * 1000);
810QVariant FactMetaData::_ouncesToGrams(
const QVariant &oz)
812 return QVariant(oz.toDouble() * constants.ouncesToGrams);
815QVariant FactMetaData::_poundsToGrams(
const QVariant &lbs)
817 return QVariant(lbs.toDouble() * constants.poundsToGrams);
820QVariant FactMetaData::_gramsToKilograms(
const QVariant &g)
822 return QVariant(g.toDouble() / 1000);
825QVariant FactMetaData::_gramsToOunces(
const QVariant &g)
827 return QVariant(g.toDouble() / constants.ouncesToGrams);
830QVariant FactMetaData::_gramsToPunds(
const QVariant &g)
832 return QVariant(g.toDouble() / constants.poundsToGrams);
847 for (
size_t i = 0; i < std::size(_rgKnownTypeStrings); i++) {
848 if (typeString.compare(_rgKnownTypeStrings[i], Qt::CaseInsensitive) == 0) {
849 return _rgKnownValueTypes[i];
860 for (
size_t i = 0; i < std::size(_rgKnownTypeStrings); i++) {
861 if (
type == _rgKnownValueTypes[i]) {
862 return _rgKnownTypeStrings[i];
866 return QStringLiteral(
"UnknownType%1").arg(
type);
889 qWarning(FactMetaDataLog) <<
"Unsupported fact value type" <<
type;
894void FactMetaData::_setAppSettingsTranslators()
898 for (
size_t i = 0; i < std::size(_rgAppSettingsTranslations); i++) {
899 const AppSettingsTranslation_s *pAppSettingsTranslation = &_rgAppSettingsTranslations[i];
901 if (_rawUnits.toLower() != pAppSettingsTranslation->rawUnits.toLower()) {
906 uint settingsUnits = 0;
908 switch (pAppSettingsTranslation->unitType) {
909 case UnitHorizontalDistance:
910 settingsUnits = settings->horizontalDistanceUnits()->rawValue().toUInt();
912 case UnitVerticalDistance:
913 settingsUnits = settings->verticalDistanceUnits()->rawValue().toUInt();
916 settingsUnits = settings->speedUnits()->rawValue().toUInt();
919 settingsUnits = settings->areaUnits()->rawValue().toUInt();
921 case UnitTemperature:
922 settingsUnits = settings->temperatureUnits()->rawValue().toUInt();
925 settingsUnits = settings->weightUnits()->rawValue().toUInt();
931 if (settingsUnits == pAppSettingsTranslation->unitOption) {
932 _cookedUnits = pAppSettingsTranslation->cookedUnits;
933 setTranslators(pAppSettingsTranslation->rawTranslator, pAppSettingsTranslation->cookedTranslator);
940const FactMetaData::AppSettingsTranslation_s* FactMetaData::_findAppSettingsUnitsTranslation(
const QString &rawUnits, UnitTypes type)
942 for (
size_t i = 0; i < std::size(_rgAppSettingsTranslations); i++) {
943 const AppSettingsTranslation_s *
const pAppSettingsTranslation = &_rgAppSettingsTranslations[i];
945 if (
rawUnits.toLower() != pAppSettingsTranslation->rawUnits.toLower()) {
952 case UnitHorizontalDistance:
953 unitOption = unitsSettings->horizontalDistanceUnits()->rawValue().toUInt();
955 case UnitVerticalDistance:
956 unitOption = unitsSettings->verticalDistanceUnits()->rawValue().toUInt();
959 unitOption = unitsSettings->areaUnits()->rawValue().toUInt();
962 unitOption = unitsSettings->speedUnits()->rawValue().toUInt();
964 case UnitTemperature:
965 unitOption = unitsSettings->temperatureUnits()->rawValue().toUInt();
968 unitOption = unitsSettings->weightUnits()->rawValue().toUInt();
972 if ((pAppSettingsTranslation->unitType ==
type) && (pAppSettingsTranslation->unitOption == unitOption)) {
973 return pAppSettingsTranslation;
982 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"m", UnitHorizontalDistance);
983 if (pAppSettingsTranslation) {
984 return pAppSettingsTranslation->rawTranslator(meters);
992 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"vertical m", UnitVerticalDistance);
993 if (pAppSettingsTranslation) {
994 return pAppSettingsTranslation->rawTranslator(meters);
1002 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"m", UnitHorizontalDistance);
1003 if (pAppSettingsTranslation) {
1004 return pAppSettingsTranslation->cookedTranslator(distance);
1012 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"vertical m", UnitVerticalDistance);
1013 if (pAppSettingsTranslation) {
1014 return pAppSettingsTranslation->cookedTranslator(distance);
1022 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"m", UnitHorizontalDistance);
1023 if (pAppSettingsTranslation) {
1024 return pAppSettingsTranslation->cookedUnits;
1026 return QStringLiteral(
"m");
1032 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"vertical m", UnitVerticalDistance);
1033 if (pAppSettingsTranslation) {
1034 return pAppSettingsTranslation->cookedUnits;
1036 return QStringLiteral(
"m");
1042 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"g", UnitWeight);
1043 if (pAppSettingsTranslation) {
1044 return pAppSettingsTranslation->cookedUnits;
1046 return QStringLiteral(
"g");
1052 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"m^2", UnitArea);
1053 if (pAppSettingsTranslation) {
1054 return pAppSettingsTranslation->rawTranslator(squareMeters);
1056 return squareMeters;
1062 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"m^2", UnitArea);
1063 if (pAppSettingsTranslation) {
1064 return pAppSettingsTranslation->cookedTranslator(area);
1072 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"m^2", UnitArea);
1073 if (pAppSettingsTranslation) {
1074 return pAppSettingsTranslation->cookedUnits;
1076 return QStringLiteral(
"m^2");
1081 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"g", UnitWeight);
1082 if (pAppSettingsTranslation) {
1083 return pAppSettingsTranslation->rawTranslator(grams);
1090 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"g", UnitWeight);
1091 if (pAppSettingsTranslation) {
1092 return pAppSettingsTranslation->cookedTranslator(weight);
1100 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"m/s", UnitSpeed);
1101 if (pAppSettingsTranslation) {
1102 return pAppSettingsTranslation->rawTranslator(metersSecond);
1104 return metersSecond;
1110 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"m/s", UnitSpeed);
1111 if (pAppSettingsTranslation) {
1112 return pAppSettingsTranslation->cookedTranslator(speed);
1120 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"m/s", UnitSpeed);
1121 if (pAppSettingsTranslation) {
1122 return pAppSettingsTranslation->cookedUnits;
1124 return QStringLiteral(
"m/s");
1130 return _rawTranslator(this->
rawIncrement()).toDouble();
1139 double increment = _rawTranslator(this->
rawIncrement()).toDouble();
1140 if (!qIsNaN(increment)) {
1141 double integralPart;
1144 increment = fabs(modf(increment, &integralPart));
1145 if (increment == 0.0) {
1147 incrementDecimalPlaces = 0;
1149 incrementDecimalPlaces = -ceil(log10(increment));
1155 actualDecimalPlaces = incrementDecimalPlaces;
1159 const double ctest = _rawTranslator(1.0).toDouble();
1161 settingsDecimalPlaces += -log10(ctest);
1163 settingsDecimalPlaces = qMin(25, settingsDecimalPlaces);
1164 settingsDecimalPlaces = qMax(0, settingsDecimalPlaces);
1166 actualDecimalPlaces = settingsDecimalPlaces;
1169 actualDecimalPlaces = _decimalPlaces;
1172 return actualDecimalPlaces;
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 },
1212 qWarning(FactMetaDataLog) <<
"Unknown type" << json[_typeJsonKey].toString();
1218 metaData->_name = json[_nameJsonKey].toString();
1220 QStringList rgDescriptions;
1221 QList<double> rgDoubleValues;
1222 QList<int> rgIntValues;
1223 QStringList rgStringValues;
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);
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);
1233 foundBitmask = rgDescriptions.count() != 0;
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);
1241 if (
errorString.isEmpty() && !rgDescriptions.isEmpty()) {
1242 for (qsizetype i = 0; i < rgDescriptions.count(); i++) {
1244 metaData->
addBitmaskInfo(rgDescriptions[i], 1 << rgIntValues[i]);
1246 const QVariant rawValueVariant = !rgDoubleValues.isEmpty() ? QVariant(rgDoubleValues[i]) : QVariant(rgStringValues[i]);
1247 QVariant convertedValueVariant;
1248 QString enumErrorString;
1249 if (metaData->
convertAndValidateRaw(rawValueVariant,
false , convertedValueVariant, enumErrorString)) {
1250 metaData->
addEnumInfo(rgDescriptions[i], convertedValueVariant);
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;
1263 metaData->
setLabel(json[_labelJsonKey].toString());
1266 if (json.contains(_unitsJsonKey)) {
1267 metaData->
setRawUnits(json[_unitsJsonKey].toString());
1270 QString defaultValueJsonKey = _defaultValueJsonKey;
1271#if defined(Q_OS_ANDROID) || defined(Q_OS_IOS)
1272 if (json.contains(_mobileDefaultValueJsonKey)) {
1273 defaultValueJsonKey = _mobileDefaultValueJsonKey;
1277 if (json.contains(defaultValueJsonKey)) {
1278 const QJsonValue jsonValue = json[defaultValueJsonKey];
1283 QVariant typedValue;
1284 QString defaultValueErrorString;
1285 const QVariant initialValue = jsonValue.toVariant();
1290 qWarning(FactMetaDataLog) <<
"Invalid default value,"
1291 <<
"name:" << metaData->
name()
1292 <<
"type:" << metaData->
type()
1293 <<
"value:" << initialValue
1294 <<
"error:" << defaultValueErrorString;
1299 if (json.contains(_incrementJsonKey)) {
1300 QVariant typedValue;
1301 QString incrementErrorString;
1302 const QVariant initialValue = json[_incrementJsonKey].toVariant();
1306 qWarning(FactMetaDataLog) <<
"Invalid increment value,"
1307 <<
"name:" << metaData->
name()
1308 <<
"type:" << metaData->
type()
1309 <<
"value:" << initialValue
1310 <<
"error:" << incrementErrorString;
1314 if (json.contains(_minJsonKey)) {
1315 QVariant typedValue;
1316 QString minErrorString;
1317 const QVariant initialValue = json[_minJsonKey].toVariant();
1321 qWarning(FactMetaDataLog) <<
"Invalid min value,"
1322 <<
"name:" << metaData->
name()
1323 <<
"type:" << metaData->
type()
1324 <<
"value:" << initialValue
1325 <<
"error:" << minErrorString;
1329 if (json.contains(_maxJsonKey)) {
1330 QVariant typedValue;
1331 QString maxErrorString;
1332 const QVariant initialValue = json[_maxJsonKey].toVariant();
1336 qWarning(FactMetaDataLog) <<
"Invalid max value,"
1337 <<
"name:" << metaData->
name()
1338 <<
"type:" << metaData->
type()
1339 <<
"value:" << initialValue
1340 <<
"error:" << maxErrorString;
1346 if (json.contains(_userMinJsonKey)) {
1347 QVariant typedValue;
1348 QString userMinErrorString;
1349 const QVariant initialValue = json[_userMinJsonKey].toVariant();
1353 qWarning(FactMetaDataLog) <<
"Invalid userMin value,"
1354 <<
"name:" << metaData->
name()
1355 <<
"type:" << metaData->
type()
1356 <<
"value:" << initialValue
1357 <<
"error:" << userMinErrorString;
1361 if (json.contains(_userMaxJsonKey)) {
1362 QVariant typedValue;
1363 QString userMaxErrorString;
1364 const QVariant initialValue = json[_userMaxJsonKey].toVariant();
1368 qWarning(FactMetaDataLog) <<
"Invalid userMax value,"
1369 <<
"name:" << metaData->
name()
1370 <<
"type:" << metaData->
type()
1371 <<
"value:" << initialValue
1372 <<
"error:" << userMaxErrorString;
1376 bool hasControlJsonKey =
true;
1377 if (json.contains(_hasControlJsonKey)) {
1378 hasControlJsonKey = json[_hasControlJsonKey].toBool();
1383 if (json.contains(_qgcRebootRequiredJsonKey)) {
1388 bool rebootRequired =
false;
1389 if (json.contains(_rebootRequiredJsonKey)) {
1390 rebootRequired = json[_rebootRequiredJsonKey].toBool();
1395 if (json.contains(_readOnlyJsonKey)) {
1396 readOnly = json[_readOnlyJsonKey].toBool();
1401 if (json.contains(_volatileJsonKey)) {
1405 if (json.contains(_groupJsonKey)) {
1406 metaData->
setGroup(json[_groupJsonKey].toString());
1409 if (json.contains(_categoryJsonKey)) {
1410 metaData->
setCategory(json[_categoryJsonKey].toString());
1416void FactMetaData::_loadJsonDefines(
const QJsonObject &jsonDefinesObject, QMap<QString, QString> &defineMap)
1418 for (
const QString &defineName: jsonDefinesObject.keys()) {
1419 const QString mapKey = _jsonMetaDataDefinesName + QStringLiteral(
".") + defineName;
1420 defineMap[mapKey] = jsonDefinesObject[defineName].toString();
1426 QMap<QString, FactMetaData*> metaDataMap;
1432 QStringList{
"label",
"shortDesc",
"longDesc",
"enumStrings"},
1433 QStringList{
"name"});
1435 qWarning(FactMetaDataLog) <<
"Internal Error:" <<
errorString;
1439 static const QList<JsonParsing::KeyValidateInfo> keyInfoList = {
1440 { FactMetaData::_jsonMetaDataDefinesName, QJsonValue::Object,
false },
1441 { FactMetaData::_jsonMetaDataFactsName, QJsonValue::Array,
true },
1444 qWarning(FactMetaDataLog) <<
"Json document incorrect format:" <<
errorString;
1448 QMap<QString , QString > defineMap;
1449 _loadJsonDefines(jsonObject[FactMetaData::_jsonMetaDataDefinesName].toObject(), defineMap);
1450 const QJsonArray factArray = jsonObject[FactMetaData::_jsonMetaDataFactsName].toArray();
1457 QMap<QString, FactMetaData*> metaDataMap;
1458 for (
const QJsonValue &jsonValue : jsonArray) {
1459 if (!jsonValue.isObject()) {
1460 qWarning(FactMetaDataLog) <<
"JsonValue is not an object";
1464 const QJsonObject jsonObject = jsonValue.toObject();
1466 if (metaDataMap.contains(metaData->
name())) {
1467 qWarning(FactMetaDataLog) <<
"Duplicate fact name:" << metaData->
name();
1470 metaDataMap[metaData->
name()] = metaData;
1480 return qMax(_rawTranslator(_rawMax).toDouble(), _rawTranslator(_rawMin).toDouble());
1486 return qMin(_rawTranslator(_rawMax).toDouble(), _rawTranslator(_rawMin).toDouble());
1496 const QRegularExpression splitRegex(
"[,,、]");
1497 QStringList valueList = translatedList.split(splitRegex, Qt::SkipEmptyParts);
1498 for (QString &value: valueList) {
1499 value = value.trimmed();
1504bool FactMetaData::_parseEnum(
const QString& name,
const QJsonObject &jsonObject,
const DefineMap_t &defineMap, QStringList &rgDescriptions, QStringList &rgValues, QString &
errorString)
1506 rgDescriptions.clear();
1510 if (!jsonObject.contains(_enumStringsJsonKey)) {
1514 const QString jsonStrings = jsonObject.value(_enumStringsJsonKey).toString();
1515 const QString defineMapStrings = defineMap.value(jsonStrings, jsonStrings);
1518 const QString jsonValues = jsonObject.value(_enumValuesJsonKey).toString();
1519 const QString defineMapValues = defineMap.value(jsonValues, jsonValues);
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());
1530bool FactMetaData::_parseValuesArray(
const QJsonObject &jsonObject, QStringList &rgDescriptions, QList<double> &rgValues, QString &
errorString)
1532 rgDescriptions.clear();
1536 if (!jsonObject.contains(_enumValuesArrayJsonKey)) {
1540 static const QList<JsonParsing::KeyValidateInfo> keyInfoList = {
1541 { _enumValuesArrayDescriptionJsonKey, QJsonValue::String,
true },
1542 { _enumValuesArrayValueJsonKey, QJsonValue::Double,
true },
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.");
1552 const QJsonObject &valueDescriptionObject = jsonValue.toObject();
1558 rgDescriptions.append(valueDescriptionObject[_enumValuesArrayDescriptionJsonKey].toString());
1559 rgValues.append(valueDescriptionObject[_enumValuesArrayValueJsonKey].toDouble());
1565bool FactMetaData::_parseBitmaskArray(
const QJsonObject &jsonObject, QStringList &rgDescriptions, QList<int> &rgValues, QString &
errorString)
1567 rgDescriptions.clear();
1571 if (!jsonObject.contains(_enumBitmaskArrayJsonKey)) {
1575 static const QList<JsonParsing::KeyValidateInfo> keyInfoList = {
1576 { _enumBitmaskArrayDescriptionJsonKey, QJsonValue::String,
true },
1577 { _enumBitmaskArrayIndexJsonKey, QJsonValue::Double,
true },
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.");
1587 const QJsonObject &valueDescriptionObject = jsonValue.toObject();
1593 rgDescriptions.append(valueDescriptionObject[_enumBitmaskArrayDescriptionJsonKey].toString());
1594 rgValues.append(valueDescriptionObject[_enumBitmaskArrayIndexJsonKey].toInt());
1602 if (!_rawUserMin.isValid()) {
1606 return _rawTranslator(_rawUserMin);
1611 if (!_rawUserMax.isValid()) {
1615 return _rawTranslator(_rawUserMax);
#define QGC_LOGGING_CATEGORY(name, categoryStr)
#define MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN
UnitsSettings * unitsSettings() const
static SettingsManager * instance()
@ TemperatureUnitsCelsius
@ TemperatureUnitsFarenheit
@ VerticalDistanceUnitsFeet
@ VerticalDistanceUnitsMeters
@ SpeedUnitsKilometersPerHour
@ SpeedUnitsFeetPerSecond
@ SpeedUnitsMetersPerSecond
@ AreaUnitsSquareKilometers
@ 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)