8#include <QtCore/QtMath>
14 {
"centi-degrees",
"deg", FactMetaData::_centiDegreesToDegrees, FactMetaData::_degreesToCentiDegrees },
15 {
"radians",
"deg", FactMetaData::_radiansToDegrees, FactMetaData::_degreesToRadians },
16 {
"rad",
"deg", FactMetaData::_radiansToDegrees, FactMetaData::_degreesToRadians },
17 {
"gimbal-degrees",
"deg", FactMetaData::_mavlinkGimbalDegreesToUserGimbalDegrees, FactMetaData::_userGimbalDegreesToMavlinkGimbalDegrees },
18 {
"norm",
"%", FactMetaData::_normToPercent, FactMetaData::_percentToNorm },
19 {
"centi-celsius",
"C", FactMetaData::_centiCelsiusToCelsius, FactMetaData::_celsiusToCentiCelsius },
23const FactMetaData::AppSettingsTranslation_s FactMetaData::_rgAppSettingsTranslations[] = {
41 {
"m^2",
"ac", FactMetaData::UnitArea,
UnitsSettings::AreaUnitsAcres, FactMetaData::_squareMetersToAcres, FactMetaData::_acresToSquareMeters },
46 {
"m/s",
"kn", FactMetaData::UnitSpeed,
UnitsSettings::SpeedUnitsKnots, FactMetaData::_metersPerSecondToKnots, FactMetaData::_knotsToMetersPerSecond },
89 _decimalPlaces = other._decimalPlaces;
90 _rawDefaultValue = other._rawDefaultValue;
91 _defaultValueAvailable = other._defaultValueAvailable;
92 _bitmaskStrings = other._bitmaskStrings;
93 _bitmaskValues = other._bitmaskValues;
94 _enumStrings = other._enumStrings;
95 _enumValues = other._enumValues;
96 _category = other._category;
97 _group = other._group;
98 _longDescription = other._longDescription;
99 _rawMax = other._rawMax;
100 _rawMin = other._rawMin;
101 _rawUserMin = other._rawUserMin;
102 _rawUserMax = other._rawUserMax;
104 _shortDescription = other._shortDescription;
106 _rawUnits = other._rawUnits;
107 _cookedUnits = other._cookedUnits;
108 _rawTranslator = other._rawTranslator;
109 _cookedTranslator = other._cookedTranslator;
110 _vehicleRebootRequired = other._vehicleRebootRequired;
111 _qgcRebootRequired = other._qgcRebootRequired;
112 _rawIncrement = other._rawIncrement;
113 _hasControl = other._hasControl;
114 _readOnly = other._readOnly;
115 _writeOnly = other._writeOnly;
116 _volatile = other._volatile;
123 if (_defaultValueAvailable) {
124 return _rawDefaultValue;
126 qWarning(FactMetaDataLog) <<
"Attempt to access unavailable default value";
135 _defaultValueAvailable =
true;
137 qWarning(FactMetaDataLog) <<
"Attempt to set default value which is outside min/max range";
143 if (isInRawMinLimit(
rawMin)) {
145 if (_rawUserMin.isValid() && !isInRawMinLimit(_rawUserMin)) {
146 _rawUserMin = _rawMin;
149 qWarning(FactMetaDataLog) <<
"Attempt to set min below allowable value for fact:" <<
name()
150 <<
", value attempted:" <<
rawMin
151 <<
", type:" <<
type()
152 <<
", min for type:" << _minForType();
153 _rawMin = _minForType();
154 _rawUserMin = _rawMin;
160 if (isInRawMaxLimit(
rawMax)) {
162 if (_rawUserMax.isValid() && !isInRawMaxLimit(_rawUserMax)) {
163 _rawUserMax = _rawMax;
166 qWarning(FactMetaDataLog) <<
"Attempt to set max above allowable value for fact:" <<
name()
167 <<
", value attempted:" <<
rawMax
168 <<
", type:" <<
type()
169 <<
", max for type:" << _maxForType();
170 _rawMax = _maxForType();
171 _rawUserMax = _rawMax;
180 qWarning(FactMetaDataLog) <<
"Attempt to set user min below allowable value for fact:" <<
name()
182 <<
", type:" <<
type()
183 <<
", min:" << _rawMin;
184 _rawUserMin = _rawMin;
193 qWarning(FactMetaDataLog) <<
"Attempt to set user max above allowable value for fact:" <<
name()
195 <<
", type:" <<
type()
196 <<
", max:" << _rawMax;
197 _rawUserMax = _rawMax;
201bool FactMetaData::isInRawMinLimit(
const QVariant &variantValue)
const
205 return (_rawMin.value<
unsigned char>() <= variantValue.value<
unsigned char>());
207 return (_rawMin.value<
signed char>() <= variantValue.value<
signed char>());
209 return (_rawMin.value<
unsigned short int>() <= variantValue.value<
unsigned short int>());
211 return (_rawMin.value<
short int>() <= variantValue.value<
short int>());
213 return (_rawMin.value<uint32_t>() <= variantValue.value<uint32_t>());
215 return (_rawMin.value<int32_t>() <= variantValue.value<int32_t>());
217 return (_rawMin.value<uint64_t>() <= variantValue.value<uint64_t>());
219 return (_rawMin.value<int64_t>() <= variantValue.value<int64_t>());
221 return ((qIsNaN(variantValue.toFloat())) || (_rawMin.value<
float>() <= variantValue.value<
float>()));
223 return ((qIsNaN(variantValue.toDouble())) || (_rawMin.value<
double>() <= variantValue.value<
double>()));
229bool FactMetaData::isInRawMaxLimit(
const QVariant &variantValue)
const
233 return (_rawMax.value<
unsigned char>() >= variantValue.value<
unsigned char>());
235 return (_rawMax.value<
signed char>() >= variantValue.value<
signed char>());
237 return (_rawMax.value<
unsigned short int>() >= variantValue.value<
unsigned short int>());
239 return (_rawMax.value<
short int>() >= variantValue.value<
short int>());
241 return (_rawMax.value<uint32_t>() >= variantValue.value<uint32_t>());
243 return (_rawMax.value<int32_t>() >= variantValue.value<int32_t>());
245 return (_rawMax.value<uint64_t>() >= variantValue.value<uint64_t>());
247 return (_rawMax.value<int64_t>() >= variantValue.value<int64_t>());
249 return (qIsNaN(variantValue.toFloat()) || (_rawMax.value<
float>() >= variantValue.value<
float>()));
251 return (qIsNaN(variantValue.toDouble()) || (_rawMax.value<
double>() >= variantValue.value<
double>()));
261 return QVariant(std::numeric_limits<unsigned char>::min());
263 return QVariant(std::numeric_limits<signed char>::min());
265 return QVariant(std::numeric_limits<unsigned short int>::min());
267 return QVariant(std::numeric_limits<short int>::min());
269 return QVariant(std::numeric_limits<uint32_t>::min());
271 return QVariant(std::numeric_limits<int32_t>::min());
273 return QVariant((qulonglong)std::numeric_limits<uint64_t>::min());
275 return QVariant((qlonglong)std::numeric_limits<int64_t>::min());
277 return QVariant(-std::numeric_limits<float>::max());
279 return QVariant(-std::numeric_limits<double>::max());
285 return QVariant(0.0);
296 return QVariant(std::numeric_limits<unsigned char>::max());
298 return QVariant(std::numeric_limits<signed char>::max());
300 return QVariant(std::numeric_limits<unsigned short int>::max());
302 return QVariant(std::numeric_limits<short int>::max());
304 return QVariant(std::numeric_limits<uint32_t>::max());
306 return QVariant(std::numeric_limits<int32_t>::max());
308 return QVariant((qulonglong)std::numeric_limits<uint64_t>::max());
310 return QVariant((qlonglong)std::numeric_limits<int64_t>::max());
312 return QVariant(std::numeric_limits<float>::max());
315 return QVariant(std::numeric_limits<double>::max());
328 bool convertOk =
false;
336 typedValue = QVariant(rawValue.toInt(&convertOk));
337 if (!convertOnly && convertOk) {
338 if (!isInRawLimit<int32_t>(typedValue)) {
344 typedValue = QVariant(rawValue.toLongLong(&convertOk));
345 if (!convertOnly && convertOk) {
346 if (!isInRawLimit<int64_t>(typedValue)) {
354 typedValue = QVariant(rawValue.toUInt(&convertOk));
355 if (!convertOnly && convertOk) {
356 if (!isInRawLimit<uint32_t>(typedValue)) {
362 typedValue = QVariant(rawValue.toULongLong(&convertOk));
363 if (!convertOnly && convertOk) {
364 if (!isInRawLimit<uint64_t>(typedValue)) {
370 typedValue = QVariant(rawValue.toFloat(&convertOk));
371 if (!convertOnly && convertOk) {
372 if (!isInRawLimit<float>(typedValue)) {
379 typedValue = QVariant(rawValue.toDouble(&convertOk));
380 if (!convertOnly && convertOk) {
381 if (!isInRawLimit<double>(typedValue)) {
388 typedValue = QVariant(rawValue.toString());
392 typedValue = QVariant(rawValue.toBool());
396 typedValue = QVariant(rawValue.toByteArray());
409 bool convertOk =
false;
413 if (!convertOnly && _customCookedValidator) {
424 typedValue = QVariant(cookedValue.toInt(&convertOk));
425 if (!convertOnly && convertOk) {
426 if (!isInCookedLimit<int32_t>(typedValue)) {
432 typedValue = QVariant(cookedValue.toLongLong(&convertOk));
433 if (!convertOnly && convertOk) {
434 if (!isInCookedLimit<int64_t>(typedValue)) {
442 typedValue = QVariant(cookedValue.toUInt(&convertOk));
443 if (!convertOnly && convertOk) {
444 if (!isInCookedLimit<uint32_t>(typedValue)) {
450 typedValue = QVariant(cookedValue.toULongLong(&convertOk));
451 if (!convertOnly && convertOk) {
452 if (!isInCookedLimit<uint64_t>(typedValue)) {
458 typedValue = QVariant(cookedValue.toFloat(&convertOk));
459 if (!convertOnly && convertOk) {
460 if (!isInCookedLimit<float>(typedValue)) {
467 typedValue = QVariant(cookedValue.toDouble(&convertOk));
468 if (!convertOnly && convertOk) {
469 if (!isInCookedLimit<double>(typedValue)) {
476 typedValue = QVariant(cookedValue.toString());
480 typedValue = QVariant(cookedValue.toBool());
484 typedValue = QVariant(cookedValue.toByteArray());
497 bool convertOk =
false;
503 typedValue = QVariant(cookedValue.toInt(&convertOk));
505 clamp<int32_t>(typedValue);
509 typedValue = QVariant(cookedValue.toLongLong(&convertOk));
511 clamp<int64_t>(typedValue);
517 typedValue = QVariant(cookedValue.toUInt(&convertOk));
519 clamp<uint32_t>(typedValue);
523 typedValue = QVariant(cookedValue.toULongLong(&convertOk));
525 clamp<uint64_t>(typedValue);
529 typedValue = QVariant(cookedValue.toFloat(&convertOk));
531 clamp<float>(typedValue);
536 typedValue = QVariant(cookedValue.toDouble(&convertOk));
538 clamp<double>(typedValue);
543 typedValue = QVariant(cookedValue.toString());
547 typedValue = QVariant(cookedValue.toBool());
551 typedValue = QVariant(cookedValue.toByteArray());
560 if (strings.count() != values.count()) {
561 qWarning(FactMetaDataLog) <<
"Count mismatch strings:values" << strings.count() << values.count();
565 _bitmaskStrings = strings;
566 _bitmaskValues = values;
572 _bitmaskStrings <<
name;
573 _bitmaskValues << value;
578 if (strings.count() != values.count()) {
579 qWarning(FactMetaDataLog) <<
"Count mismatch strings:values" << strings.count() << values.count();
583 _enumStrings = strings;
584 _enumValues = values;
590 _enumStrings <<
name;
591 _enumValues << value;
596 const int index = _enumValues.indexOf(value);
598 qWarning(FactMetaDataLog) <<
"Value does not exist in fact:" << value;
602 _enumValues.removeAt(index);
603 _enumStrings.removeAt(index);
608 _rawTranslator = rawTranslator_;
609 _cookedTranslator = cookedTranslator_;
614 if (_enumStrings.count() || _bitmaskStrings.count()) {
617 _cookedUnits = _rawUnits;
620 for (
size_t i = 0; i < std::size(_rgBuiltInTranslations); i++) {
621 const BuiltInTranslation_s *pBuiltInTranslation = &_rgBuiltInTranslations[i];
623 if (pBuiltInTranslation->rawUnits.toLower() == _rawUnits.toLower()) {
624 _cookedUnits = pBuiltInTranslation->cookedUnits;
625 setTranslators(pBuiltInTranslation->rawTranslator, pBuiltInTranslation->cookedTranslator);
632 _setAppSettingsTranslators();
635QVariant FactMetaData::_degreesToRadians(
const QVariant °rees)
637 return QVariant(qDegreesToRadians(degrees.toDouble()));
640QVariant FactMetaData::_radiansToDegrees(
const QVariant &radians)
642 return QVariant(qRadiansToDegrees(radians.toDouble()));
645QVariant FactMetaData::_centiDegreesToDegrees(
const QVariant ¢iDegrees)
647 return QVariant(centiDegrees.toReal() / 100.0);
650QVariant FactMetaData::_degreesToCentiDegrees(
const QVariant °rees)
652 return QVariant(qRound(degrees.toReal() * 100.0));
655QVariant FactMetaData::_centiCelsiusToCelsius(
const QVariant ¢iCelsius)
657 return QVariant(centiCelsius.toReal() / 100.0);
660QVariant FactMetaData::_celsiusToCentiCelsius(
const QVariant &celsius)
662 return QVariant(qRound(celsius.toReal() * 100.0));
665QVariant FactMetaData::_userGimbalDegreesToMavlinkGimbalDegrees(
const QVariant &userGimbalDegrees)
669 return (userGimbalDegrees.toDouble() * -1.0);
672QVariant FactMetaData::_mavlinkGimbalDegreesToUserGimbalDegrees(
const QVariant& mavlinkGimbalDegrees)
676 return (mavlinkGimbalDegrees.toDouble() * -1.0);
679QVariant FactMetaData::_metersToFeet(
const QVariant &meters)
681 return QVariant((meters.toDouble() * 1.0) / constants.feetToMeters);
684QVariant FactMetaData::_feetToMeters(
const QVariant &feet)
686 return QVariant(feet.toDouble() * constants.feetToMeters);
689QVariant FactMetaData::_squareMetersToSquareKilometers(
const QVariant &squareMeters)
691 return QVariant(squareMeters.toDouble() * 0.000001);
694QVariant FactMetaData::_squareKilometersToSquareMeters(
const QVariant &squareKilometers)
696 return QVariant(squareKilometers.toDouble() * 1000000.0);
699QVariant FactMetaData::_squareMetersToHectares(
const QVariant &squareMeters)
701 return QVariant(squareMeters.toDouble() * 0.0001);
704QVariant FactMetaData::_hectaresToSquareMeters(
const QVariant &hectares)
706 return QVariant(hectares.toDouble() * 1000.0);
709QVariant FactMetaData::_squareMetersToSquareFeet(
const QVariant &squareMeters)
711 return QVariant(squareMeters.toDouble() * constants.squareMetersToSquareFeet);
714QVariant FactMetaData::_squareFeetToSquareMeters(
const QVariant &squareFeet)
716 return QVariant(squareFeet.toDouble() * constants.feetToSquareMeters);
719QVariant FactMetaData::_squareMetersToAcres(
const QVariant &squareMeters)
721 return QVariant(squareMeters.toDouble() * constants.squareMetersToAcres);
724QVariant FactMetaData::_acresToSquareMeters(
const QVariant &acres)
726 return QVariant(acres.toDouble() * constants.acresToSquareMeters);
729QVariant FactMetaData::_squareMetersToSquareMiles(
const QVariant &squareMeters)
731 return QVariant(squareMeters.toDouble() * constants.squareMetersToSquareMiles);
734QVariant FactMetaData::_squareMilesToSquareMeters(
const QVariant &squareMiles)
736 return QVariant(squareMiles.toDouble() * constants.squareMilesToSquareMeters);
739QVariant FactMetaData::_metersPerSecondToMilesPerHour(
const QVariant &metersPerSecond)
741 return QVariant(((metersPerSecond.toDouble() * 1.0) / constants.milesToMeters) * constants.secondsPerHour);
744QVariant FactMetaData::_milesPerHourToMetersPerSecond(
const QVariant &milesPerHour)
746 return QVariant((milesPerHour.toDouble() * constants.milesToMeters) / constants.secondsPerHour);
749QVariant FactMetaData::_metersPerSecondToKilometersPerHour(
const QVariant &metersPerSecond)
751 return QVariant((metersPerSecond.toDouble() / 1000.0) * constants.secondsPerHour);
754QVariant FactMetaData::_kilometersPerHourToMetersPerSecond(
const QVariant &kilometersPerHour)
756 return QVariant((kilometersPerHour.toDouble() * 1000.0) / constants.secondsPerHour);
759QVariant FactMetaData::_metersPerSecondToKnots(
const QVariant &metersPerSecond)
761 return QVariant((metersPerSecond.toDouble() * constants.secondsPerHour) / (1000.0 * constants.knotsToKPH));
764QVariant FactMetaData::_knotsToMetersPerSecond(
const QVariant& knots)
766 return QVariant(knots.toDouble() * (1000.0 * constants.knotsToKPH / constants.secondsPerHour));
769QVariant FactMetaData::_percentToNorm(
const QVariant &percent)
771 return QVariant(percent.toDouble() / 100.0);
774QVariant FactMetaData::_normToPercent(
const QVariant &normalized)
776 return QVariant(normalized.toDouble() * 100.0);
779QVariant FactMetaData::_centimetersToInches(
const QVariant ¢imeters)
781 return QVariant((centimeters.toDouble() * 1.0) / constants.inchesToCentimeters);
784QVariant FactMetaData::_inchesToCentimeters(
const QVariant &inches)
786 return QVariant(inches.toDouble() * constants.inchesToCentimeters);
789QVariant FactMetaData::_celsiusToFarenheit(
const QVariant &celsius)
791 return QVariant((celsius.toDouble() * (9.0 / 5.0)) + 32);
794QVariant FactMetaData::_farenheitToCelsius(
const QVariant &farenheit)
796 return QVariant((farenheit.toDouble() - 32) * (5.0 / 9.0));
799QVariant FactMetaData::_kilogramsToGrams(
const QVariant &kg)
801 return QVariant(kg.toDouble() * 1000);
804QVariant FactMetaData::_ouncesToGrams(
const QVariant &oz)
806 return QVariant(oz.toDouble() * constants.ouncesToGrams);
809QVariant FactMetaData::_poundsToGrams(
const QVariant &lbs)
811 return QVariant(lbs.toDouble() * constants.poundsToGrams);
814QVariant FactMetaData::_gramsToKilograms(
const QVariant &g)
816 return QVariant(g.toDouble() / 1000);
819QVariant FactMetaData::_gramsToOunces(
const QVariant &g)
821 return QVariant(g.toDouble() / constants.ouncesToGrams);
824QVariant FactMetaData::_gramsToPunds(
const QVariant &g)
826 return QVariant(g.toDouble() / constants.poundsToGrams);
841 for (
size_t i = 0; i < std::size(_rgKnownTypeStrings); i++) {
842 if (typeString.compare(_rgKnownTypeStrings[i], Qt::CaseInsensitive) == 0) {
843 return _rgKnownValueTypes[i];
854 for (
size_t i = 0; i < std::size(_rgKnownTypeStrings); i++) {
855 if (
type == _rgKnownValueTypes[i]) {
856 return _rgKnownTypeStrings[i];
860 return QStringLiteral(
"UnknownType%1").arg(
type);
881 return MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN;
883 qWarning(FactMetaDataLog) <<
"Unsupported fact value type" <<
type;
888void FactMetaData::_setAppSettingsTranslators()
892 for (
size_t i = 0; i < std::size(_rgAppSettingsTranslations); i++) {
893 const AppSettingsTranslation_s *pAppSettingsTranslation = &_rgAppSettingsTranslations[i];
895 if (_rawUnits.toLower() != pAppSettingsTranslation->rawUnits.toLower()) {
899 UnitsSettings *
const settings = SettingsManager::instance()->unitsSettings();
900 uint settingsUnits = 0;
902 switch (pAppSettingsTranslation->unitType) {
903 case UnitHorizontalDistance:
906 case UnitVerticalDistance:
910 settingsUnits = settings->
speedUnits()->rawValue().toUInt();
913 settingsUnits = settings->
areaUnits()->rawValue().toUInt();
915 case UnitTemperature:
919 settingsUnits = settings->
weightUnits()->rawValue().toUInt();
925 if (settingsUnits == pAppSettingsTranslation->unitOption) {
926 _cookedUnits = pAppSettingsTranslation->cookedUnits;
927 setTranslators(pAppSettingsTranslation->rawTranslator, pAppSettingsTranslation->cookedTranslator);
934const FactMetaData::AppSettingsTranslation_s* FactMetaData::_findAppSettingsUnitsTranslation(
const QString &rawUnits, UnitTypes type)
936 for (
size_t i = 0; i < std::size(_rgAppSettingsTranslations); i++) {
937 const AppSettingsTranslation_s *
const pAppSettingsTranslation = &_rgAppSettingsTranslations[i];
939 if (
rawUnits.toLower() != pAppSettingsTranslation->rawUnits.toLower()) {
944 UnitsSettings *unitsSettings = SettingsManager::instance()->unitsSettings();
946 case UnitHorizontalDistance:
949 case UnitVerticalDistance:
953 unitOption = unitsSettings->
areaUnits()->rawValue().toUInt();
956 unitOption = unitsSettings->
speedUnits()->rawValue().toUInt();
958 case UnitTemperature:
962 unitOption = unitsSettings->
weightUnits()->rawValue().toUInt();
966 if ((pAppSettingsTranslation->unitType ==
type) && (pAppSettingsTranslation->unitOption == unitOption)) {
967 return pAppSettingsTranslation;
976 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"m", UnitHorizontalDistance);
977 if (pAppSettingsTranslation) {
978 return pAppSettingsTranslation->rawTranslator(meters);
986 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"vertical m", UnitVerticalDistance);
987 if (pAppSettingsTranslation) {
988 return pAppSettingsTranslation->rawTranslator(meters);
996 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"m", UnitHorizontalDistance);
997 if (pAppSettingsTranslation) {
998 return pAppSettingsTranslation->cookedTranslator(distance);
1006 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"vertical m", UnitVerticalDistance);
1007 if (pAppSettingsTranslation) {
1008 return pAppSettingsTranslation->cookedTranslator(distance);
1016 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"m", UnitHorizontalDistance);
1017 if (pAppSettingsTranslation) {
1018 return pAppSettingsTranslation->cookedUnits;
1020 return QStringLiteral(
"m");
1026 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"vertical m", UnitVerticalDistance);
1027 if (pAppSettingsTranslation) {
1028 return pAppSettingsTranslation->cookedUnits;
1030 return QStringLiteral(
"m");
1036 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"g", UnitWeight);
1037 if (pAppSettingsTranslation) {
1038 return pAppSettingsTranslation->cookedUnits;
1040 return QStringLiteral(
"g");
1046 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"m^2", UnitArea);
1047 if (pAppSettingsTranslation) {
1048 return pAppSettingsTranslation->rawTranslator(squareMeters);
1050 return squareMeters;
1056 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"m^2", UnitArea);
1057 if (pAppSettingsTranslation) {
1058 return pAppSettingsTranslation->cookedTranslator(area);
1066 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"m^2", UnitArea);
1067 if (pAppSettingsTranslation) {
1068 return pAppSettingsTranslation->cookedUnits;
1070 return QStringLiteral(
"m^2");
1075 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"g", UnitWeight);
1076 if (pAppSettingsTranslation) {
1077 return pAppSettingsTranslation->rawTranslator(grams);
1084 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"g", UnitWeight);
1085 if (pAppSettingsTranslation) {
1086 return pAppSettingsTranslation->cookedTranslator(weight);
1094 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"m/s", UnitSpeed);
1095 if (pAppSettingsTranslation) {
1096 return pAppSettingsTranslation->rawTranslator(metersSecond);
1098 return metersSecond;
1104 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"m/s", UnitSpeed);
1105 if (pAppSettingsTranslation) {
1106 return pAppSettingsTranslation->cookedTranslator(speed);
1114 const AppSettingsTranslation_s *
const pAppSettingsTranslation = _findAppSettingsUnitsTranslation(
"m/s", UnitSpeed);
1115 if (pAppSettingsTranslation) {
1116 return pAppSettingsTranslation->cookedUnits;
1118 return QStringLiteral(
"m/s");
1124 return _rawTranslator(this->
rawIncrement()).toDouble();
1133 double increment = _rawTranslator(this->
rawIncrement()).toDouble();
1134 if (!qIsNaN(increment)) {
1135 double integralPart;
1138 increment = fabs(modf(increment, &integralPart));
1139 if (increment == 0.0) {
1141 incrementDecimalPlaces = 0;
1143 incrementDecimalPlaces = -ceil(log10(increment));
1149 actualDecimalPlaces = incrementDecimalPlaces;
1153 const double ctest = _rawTranslator(1.0).toDouble();
1155 settingsDecimalPlaces += -log10(ctest);
1157 settingsDecimalPlaces = qMin(25, settingsDecimalPlaces);
1158 settingsDecimalPlaces = qMax(0, settingsDecimalPlaces);
1160 actualDecimalPlaces = settingsDecimalPlaces;
1163 actualDecimalPlaces = _decimalPlaces;
1166 return actualDecimalPlaces;
1173 static const QList<JsonHelper::KeyValidateInfo> keyInfoList = {
1174 { _nameJsonKey, QJsonValue::String,
true },
1175 { _typeJsonKey, QJsonValue::String,
true },
1176 { _shortDescriptionJsonKey, QJsonValue::String,
false },
1177 { _longDescriptionJsonKey, QJsonValue::String,
false },
1178 { _unitsJsonKey, QJsonValue::String,
false },
1179 { _decimalPlacesJsonKey, QJsonValue::Double,
false },
1180 { _minJsonKey, QJsonValue::Double,
false },
1181 { _maxJsonKey, QJsonValue::Double,
false },
1182 { _userMinJsonKey, QJsonValue::Double,
false },
1183 { _userMaxJsonKey, QJsonValue::Double,
false },
1184 { _hasControlJsonKey, QJsonValue::Bool,
false },
1185 { _qgcRebootRequiredJsonKey, QJsonValue::Bool,
false },
1186 { _rebootRequiredJsonKey, QJsonValue::Bool,
false },
1187 { _categoryJsonKey, QJsonValue::String,
false },
1188 { _groupJsonKey, QJsonValue::String,
false },
1189 { _volatileJsonKey, QJsonValue::Bool,
false },
1190 { _enumBitmaskArrayJsonKey, QJsonValue::Array,
false },
1191 { _enumValuesArrayJsonKey, QJsonValue::Array,
false },
1192 { _enumValuesJsonKey, QJsonValue::String,
false },
1193 { _enumStringsJsonKey, QJsonValue::String,
false },
1204 qWarning(FactMetaDataLog) <<
"Unknown type" << json[_typeJsonKey].toString();
1210 metaData->_name = json[_nameJsonKey].toString();
1212 QStringList rgDescriptions;
1213 QList<double> rgDoubleValues;
1214 QList<int> rgIntValues;
1215 QStringList rgStringValues;
1217 bool foundBitmask =
false;
1218 if (!_parseValuesArray(json, rgDescriptions, rgDoubleValues,
errorString)) {
1219 qWarning(FactMetaDataLog) << QStringLiteral(
"FactMetaData::createFromJsonObject _parseValueDescriptionArray for '%1' failed. %2").arg(metaData->
name(),
errorString);
1221 if (rgDescriptions.isEmpty()) {
1222 if (!_parseBitmaskArray(json, rgDescriptions, rgIntValues,
errorString)) {
1223 qWarning(FactMetaDataLog) << QStringLiteral(
"FactMetaData::createFromJsonObject _parseBitmaskArray for '%1' failed. %2").arg(metaData->
name(),
errorString);
1225 foundBitmask = rgDescriptions.count() != 0;
1227 if (rgDescriptions.isEmpty()) {
1228 if (!_parseEnum(metaData->_name, json, defineMap, rgDescriptions, rgStringValues,
errorString)) {
1229 qWarning(FactMetaDataLog) << QStringLiteral(
"FactMetaData::createFromJsonObject _parseEnum for '%1' failed. %2").arg(metaData->
name(),
errorString);
1233 if (
errorString.isEmpty() && !rgDescriptions.isEmpty()) {
1234 for (qsizetype i = 0; i < rgDescriptions.count(); i++) {
1236 metaData->
addBitmaskInfo(rgDescriptions[i], 1 << rgIntValues[i]);
1238 const QVariant rawValueVariant = !rgDoubleValues.isEmpty() ? QVariant(rgDoubleValues[i]) : QVariant(rgStringValues[i]);
1239 QVariant convertedValueVariant;
1240 QString enumErrorString;
1241 if (metaData->
convertAndValidateRaw(rawValueVariant,
false , convertedValueVariant, enumErrorString)) {
1242 metaData->
addEnumInfo(rgDescriptions[i], convertedValueVariant);
1244 qWarning(FactMetaDataLog) << QStringLiteral(
"FactMetaData::createFromJsonObject convertAndValidateRaw on enum value for %1 failed.").arg(metaData->
name())
1245 <<
"type:" << metaData->
type()
1246 <<
"value:" << rawValueVariant
1247 <<
"error:" << enumErrorString;
1257 if (json.contains(_unitsJsonKey)) {
1258 metaData->
setRawUnits(json[_unitsJsonKey].toString());
1261 QString defaultValueJsonKey = _defaultValueJsonKey;
1262#if defined(Q_OS_ANDROID) || defined(Q_OS_IOS)
1263 if (json.contains(_mobileDefaultValueJsonKey)) {
1264 defaultValueJsonKey = _mobileDefaultValueJsonKey;
1268 if (json.contains(defaultValueJsonKey)) {
1269 const QJsonValue jsonValue = json[defaultValueJsonKey];
1274 QVariant typedValue;
1275 QString defaultValueErrorString;
1276 const QVariant initialValue = jsonValue.toVariant();
1281 qWarning(FactMetaDataLog) <<
"Invalid default value,"
1282 <<
"name:" << metaData->
name()
1283 <<
"type:" << metaData->
type()
1284 <<
"value:" << initialValue
1285 <<
"error:" << defaultValueErrorString;
1290 if (json.contains(_incrementJsonKey)) {
1291 QVariant typedValue;
1292 QString incrementErrorString;
1293 const QVariant initialValue = json[_incrementJsonKey].toVariant();
1297 qWarning(FactMetaDataLog) <<
"Invalid increment value,"
1298 <<
"name:" << metaData->
name()
1299 <<
"type:" << metaData->
type()
1300 <<
"value:" << initialValue
1301 <<
"error:" << incrementErrorString;
1305 if (json.contains(_minJsonKey)) {
1306 QVariant typedValue;
1307 QString minErrorString;
1308 const QVariant initialValue = json[_minJsonKey].toVariant();
1312 qWarning(FactMetaDataLog) <<
"Invalid min value,"
1313 <<
"name:" << metaData->
name()
1314 <<
"type:" << metaData->
type()
1315 <<
"value:" << initialValue
1316 <<
"error:" << minErrorString;
1320 if (json.contains(_maxJsonKey)) {
1321 QVariant typedValue;
1322 QString maxErrorString;
1323 const QVariant initialValue = json[_maxJsonKey].toVariant();
1327 qWarning(FactMetaDataLog) <<
"Invalid max value,"
1328 <<
"name:" << metaData->
name()
1329 <<
"type:" << metaData->
type()
1330 <<
"value:" << initialValue
1331 <<
"error:" << maxErrorString;
1337 if (json.contains(_userMinJsonKey)) {
1338 QVariant typedValue;
1339 QString userMinErrorString;
1340 const QVariant initialValue = json[_userMinJsonKey].toVariant();
1344 qWarning(FactMetaDataLog) <<
"Invalid userMin value,"
1345 <<
"name:" << metaData->
name()
1346 <<
"type:" << metaData->
type()
1347 <<
"value:" << initialValue
1348 <<
"error:" << userMinErrorString;
1352 if (json.contains(_userMaxJsonKey)) {
1353 QVariant typedValue;
1354 QString userMaxErrorString;
1355 const QVariant initialValue = json[_userMaxJsonKey].toVariant();
1359 qWarning(FactMetaDataLog) <<
"Invalid userMax value,"
1360 <<
"name:" << metaData->
name()
1361 <<
"type:" << metaData->
type()
1362 <<
"value:" << initialValue
1363 <<
"error:" << userMaxErrorString;
1367 bool hasControlJsonKey =
true;
1368 if (json.contains(_hasControlJsonKey)) {
1369 hasControlJsonKey = json[_hasControlJsonKey].toBool();
1374 if (json.contains(_qgcRebootRequiredJsonKey)) {
1379 bool rebootRequired =
false;
1380 if (json.contains(_rebootRequiredJsonKey)) {
1381 rebootRequired = json[_rebootRequiredJsonKey].toBool();
1386 if (json.contains(_volatileJsonKey)) {
1391 if (json.contains(_groupJsonKey)) {
1392 metaData->
setGroup(json[_groupJsonKey].toString());
1395 if (json.contains(_categoryJsonKey)) {
1396 metaData->
setCategory(json[_categoryJsonKey].toString());
1402void FactMetaData::_loadJsonDefines(
const QJsonObject &jsonDefinesObject, QMap<QString, QString> &defineMap)
1404 for (
const QString &defineName: jsonDefinesObject.keys()) {
1405 const QString mapKey = _jsonMetaDataDefinesName + QStringLiteral(
".") + defineName;
1406 defineMap[mapKey] = jsonDefinesObject[defineName].toString();
1412 QMap<QString, FactMetaData*> metaDataMap;
1418 qWarning(FactMetaDataLog) <<
"Internal Error:" <<
errorString;
1422 static const QList<JsonHelper::KeyValidateInfo> keyInfoList = {
1423 { FactMetaData::_jsonMetaDataDefinesName, QJsonValue::Object,
false },
1424 { FactMetaData::_jsonMetaDataFactsName, QJsonValue::Array,
true },
1427 qWarning(FactMetaDataLog) <<
"Json document incorrect format:" <<
errorString;
1431 QMap<QString , QString > defineMap;
1432 _loadJsonDefines(jsonObject[FactMetaData::_jsonMetaDataDefinesName].toObject(), defineMap);
1433 const QJsonArray factArray = jsonObject[FactMetaData::_jsonMetaDataFactsName].toArray();
1440 QMap<QString, FactMetaData*> metaDataMap;
1441 for (
const QJsonValue &jsonValue : jsonArray) {
1442 if (!jsonValue.isObject()) {
1443 qWarning(FactMetaDataLog) <<
"JsonValue is not an object";
1447 const QJsonObject jsonObject = jsonValue.toObject();
1449 if (metaDataMap.contains(metaData->
name())) {
1450 qWarning(FactMetaDataLog) <<
"Duplicate fact name:" << metaData->
name();
1453 metaDataMap[metaData->
name()] = metaData;
1463 return qMax(_rawTranslator(_rawMax).toDouble(), _rawTranslator(_rawMin).toDouble());
1469 return qMin(_rawTranslator(_rawMax).toDouble(), _rawTranslator(_rawMin).toDouble());
1482 const QRegularExpression splitRegex(
"[,,、]");
1483 QStringList valueList = translatedList.split(splitRegex, Qt::SkipEmptyParts);
1484 for (QString &value: valueList) {
1485 value = value.trimmed();
1490bool FactMetaData::_parseEnum(
const QString& name,
const QJsonObject &jsonObject,
const DefineMap_t &defineMap, QStringList &rgDescriptions, QStringList &rgValues, QString &
errorString)
1492 rgDescriptions.clear();
1496 if (!jsonObject.contains(_enumStringsJsonKey)) {
1500 const QString jsonStrings = jsonObject.value(_enumStringsJsonKey).toString();
1501 const QString defineMapStrings = defineMap.value(jsonStrings, jsonStrings);
1504 const QString jsonValues = jsonObject.value(_enumValuesJsonKey).toString();
1505 const QString defineMapValues = defineMap.value(jsonValues, jsonValues);
1508 if (rgDescriptions.count() != rgValues.count()) {
1509 errorString = QStringLiteral(
"Enum strings/values count mismatch - name: '%1' strings: '%2'[%3] values: '%4'[%5]").arg(
name).arg(defineMapStrings).arg(rgDescriptions.count()).arg(defineMapValues).arg(rgValues.count());
1516bool FactMetaData::_parseValuesArray(
const QJsonObject &jsonObject, QStringList &rgDescriptions, QList<double> &rgValues, QString &
errorString)
1518 rgDescriptions.clear();
1522 if (!jsonObject.contains(_enumValuesArrayJsonKey)) {
1526 static const QList<JsonHelper::KeyValidateInfo> keyInfoList = {
1527 { _enumValuesArrayDescriptionJsonKey, QJsonValue::String,
true },
1528 { _enumValuesArrayValueJsonKey, QJsonValue::Double,
true },
1531 const QJsonArray &rgValueDescription = jsonObject[_enumValuesArrayJsonKey].toArray();
1532 for (
const QJsonValue& jsonValue : rgValueDescription) {
1533 if (jsonValue.type() != QJsonValue::Object) {
1534 errorString = QStringLiteral(
"Value in \"values\" array is not an object.");
1538 const QJsonObject &valueDescriptionObject = jsonValue.toObject();
1544 rgDescriptions.append(valueDescriptionObject[_enumValuesArrayDescriptionJsonKey].toString());
1545 rgValues.append(valueDescriptionObject[_enumValuesArrayValueJsonKey].toDouble());
1551bool FactMetaData::_parseBitmaskArray(
const QJsonObject &jsonObject, QStringList &rgDescriptions, QList<int> &rgValues, QString &
errorString)
1553 rgDescriptions.clear();
1557 if (!jsonObject.contains(_enumBitmaskArrayJsonKey)) {
1561 static const QList<JsonHelper::KeyValidateInfo> keyInfoList = {
1562 { _enumBitmaskArrayDescriptionJsonKey, QJsonValue::String,
true },
1563 { _enumBitmaskArrayIndexJsonKey, QJsonValue::Double,
true },
1566 const QJsonArray &rgValueDescription = jsonObject[_enumBitmaskArrayJsonKey].toArray();
1567 for (
const QJsonValue &jsonValue : rgValueDescription) {
1568 if (jsonValue.type() != QJsonValue::Object) {
1569 errorString = QStringLiteral(
"Value in \"values\" array is not an object.");
1573 const QJsonObject &valueDescriptionObject = jsonValue.toObject();
1579 rgDescriptions.append(valueDescriptionObject[_enumBitmaskArrayDescriptionJsonKey].toString());
1580 rgValues.append(valueDescriptionObject[_enumBitmaskArrayIndexJsonKey].toInt());
1588 if (!_rawUserMin.isValid()) {
1592 return _rawTranslator(_rawUserMin);
1597 if (!_rawUserMax.isValid()) {
1601 return _rawTranslator(_rawUserMax);
#define QGC_LOGGING_CATEGORY(name, categoryStr)
@ TemperatureUnitsCelsius
@ TemperatureUnitsFarenheit
@ VerticalDistanceUnitsFeet
@ VerticalDistanceUnitsMeters
Fact *weightUnits READ weightUnits CONSTANT Fact * weightUnits()
Fact *speedUnits READ speedUnits CONSTANT Fact * speedUnits()
@ SpeedUnitsKilometersPerHour
@ SpeedUnitsFeetPerSecond
@ SpeedUnitsMetersPerSecond
Fact *horizontalDistanceUnits READ horizontalDistanceUnits CONSTANT Fact * horizontalDistanceUnits()
Fact *temperatureUnits READ temperatureUnits CONSTANT Fact * temperatureUnits()
@ AreaUnitsSquareKilometers
@ HorizontalDistanceUnitsFeet
@ HorizontalDistanceUnitsMeters
Fact *verticalDistanceUnits READ verticalDistanceUnits CONSTANT Fact * verticalDistanceUnits()
Fact *areaUnits READ areaUnits CONSTANT Fact * areaUnits()
QJsonObject openInternalQGCJsonFile(const QString &jsonFilename, const QString &expectedFileType, int minSupportedVersion, int maxSupportedVersion, int &version, QString &errorString)
returned error string if validation fails
bool validateKeys(const QJsonObject &jsonObject, const QList< KeyValidateInfo > &keyInfo, QString &errorString)