diff --git a/custom-example/res/CustomFlyViewOverlay.qml b/custom-example/res/CustomFlyViewOverlay.qml index ebae0ba3bb17a2533784b7c986e56763c05b491a..50bd38f3c2f50a5b50038a48b31143c070a07dcc 100644 --- a/custom-example/res/CustomFlyViewOverlay.qml +++ b/custom-example/res/CustomFlyViewOverlay.qml @@ -66,7 +66,7 @@ Item { if (activeVehicle && gcsPosition.latitude && Math.abs(gcsPosition.latitude) > 0.001 && gcsPosition.longitude && Math.abs(gcsPosition.longitude) > 0.001) { var gcs = QtPositioning.coordinate(gcsPosition.latitude, gcsPosition.longitude) var veh = activeVehicle.coordinate; - _distance = QGroundControl.metersToAppSettingsDistanceUnits(gcs.distanceTo(veh)); + _distance = QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(gcs.distanceTo(veh)); //-- Ignore absurd values if(_distance > 99999) _distance = 0; diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 642fbda510a4ef42c4c180da1096565c2bce941f..802ec4485b61ce7452597076cbc3b32de0af3a9f 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -434,6 +434,7 @@ contains (DEFINES, QGC_ENABLE_PAIRING) { # HEADERS += \ + src/QmlControls/QmlUnitsConversion.h \ src/api/QGCCorePlugin.h \ src/api/QGCOptions.h \ src/api/QGCSettings.h \ diff --git a/src/AutoPilotPlugins/APM/APMFollowComponent.qml b/src/AutoPilotPlugins/APM/APMFollowComponent.qml index 77c6c93022130dbb5cfd0a28bf3325d37bf3325e..135563f499973a71bc2272af4c670f3315badd58 100644 --- a/src/AutoPilotPlugins/APM/APMFollowComponent.qml +++ b/src/AutoPilotPlugins/APM/APMFollowComponent.qml @@ -151,7 +151,7 @@ SetupPage { } function _radiansToHeading(radians) { - var geometricAngle = QGroundControl.radiansToDegrees(radians) + var geometricAngle = QGroundControl.unitsConversion.radiansToDegrees(radians) var headingAngle = 90 - geometricAngle if (headingAngle < 0) { headingAngle += 360 @@ -163,7 +163,7 @@ SetupPage { function _headingToRadians(heading) { var geometricAngle = -(heading - 90) - return QGroundControl.degreesToRadians(geometricAngle) + return QGroundControl.unitsConversion.degreesToRadians(geometricAngle) } APMFollowComponentController { @@ -419,7 +419,7 @@ SetupPage { QGCLabel { id: distanceLabel anchors.centerIn: distanceLine - text: controller.distance.valueString + " " + QGroundControl.appSettingsDistanceUnitsString + text: controller.distance.valueString + " " + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString transform: Rotation { origin.x: distanceLabel.width / 2 @@ -497,7 +497,7 @@ SetupPage { QGCLabel { id: heightValueLabel anchors.centerIn: parent - text: controller.height.valueString + " " + QGroundControl.appSettingsDistanceUnitsString + text: controller.height.valueString + " " + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString } } diff --git a/src/AutoPilotPlugins/PX4/SafetyComponent.qml b/src/AutoPilotPlugins/PX4/SafetyComponent.qml index 2baf3f3c6d4607e91c5810902c97d882731311e2..cc027693bfe93226bdf832798783d745f5efd511 100644 --- a/src/AutoPilotPlugins/PX4/SafetyComponent.qml +++ b/src/AutoPilotPlugins/PX4/SafetyComponent.qml @@ -198,7 +198,7 @@ SetupPage { } QGCLabel { - text: qsTr("Minimum Distance: (") + QGroundControl.appSettingsDistanceUnitsString + ")" + text: qsTr("Minimum Distance: (") + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString + ")" Layout.fillWidth: true Layout.alignment: Qt.AlignVCenter } @@ -209,15 +209,15 @@ SetupPage { Layout.minimumHeight: ScreenTools.defaultFontPixelHeight * 2 Layout.fillWidth: true Layout.fillHeight: true - maximumValue: QGroundControl.metersToAppSettingsDistanceUnits(15) - minimumValue: QGroundControl.metersToAppSettingsDistanceUnits(1) + maximumValue: QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(15) + minimumValue: QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(1) stepSize: 1 displayValue: true updateValueWhileDragging: false Layout.alignment: Qt.AlignVCenter value: { if (_collisionPrevention && _collisionPrevention.rawValue > 0) { - return QGroundControl.metersToAppSettingsDistanceUnits(_collisionPrevention.rawValue) + return QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(_collisionPrevention.rawValue) } else { return 1; } @@ -226,7 +226,7 @@ SetupPage { if(_collisionPrevention) { //-- Negative means disabled if(_collisionPrevention.rawValue >= 0) { - _collisionPrevention.rawValue = QGroundControl.appSettingsDistanceUnitsToMeters(value) + _collisionPrevention.rawValue = QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsToMeters(value) } } } diff --git a/src/FactSystem/FactMetaData.cc b/src/FactSystem/FactMetaData.cc index b4b8ce4de4272c4bfc1f66837dd99f085349a14a..f3a3c2d5a164722e9b90bf4e64252f31312aae43 100644 --- a/src/FactSystem/FactMetaData.cc +++ b/src/FactSystem/FactMetaData.cc @@ -32,6 +32,11 @@ const qreal FactMetaData::UnitConsts_s::milesToMeters = 1609.344; const qreal FactMetaData::UnitConsts_s::feetToMeters = 0.3048; const qreal FactMetaData::UnitConsts_s::inchesToCentimeters = 2.54; +//Weight +const qreal FactMetaData::UnitConsts_s::ouncesToGrams = 28.3495; +const qreal FactMetaData::UnitConsts_s::poundsToGrams = 453.592; + + static const char* kDefaultCategory = QT_TRANSLATE_NOOP("FactMetaData", "Other"); static const char* kDefaultGroup = QT_TRANSLATE_NOOP("FactMetaData", "Misc"); @@ -48,27 +53,34 @@ const FactMetaData::BuiltInTranslation_s FactMetaData::_rgBuiltInTranslations[] // Translations driven by app settings const FactMetaData::AppSettingsTranslation_s FactMetaData::_rgAppSettingsTranslations[] = { - { "m", "m", FactMetaData::UnitDistance, UnitsSettings::DistanceUnitsMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator }, - { "meter", "meter", FactMetaData::UnitDistance, UnitsSettings::DistanceUnitsMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator }, - { "meters", "meters", FactMetaData::UnitDistance, UnitsSettings::DistanceUnitsMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator }, - { "cm/px", "cm/px", FactMetaData::UnitDistance, UnitsSettings::DistanceUnitsMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator }, - { "m/s", "m/s", FactMetaData::UnitSpeed, UnitsSettings::SpeedUnitsMetersPerSecond, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator }, - { "C", "C", FactMetaData::UnitTemperature, UnitsSettings::TemperatureUnitsCelsius, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator }, - { "m^2", "m^2", FactMetaData::UnitArea, UnitsSettings::AreaUnitsSquareMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator }, - { "m", "ft", FactMetaData::UnitDistance, UnitsSettings::DistanceUnitsFeet, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters }, - { "meter", "ft", FactMetaData::UnitDistance, UnitsSettings::DistanceUnitsFeet, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters }, - { "meters", "ft", FactMetaData::UnitDistance, UnitsSettings::DistanceUnitsFeet, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters }, - { "cm/px", "in/px", FactMetaData::UnitDistance, UnitsSettings::DistanceUnitsFeet, FactMetaData::_centimetersToInches, FactMetaData::_inchesToCentimeters }, - { "m^2", "km^2", FactMetaData::UnitArea, UnitsSettings::AreaUnitsSquareKilometers, FactMetaData::_squareMetersToSquareKilometers, FactMetaData::_squareKilometersToSquareMeters }, - { "m^2", "ha", FactMetaData::UnitArea, UnitsSettings::AreaUnitsHectares, FactMetaData::_squareMetersToHectares, FactMetaData::_hectaresToSquareMeters }, - { "m^2", "ft^2", FactMetaData::UnitArea, UnitsSettings::AreaUnitsSquareFeet, FactMetaData::_squareMetersToSquareFeet, FactMetaData::_squareFeetToSquareMeters }, - { "m^2", "ac", FactMetaData::UnitArea, UnitsSettings::AreaUnitsAcres, FactMetaData::_squareMetersToAcres, FactMetaData::_acresToSquareMeters }, - { "m^2", "mi^2", FactMetaData::UnitArea, UnitsSettings::AreaUnitsSquareMiles, FactMetaData::_squareMetersToSquareMiles, FactMetaData::_squareMilesToSquareMeters }, - { "m/s", "ft/s", FactMetaData::UnitSpeed, UnitsSettings::SpeedUnitsFeetPerSecond, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters }, - { "m/s", "mph", FactMetaData::UnitSpeed, UnitsSettings::SpeedUnitsMilesPerHour, FactMetaData::_metersPerSecondToMilesPerHour, FactMetaData::_milesPerHourToMetersPerSecond }, - { "m/s", "km/h", FactMetaData::UnitSpeed, UnitsSettings::SpeedUnitsKilometersPerHour, FactMetaData::_metersPerSecondToKilometersPerHour, FactMetaData::_kilometersPerHourToMetersPerSecond }, - { "m/s", "kn", FactMetaData::UnitSpeed, UnitsSettings::SpeedUnitsKnots, FactMetaData::_metersPerSecondToKnots, FactMetaData::_knotsToMetersPerSecond }, - { "C", "F", FactMetaData::UnitTemperature, UnitsSettings::TemperatureUnitsFarenheit, FactMetaData::_celsiusToFarenheit, FactMetaData::_farenheitToCelsius }, + { "m", "m", FactMetaData::UnitHorizontalDistance, UnitsSettings::HorizontalDistanceUnitsMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator }, + { "meter", "meter", FactMetaData::UnitHorizontalDistance, UnitsSettings::HorizontalDistanceUnitsMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator }, + { "meters", "meters", FactMetaData::UnitHorizontalDistance, UnitsSettings::HorizontalDistanceUnitsMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator }, + //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 + { "vertical m", "m", FactMetaData::UnitVerticalDistance, UnitsSettings::VerticalDistanceUnitsMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator }, + { "cm/px", "cm/px", FactMetaData::UnitHorizontalDistance, UnitsSettings::HorizontalDistanceUnitsMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator }, + { "m/s", "m/s", FactMetaData::UnitSpeed, UnitsSettings::SpeedUnitsMetersPerSecond, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator }, + { "C", "C", FactMetaData::UnitTemperature, UnitsSettings::TemperatureUnitsCelsius, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator }, + { "m^2", "m\u00B2", FactMetaData::UnitArea, UnitsSettings::AreaUnitsSquareMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator }, + { "m", "ft", FactMetaData::UnitHorizontalDistance, UnitsSettings::HorizontalDistanceUnitsFeet, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters }, + { "meter", "ft", FactMetaData::UnitHorizontalDistance, UnitsSettings::HorizontalDistanceUnitsFeet, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters }, + { "meters", "ft", FactMetaData::UnitHorizontalDistance, UnitsSettings::HorizontalDistanceUnitsFeet, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters }, + { "alt m", "ft", FactMetaData::UnitVerticalDistance, UnitsSettings::VerticalDistanceUnitsFeet, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters }, + { "cm/px", "in/px", FactMetaData::UnitHorizontalDistance, UnitsSettings::HorizontalDistanceUnitsFeet, FactMetaData::_centimetersToInches, FactMetaData::_inchesToCentimeters }, + { "m^2", "km\u00B2", FactMetaData::UnitArea, UnitsSettings::AreaUnitsSquareKilometers, FactMetaData::_squareMetersToSquareKilometers, FactMetaData::_squareKilometersToSquareMeters }, + { "m^2", "ha", FactMetaData::UnitArea, UnitsSettings::AreaUnitsHectares, FactMetaData::_squareMetersToHectares, FactMetaData::_hectaresToSquareMeters }, + { "m^2", "ft\u00B2", FactMetaData::UnitArea, UnitsSettings::AreaUnitsSquareFeet, FactMetaData::_squareMetersToSquareFeet, FactMetaData::_squareFeetToSquareMeters }, + { "m^2", "ac", FactMetaData::UnitArea, UnitsSettings::AreaUnitsAcres, FactMetaData::_squareMetersToAcres, FactMetaData::_acresToSquareMeters }, + { "m^2", "mi\u00B2", FactMetaData::UnitArea, UnitsSettings::AreaUnitsSquareMiles, FactMetaData::_squareMetersToSquareMiles, FactMetaData::_squareMilesToSquareMeters }, + { "m/s", "ft/s", FactMetaData::UnitSpeed, UnitsSettings::SpeedUnitsFeetPerSecond, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters }, + { "m/s", "mph", FactMetaData::UnitSpeed, UnitsSettings::SpeedUnitsMilesPerHour, FactMetaData::_metersPerSecondToMilesPerHour, FactMetaData::_milesPerHourToMetersPerSecond }, + { "m/s", "km/h", FactMetaData::UnitSpeed, UnitsSettings::SpeedUnitsKilometersPerHour, FactMetaData::_metersPerSecondToKilometersPerHour, FactMetaData::_kilometersPerHourToMetersPerSecond }, + { "m/s", "kn", FactMetaData::UnitSpeed, UnitsSettings::SpeedUnitsKnots, FactMetaData::_metersPerSecondToKnots, FactMetaData::_knotsToMetersPerSecond }, + { "C", "F", FactMetaData::UnitTemperature, UnitsSettings::TemperatureUnitsFarenheit, FactMetaData::_celsiusToFarenheit, FactMetaData::_farenheitToCelsius }, + { "g", "g", FactMetaData::UnitWeight, UnitsSettings::WeightUnitsGrams, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator }, + { "g", "kg", FactMetaData::UnitWeight, UnitsSettings::WeightUnitsKg, FactMetaData::_gramsToKilograms, FactMetaData::_kilogramsToGrams }, + { "g", "oz", FactMetaData::UnitWeight, UnitsSettings::WeightUnitsOz, FactMetaData::_gramsToOunces, FactMetaData::_ouncesToGrams }, + { "g", "lbs", FactMetaData::UnitWeight, UnitsSettings::WeightUnitsLbs, FactMetaData::_gramsToPunds, FactMetaData::_poundsToGrams }, }; const char* FactMetaData::_decimalPlacesJsonKey = "decimalPlaces"; @@ -790,6 +802,30 @@ QVariant FactMetaData::_farenheitToCelsius(const QVariant& farenheit) return QVariant((farenheit.toDouble() - 32) * (5.0 / 9.0)); } +QVariant FactMetaData::_kilogramsToGrams(const QVariant& kg) { + return QVariant(kg.toDouble() * 1000); +} + +QVariant FactMetaData::_ouncesToGrams(const QVariant& oz) { + return QVariant(oz.toDouble() * constants.ouncesToGrams); +} + +QVariant FactMetaData::_poundsToGrams(const QVariant& lbs) { + return QVariant(lbs.toDouble() * constants.poundsToGrams); +} + +QVariant FactMetaData::_gramsToKilograms(const QVariant& g) { + return QVariant(g.toDouble() / 1000); +} + +QVariant FactMetaData::_gramsToOunces(const QVariant& g) { + return QVariant(g.toDouble() / constants.ouncesToGrams); +} + +QVariant FactMetaData::_gramsToPunds(const QVariant& g) { + return QVariant(g.toDouble() / constants.poundsToGrams); +} + void FactMetaData::setRawUnits(const QString& rawUnits) { _rawUnits = rawUnits; @@ -892,8 +928,11 @@ void FactMetaData::_setAppSettingsTranslators(void) uint settingsUnits = 0; switch (pAppSettingsTranslation->unitType) { - case UnitDistance: - settingsUnits = settings->distanceUnits()->rawValue().toUInt(); + case UnitHorizontalDistance: + settingsUnits = settings->horizontalDistanceUnits()->rawValue().toUInt(); + break; + case UnitVerticalDistance: + settingsUnits = settings->verticalDistanceUnits()->rawValue().toUInt(); break; case UnitSpeed: settingsUnits = settings->speedUnits()->rawValue().toUInt(); @@ -904,6 +943,9 @@ void FactMetaData::_setAppSettingsTranslators(void) case UnitTemperature: settingsUnits = settings->temperatureUnits()->rawValue().toUInt(); break; + case UnitWeight: + settingsUnits = settings->weightUnits()->rawValue().toUInt(); + break; default: break; } @@ -917,7 +959,45 @@ void FactMetaData::_setAppSettingsTranslators(void) } } -const FactMetaData::AppSettingsTranslation_s* FactMetaData::_findAppSettingsDistanceUnitsTranslation(const QString& rawUnits) +const FactMetaData::AppSettingsTranslation_s* FactMetaData::_findAppSettingsHorizontalDistanceUnitsTranslation(const QString& rawUnits) +{ + for (size_t i=0; irawUnits.toLower()) { + continue; + } + + uint settingsUnits = qgcApp()->toolbox()->settingsManager()->unitsSettings()->horizontalDistanceUnits()->rawValue().toUInt(); + + if (pAppSettingsTranslation->unitType == UnitHorizontalDistance + && pAppSettingsTranslation->unitOption == settingsUnits) { + return pAppSettingsTranslation; + } + } + return nullptr; +} + +const FactMetaData::AppSettingsTranslation_s* FactMetaData::_findAppSettingsVerticalDistanceUnitsTranslation(const QString& rawUnits) +{ + for (size_t i=0; irawUnits.toLower()) { + continue; + } + + uint settingsUnits = qgcApp()->toolbox()->settingsManager()->unitsSettings()->verticalDistanceUnits()->rawValue().toUInt(); + + if (pAppSettingsTranslation->unitType == UnitVerticalDistance + && pAppSettingsTranslation->unitOption == settingsUnits) { + return pAppSettingsTranslation; + } + } + return nullptr; +} + +const FactMetaData::AppSettingsTranslation_s* FactMetaData::_findAppSettingsWeightUnitsTranslation(const QString& rawUnits) { for (size_t i=0; itoolbox()->settingsManager()->unitsSettings()->distanceUnits()->rawValue().toUInt(); + uint settingsUnits = qgcApp()->toolbox()->settingsManager()->unitsSettings()->weightUnits()->rawValue().toUInt(); - if (pAppSettingsTranslation->unitType == UnitDistance + if (pAppSettingsTranslation->unitType == UnitWeight && pAppSettingsTranslation->unitOption == settingsUnits) { return pAppSettingsTranslation; } @@ -956,9 +1036,19 @@ const FactMetaData::AppSettingsTranslation_s* FactMetaData::_findAppSettingsArea return nullptr; } -QVariant FactMetaData::metersToAppSettingsDistanceUnits(const QVariant& meters) +QVariant FactMetaData::metersToAppSettingsHorizontalDistanceUnits(const QVariant& meters) +{ + const AppSettingsTranslation_s* pAppSettingsTranslation = _findAppSettingsHorizontalDistanceUnitsTranslation("m"); + if (pAppSettingsTranslation) { + return pAppSettingsTranslation->rawTranslator(meters); + } else { + return meters; + } +} + +QVariant FactMetaData::metersToAppSettingsVerticalDistanceUnits(const QVariant& meters) { - const AppSettingsTranslation_s* pAppSettingsTranslation = _findAppSettingsDistanceUnitsTranslation("m"); + const AppSettingsTranslation_s* pAppSettingsTranslation = _findAppSettingsVerticalDistanceUnitsTranslation("vertical m"); if (pAppSettingsTranslation) { return pAppSettingsTranslation->rawTranslator(meters); } else { @@ -966,9 +1056,9 @@ QVariant FactMetaData::metersToAppSettingsDistanceUnits(const QVariant& meters) } } -QVariant FactMetaData::appSettingsDistanceUnitsToMeters(const QVariant& distance) +QVariant FactMetaData::appSettingsHorizontalDistanceUnitsToMeters(const QVariant& distance) { - const AppSettingsTranslation_s* pAppSettingsTranslation = _findAppSettingsDistanceUnitsTranslation("m"); + const AppSettingsTranslation_s* pAppSettingsTranslation = _findAppSettingsHorizontalDistanceUnitsTranslation("m"); if (pAppSettingsTranslation) { return pAppSettingsTranslation->cookedTranslator(distance); } else { @@ -976,9 +1066,19 @@ QVariant FactMetaData::appSettingsDistanceUnitsToMeters(const QVariant& distance } } -QString FactMetaData::appSettingsDistanceUnitsString(void) +QVariant FactMetaData::appSettingsVerticalDistanceUnitsToMeters(const QVariant& distance) { - const AppSettingsTranslation_s* pAppSettingsTranslation = _findAppSettingsDistanceUnitsTranslation("m"); + const AppSettingsTranslation_s* pAppSettingsTranslation = _findAppSettingsVerticalDistanceUnitsTranslation("alt m"); + if (pAppSettingsTranslation) { + return pAppSettingsTranslation->cookedTranslator(distance); + } else { + return distance; + } +} + +QString FactMetaData::appSettingsHorizontalDistanceUnitsString(void) +{ + const AppSettingsTranslation_s* pAppSettingsTranslation = _findAppSettingsHorizontalDistanceUnitsTranslation("m"); if (pAppSettingsTranslation) { return pAppSettingsTranslation->cookedUnits; } else { @@ -986,6 +1086,26 @@ QString FactMetaData::appSettingsDistanceUnitsString(void) } } +QString FactMetaData::appSettingsVerticalDistanceUnitsString(void) +{ + const AppSettingsTranslation_s* pAppSettingsTranslation = _findAppSettingsVerticalDistanceUnitsTranslation("alt m"); + if (pAppSettingsTranslation) { + return pAppSettingsTranslation->cookedUnits; + } else { + return QStringLiteral("m"); + } +} + +QString FactMetaData::appSettingsWeightUnitsString(void) +{ + const AppSettingsTranslation_s* pAppSettingsTranslation = _findAppSettingsWeightUnitsTranslation("g"); + if (pAppSettingsTranslation) { + return pAppSettingsTranslation->cookedUnits; + } else { + return QStringLiteral("g"); + } +} + QVariant FactMetaData::squareMetersToAppSettingsAreaUnits(const QVariant& squareMeters) { const AppSettingsTranslation_s* pAppSettingsTranslation = _findAppSettingsAreaUnitsTranslation("m^2"); @@ -1016,6 +1136,25 @@ QString FactMetaData::appSettingsAreaUnitsString(void) } } +QVariant FactMetaData::gramsToAppSettingsWeightUnits(const QVariant& grams) { + const AppSettingsTranslation_s* pAppSettingsTranslation = _findAppSettingsWeightUnitsTranslation("g"); + if (pAppSettingsTranslation) { + return pAppSettingsTranslation->rawTranslator(grams); + } else { + return grams; + } +} + +QVariant FactMetaData::appSettingsWeightUnitsToGrams(const QVariant& weight) { + const AppSettingsTranslation_s* pAppSettingsTranslation = _findAppSettingsWeightUnitsTranslation("g"); + if (pAppSettingsTranslation) { + return pAppSettingsTranslation->cookedTranslator(weight); + } else { + return weight; + } +} + + double FactMetaData::cookedIncrement(void) const { return _rawTranslator(this->rawIncrement()).toDouble(); diff --git a/src/FactSystem/FactMetaData.h b/src/FactSystem/FactMetaData.h index c6c1484c2a7af43e7e63495de0f61010595091d3..e63d307e613b3d1097881d7cc06e4ac1139e913f 100644 --- a/src/FactSystem/FactMetaData.h +++ b/src/FactSystem/FactMetaData.h @@ -60,14 +60,32 @@ public: const FactMetaData& operator=(const FactMetaData& other); - /// Converts from meters to the user specified distance unit - static QVariant metersToAppSettingsDistanceUnits(const QVariant& meters); + /// Converts from meters to the user specified horizontal distance unit + static QVariant metersToAppSettingsHorizontalDistanceUnits(const QVariant& meters); - /// Converts from user specified distance unit to meters - static QVariant appSettingsDistanceUnitsToMeters(const QVariant& distance); + /// Converts from user specified horizontal distance unit to meters + static QVariant appSettingsHorizontalDistanceUnitsToMeters(const QVariant& distance); - /// Returns the string for distance units which has configued by user - static QString appSettingsDistanceUnitsString(void); + /// Returns the string for horizontal distance units which has configued by user + static QString appSettingsHorizontalDistanceUnitsString(void); + + /// Converts from meters to the user specified vertical distance unit + static QVariant metersToAppSettingsVerticalDistanceUnits(const QVariant& meters); + + /// Converts from user specified vertical distance unit to meters + static QVariant appSettingsVerticalDistanceUnitsToMeters(const QVariant& distance); + + /// Returns the string for vertical distance units which has configued by user + static QString appSettingsVerticalDistanceUnitsString(void); + + /// Converts from grams to the user specified weight unit + static QVariant gramsToAppSettingsWeightUnits(const QVariant& grams); + + /// Converts from user specified weight unit to grams + static QVariant appSettingsWeightUnitsToGrams(const QVariant& weight); + + /// Returns the string for weight units which has configued by user + static QString appSettingsWeightUnitsString(void); /// Converts from meters to the user specified distance unit static QVariant squareMetersToAppSettingsAreaUnits(const QVariant& squareMeters); @@ -209,25 +227,36 @@ private: static QVariant _inchesToCentimeters(const QVariant& inches); static QVariant _celsiusToFarenheit(const QVariant& celsius); static QVariant _farenheitToCelsius(const QVariant& farenheit); + static QVariant _kilogramsToGrams(const QVariant& kg); + static QVariant _ouncesToGrams(const QVariant& oz); + static QVariant _poundsToGrams(const QVariant& lbs); + static QVariant _gramsToKilograms(const QVariant& g); + static QVariant _gramsToOunces(const QVariant& g); + static QVariant _gramsToPunds(const QVariant& g); + enum UnitTypes { - UnitDistance = 0, + UnitHorizontalDistance = 0, + UnitVerticalDistance, UnitArea, UnitSpeed, - UnitTemperature + UnitTemperature, + UnitWeight }; struct AppSettingsTranslation_s { - QString rawUnits; - const char* cookedUnits; - UnitTypes unitType; - uint32_t unitOption; - Translator rawTranslator; - Translator cookedTranslator; + QString rawUnits; + const char* cookedUnits; + UnitTypes unitType; + uint32_t unitOption; + Translator rawTranslator; + Translator cookedTranslator; }; - static const AppSettingsTranslation_s* _findAppSettingsDistanceUnitsTranslation(const QString& rawUnits); + static const AppSettingsTranslation_s* _findAppSettingsHorizontalDistanceUnitsTranslation(const QString& rawUnits); + static const AppSettingsTranslation_s* _findAppSettingsVerticalDistanceUnitsTranslation(const QString& rawUnits); static const AppSettingsTranslation_s* _findAppSettingsAreaUnitsTranslation(const QString& rawUnits); + static const AppSettingsTranslation_s* _findAppSettingsWeightUnitsTranslation(const QString& rawUnits); static void _loadJsonDefines(const QJsonObject& jsonDefinesObject, QMap& defineMap); @@ -267,6 +296,8 @@ private: static const qreal milesToMeters; static const qreal feetToMeters; static const qreal inchesToCentimeters; + static const qreal ouncesToGrams; + static const qreal poundsToGrams; } constants; struct BuiltInTranslation_s { diff --git a/src/FlightDisplay/GuidedAltitudeSlider.qml b/src/FlightDisplay/GuidedAltitudeSlider.qml index 794baf79248b0a64afe91991d0d50e66798f1dc4..8444e4f07fcb205783476023fb82f61eada9eb36 100644 --- a/src/FlightDisplay/GuidedAltitudeSlider.qml +++ b/src/FlightDisplay/GuidedAltitudeSlider.qml @@ -67,14 +67,14 @@ Rectangle { QGCLabel { id: altField anchors.horizontalCenter: parent.horizontalCenter - text: newAltitudeAppUnits + " " + QGroundControl.appSettingsDistanceUnitsString + text: newAltitudeAppUnits + " " + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString property real altGainRange: Math.max(_sliderMaxAlt - _vehicleAltitude, 0) property real altLossRange: Math.max(_vehicleAltitude - _sliderMinAlt, 0) property real altExp: Math.pow(altSlider.value, 3) property real altLossGain: altExp * (altSlider.value > 0 ? altGainRange : altLossRange) property real newAltitudeMeters: _vehicleAltitude + altLossGain - property string newAltitudeAppUnits: QGroundControl.metersToAppSettingsDistanceUnits(newAltitudeMeters).toFixed(1) + property string newAltitudeAppUnits: QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(newAltitudeMeters).toFixed(1) function setToMinimumTakeoff() { altSlider.value = Math.pow(activeVehicle.minimumTakeoffAltitude() / altGainRange, 1.0/3.0) diff --git a/src/FlightMap/MapItems/VehicleMapItem.qml b/src/FlightMap/MapItems/VehicleMapItem.qml index f5975f437d401a8f759cf14d699c71438ed55228..ab7a9505e5d0cf0c71188fa06679268a1c53cfd3 100644 --- a/src/FlightMap/MapItems/VehicleMapItem.qml +++ b/src/FlightMap/MapItems/VehicleMapItem.qml @@ -84,7 +84,7 @@ MapQuickItem { visible: _adsbVehicle ? !isNaN(altitude) : _multiVehicle property string vehicleLabelText: visible ? (_adsbVehicle ? - QGroundControl.metersToAppSettingsDistanceUnits(altitude).toFixed(0) + " " + QGroundControl.appSettingsDistanceUnitsString : + QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(altitude).toFixed(0) + " " + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString : (_multiVehicle ? qsTr("Vehicle %1").arg(vehicle.id) : "")) : "" diff --git a/src/FlightMap/MapScale.qml b/src/FlightMap/MapScale.qml index 1ec4b77ece247057dc559f9958f822da70ba30ca..b95b8ba366374b220f1f8ceb42793a7ac9be8b62 100644 --- a/src/FlightMap/MapScale.qml +++ b/src/FlightMap/MapScale.qml @@ -121,7 +121,7 @@ Item { var leftCoord = mapControl.toCoordinate(Qt.point(0, scale.y), false /* clipToViewPort */) var rightCoord = mapControl.toCoordinate(Qt.point(scaleLinePixelLength, scale.y), false /* clipToViewPort */) var scaleLineMeters = Math.round(leftCoord.distanceTo(rightCoord)) - if (QGroundControl.settingsManager.unitsSettings.distanceUnits.value === UnitsSettings.DistanceUnitsFeet) { + if (QGroundControl.settingsManager.unitsSettings.horizontalDistanceUnits.value === UnitsSettings.HorizontalDistanceUnitsFeet) { calculateFeetRatio(scaleLineMeters, scaleLinePixelLength) } else { calculateMetersRatio(scaleLineMeters, scaleLinePixelLength) diff --git a/src/MissionManager/KMLPlanDomDocument.cc b/src/MissionManager/KMLPlanDomDocument.cc index a85f8a0f9540df340b8489bda3fe0063d92c7d26..cc75ed2072a0c7e81e5940d08f59a3c042f40af1 100644 --- a/src/MissionManager/KMLPlanDomDocument.cc +++ b/src/MissionManager/KMLPlanDomDocument.cc @@ -84,8 +84,8 @@ void KMLPlanDomDocument::_addFlightPath(Vehicle* vehicle, QList rg QString htmlString; htmlString += QStringLiteral("Index: %1\n").arg(item->sequenceNumber()); htmlString += uiInfo->friendlyName() + "\n"; - htmlString += QStringLiteral("Alt AMSL: %1 %2\n").arg(QString::number(FactMetaData::metersToAppSettingsDistanceUnits(coord.altitude()).toDouble(), 'f', 2)).arg(FactMetaData::appSettingsDistanceUnitsString()); - htmlString += QStringLiteral("Alt Rel: %1 %2\n").arg(QString::number(FactMetaData::metersToAppSettingsDistanceUnits(coord.altitude() - homeCoord.altitude()).toDouble(), 'f', 2)).arg(FactMetaData::appSettingsDistanceUnitsString()); + htmlString += QStringLiteral("Alt AMSL: %1 %2\n").arg(QString::number(FactMetaData::metersToAppSettingsHorizontalDistanceUnits(coord.altitude()).toDouble(), 'f', 2)).arg(FactMetaData::appSettingsHorizontalDistanceUnitsString()); + htmlString += QStringLiteral("Alt Rel: %1 %2\n").arg(QString::number(FactMetaData::metersToAppSettingsHorizontalDistanceUnits(coord.altitude() - homeCoord.altitude()).toDouble(), 'f', 2)).arg(FactMetaData::appSettingsHorizontalDistanceUnitsString()); htmlString += QStringLiteral("Lat: %1\n").arg(QString::number(coord.latitude(), 'f', 7)); htmlString += QStringLiteral("Lon: %1\n").arg(QString::number(coord.longitude(), 'f', 7)); QDomCDATASection cdataSection = createCDATASection(htmlString); diff --git a/src/PlanView/FWLandingPatternMapVisual.qml b/src/PlanView/FWLandingPatternMapVisual.qml index dfd5879af2a40e67835d16db2279fc49829fd7ba..e54c243d27f6d08b26f7cb8094dc5dce00eced3e 100644 --- a/src/PlanView/FWLandingPatternMapVisual.qml +++ b/src/PlanView/FWLandingPatternMapVisual.qml @@ -460,8 +460,8 @@ Item { sourceItem: HeightIndicator { map: _root.map - heightText: Math.floor(QGroundControl.metersToAppSettingsDistanceUnits(_transitionAltitudeMeters)) + - QGroundControl.appSettingsDistanceUnitsString + "*" + heightText: Math.floor(QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(_transitionAltitudeMeters)) + + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString + "*" } function recalc() { @@ -492,8 +492,8 @@ Item { sourceItem: HeightIndicator { map: _root.map - heightText: Math.floor(QGroundControl.metersToAppSettingsDistanceUnits(_midSlopeAltitudeMeters)) + - QGroundControl.appSettingsDistanceUnitsString + "*" + heightText: Math.floor(QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(_midSlopeAltitudeMeters)) + + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString + "*" } function recalc() { @@ -527,7 +527,7 @@ Item { sourceItem: HeightIndicator { map: _root.map - heightText: _missionItem.loiterAltitude.value.toFixed(1) + QGroundControl.appSettingsDistanceUnitsString + heightText: _missionItem.loiterAltitude.value.toFixed(1) + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString } } } diff --git a/src/PlanView/PlanToolBarIndicators.qml b/src/PlanView/PlanToolBarIndicators.qml index a4daffa087565c988e4d8c48480f9de7abaa4e75..38f53eb0dcc2fecb0c20aa51b92573fc8c95eb4e 100644 --- a/src/PlanView/PlanToolBarIndicators.qml +++ b/src/PlanView/PlanToolBarIndicators.qml @@ -50,13 +50,13 @@ Item { property real _controllerProgressPct: _controllerValid ? _planMasterController.missionController.progressPct : 0 property bool _syncInProgress: _controllerValid ? _planMasterController.missionController.syncInProgress : false - property string _distanceText: isNaN(_distance) ? "-.-" : QGroundControl.metersToAppSettingsDistanceUnits(_distance).toFixed(1) + " " + QGroundControl.appSettingsDistanceUnitsString - property string _altDifferenceText: isNaN(_altDifference) ? "-.-" : QGroundControl.metersToAppSettingsDistanceUnits(_altDifference).toFixed(1) + " " + QGroundControl.appSettingsDistanceUnitsString + property string _distanceText: isNaN(_distance) ? "-.-" : QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(_distance).toFixed(1) + " " + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString + property string _altDifferenceText: isNaN(_altDifference) ? "-.-" : QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(_altDifference).toFixed(1) + " " + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString property string _gradientText: isNaN(_gradient) ? "-.-" : _gradient.toFixed(0) + " %" property string _azimuthText: isNaN(_azimuth) ? "-.-" : Math.round(_azimuth) % 360 property string _headingText: isNaN(_azimuth) ? "-.-" : Math.round(_heading) % 360 - property string _missionDistanceText: isNaN(_missionDistance) ? "-.-" : QGroundControl.metersToAppSettingsDistanceUnits(_missionDistance).toFixed(0) + " " + QGroundControl.appSettingsDistanceUnitsString - property string _missionMaxTelemetryText: isNaN(_missionMaxTelemetry) ? "-.-" : QGroundControl.metersToAppSettingsDistanceUnits(_missionMaxTelemetry).toFixed(0) + " " + QGroundControl.appSettingsDistanceUnitsString + property string _missionDistanceText: isNaN(_missionDistance) ? "-.-" : QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(_missionDistance).toFixed(0) + " " + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString + property string _missionMaxTelemetryText: isNaN(_missionMaxTelemetry) ? "-.-" : QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(_missionMaxTelemetry).toFixed(0) + " " + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString property string _batteryChangePointText: _batteryChangePoint < 0 ? "N/A" : _batteryChangePoint property string _batteriesRequiredText: _batteriesRequired < 0 ? "N/A" : _batteriesRequired diff --git a/src/PlanView/StructureScanEditor.qml b/src/PlanView/StructureScanEditor.qml index 621db0c507771d7d7d8b976ce59de3f5d1ce9d61..7f2139dad5bbefd3c129fae8cba1aaa43fd17cd4 100644 --- a/src/PlanView/StructureScanEditor.qml +++ b/src/PlanView/StructureScanEditor.qml @@ -221,13 +221,13 @@ Rectangle { QGCLabel { text: missionItem.layers.valueString } QGCLabel { text: qsTr("Layer Height") } - QGCLabel { text: missionItem.cameraCalc.adjustedFootprintFrontal.valueString + " " + QGroundControl.appSettingsDistanceUnitsString } + QGCLabel { text: missionItem.cameraCalc.adjustedFootprintFrontal.valueString + " " + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString } QGCLabel { text: qsTr("Top Layer Alt") } - QGCLabel { text: QGroundControl.metersToAppSettingsDistanceUnits(missionItem.topFlightAlt).toFixed(1) + " " + QGroundControl.appSettingsDistanceUnitsString } + QGCLabel { text: QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(missionItem.topFlightAlt).toFixed(1) + " " + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString } QGCLabel { text: qsTr("Bottom Layer Alt") } - QGCLabel { text: QGroundControl.metersToAppSettingsDistanceUnits(missionItem.bottomFlightAlt).toFixed(1) + " " + QGroundControl.appSettingsDistanceUnitsString } + QGCLabel { text: QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(missionItem.bottomFlightAlt).toFixed(1) + " " + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString } QGCLabel { text: qsTr("Photo Count") } QGCLabel { text: missionItem.cameraShots } @@ -236,7 +236,7 @@ Rectangle { QGCLabel { text: missionItem.timeBetweenShots.toFixed(1) + " " + qsTr("secs") } QGCLabel { text: qsTr("Trigger Distance") } - QGCLabel { text: missionItem.cameraCalc.adjustedFootprintSide.valueString + " " + QGroundControl.appSettingsDistanceUnitsString } + QGCLabel { text: missionItem.cameraCalc.adjustedFootprintSide.valueString + " " + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString } } } // Grid Column diff --git a/src/PlanView/TerrainStatus.qml b/src/PlanView/TerrainStatus.qml index ee3847a63d6372d27055d6def23790a838729694..d93ab1bab2844f31683c275bf77ade4b1a4250fa 100644 --- a/src/PlanView/TerrainStatus.qml +++ b/src/PlanView/TerrainStatus.qml @@ -48,7 +48,9 @@ Rectangle { anchors.top: parent.bottom width: parent.height font.pointSize: ScreenTools.smallFontPointSize - text: qsTr("Height AMSL (%1)").arg(QGroundControl.appSettingsDistanceUnitsString) + text: qsTr("Height AMSL (%1)").arg( + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString + ) horizontalAlignment: Text.AlignHCenter rotation: -90 transformOrigin: Item.TopLeft diff --git a/src/PlanView/TransectStyleComplexItemStats.qml b/src/PlanView/TransectStyleComplexItemStats.qml index 572622862ec29af2b845c8aea03a5ddf351f4a88..5253841e6e43cea329f99260f238ffc899c4f1a7 100644 --- a/src/PlanView/TransectStyleComplexItemStats.qml +++ b/src/PlanView/TransectStyleComplexItemStats.qml @@ -14,7 +14,7 @@ Grid { columnSpacing: ScreenTools.defaultFontPixelWidth QGCLabel { text: qsTr("Survey Area") } - QGCLabel { text: QGroundControl.squareMetersToAppSettingsAreaUnits(missionItem.coveredArea).toFixed(2) + " " + QGroundControl.appSettingsAreaUnitsString } + QGCLabel { text: QGroundControl.unitsConversion.squareMetersToAppSettingsAreaUnits(missionItem.coveredArea).toFixed(2) + " " + QGroundControl.unitsConversion.appSettingsAreaUnitsString } QGCLabel { text: qsTr("Photo Count") } QGCLabel { text: missionItem.cameraShots } diff --git a/src/QmlControls/QGroundControl/Specific/UnitsWizardPage.qml b/src/QmlControls/QGroundControl/Specific/UnitsWizardPage.qml index 80df2bab5ecc263260ed271308e958552a6ab1b0..89340650059b0baa4d1c65f2002bacc1c1bfe914 100644 --- a/src/QmlControls/QGroundControl/Specific/UnitsWizardPage.qml +++ b/src/QmlControls/QGroundControl/Specific/UnitsWizardPage.qml @@ -57,18 +57,18 @@ BaseStartupWizardPage { model: [qsTr("Metric System"), qsTr("Imperial System")] Layout.preferredWidth: _comboFieldWidth - currentIndex: QGroundControl.settingsManager.unitsSettings.distanceUnits.value === UnitsSettings.DistanceUnitsMeters ? 0 : 1 + currentIndex: QGroundControl.settingsManager.unitsSettings.horizontalDistanceUnits.value === UnitsSettings.HorizontalDistanceUnitsMeters ? 0 : 1 onActivated: { var metric = (currentIndex === 0); - QGroundControl.settingsManager.unitsSettings.distanceUnits.value = metric ? UnitsSettings.DistanceUnitsMeters : UnitsSettings.DistanceUnitsFeet + QGroundControl.settingsManager.unitsSettings.horizontalDistanceUnits.value = metric ? UnitsSettings.HorizontalDistanceUnitsMeters : UnitsSettings.HorizontalDistanceUnitsFeet QGroundControl.settingsManager.unitsSettings.areaUnits.value = metric ? UnitsSettings.AreaUnitsSquareMeters : UnitsSettings.AreaUnitsSquareFeet QGroundControl.settingsManager.unitsSettings.speedUnits.value = metric ? UnitsSettings.SpeedUnitsMetersPerSecond : UnitsSettings.SpeedUnitsFeetPerSecond QGroundControl.settingsManager.unitsSettings.temperatureUnits.value = metric ? UnitsSettings.TemperatureUnitsCelsius : UnitsSettings.TemperatureUnitsFarenheit } } Repeater { - model: [ QGroundControl.settingsManager.unitsSettings.distanceUnits, QGroundControl.settingsManager.unitsSettings.areaUnits, QGroundControl.settingsManager.unitsSettings.speedUnits, QGroundControl.settingsManager.unitsSettings.temperatureUnits ] + model: [ QGroundControl.settingsManager.unitsSettings.horizontalDistanceUnits, QGroundControl.settingsManager.unitsSettings.areaUnits, QGroundControl.settingsManager.unitsSettings.speedUnits, QGroundControl.settingsManager.unitsSettings.temperatureUnits ] FactComboBox { Layout.preferredWidth: _comboFieldWidth fact: modelData diff --git a/src/QmlControls/QGroundControlQmlGlobal.h b/src/QmlControls/QGroundControlQmlGlobal.h index a3ebcf4d6ffe8d4276e2008c1612dd0b957cf37e..57f5e89e3fe072e55cf3a79c37e584b703f8ddea 100644 --- a/src/QmlControls/QGroundControlQmlGlobal.h +++ b/src/QmlControls/QGroundControlQmlGlobal.h @@ -18,13 +18,13 @@ #include "QGCApplication.h" #include "LinkManager.h" #include "SettingsFact.h" -#include "FactMetaData.h" #include "SimulatedPosition.h" #include "QGCLoggingCategory.h" #include "AppSettings.h" #include "AirspaceManager.h" #include "ADSBVehicleManager.h" #include "QGCPalette.h" +#include "QmlUnitsConversion.h" #if defined(QGC_ENABLE_PAIRING) #include "PairingManager.h" #endif @@ -83,6 +83,7 @@ public: Q_PROPERTY(bool microhardSupported READ microhardSupported CONSTANT) Q_PROPERTY(bool supportsPairing READ supportsPairing CONSTANT) Q_PROPERTY(QGCPalette* globalPalette MEMBER _globalPalette CONSTANT) // This palette will always return enabled colors + Q_PROPERTY(QmlUnitsConversion* unitsConversion READ unitsConversion CONSTANT) #if defined(QGC_ENABLE_PAIRING) Q_PROPERTY(PairingManager* pairingManager READ pairingManager CONSTANT) #endif @@ -114,10 +115,6 @@ public: Q_PROPERTY(QString missionFileExtension READ missionFileExtension CONSTANT) Q_PROPERTY(QString telemetryFileExtension READ telemetryFileExtension CONSTANT) - /// Returns the string for distance units which has configued by user - Q_PROPERTY(QString appSettingsDistanceUnitsString READ appSettingsDistanceUnitsString CONSTANT) - Q_PROPERTY(QString appSettingsAreaUnitsString READ appSettingsAreaUnitsString CONSTANT) - Q_PROPERTY(QString qgcVersion READ qgcVersion CONSTANT) Q_PROPERTY(bool skipSetupPage READ skipSetupPage WRITE setSkipSetupPage NOTIFY skipSetupPageChanged) @@ -137,22 +134,6 @@ public: Q_INVOKABLE void startAPMArduRoverMockLink (bool sendStatusText); Q_INVOKABLE void stopOneMockLink (void); - /// Converts from meters to the user specified distance unit - Q_INVOKABLE QVariant metersToAppSettingsDistanceUnits(const QVariant& meters) const { return FactMetaData::metersToAppSettingsDistanceUnits(meters); } - - /// Converts from user specified distance unit to meters - Q_INVOKABLE QVariant appSettingsDistanceUnitsToMeters(const QVariant& distance) const { return FactMetaData::appSettingsDistanceUnitsToMeters(distance); } - - QString appSettingsDistanceUnitsString(void) const { return FactMetaData::appSettingsDistanceUnitsString(); } - - /// Converts from square meters to the user specified area unit - Q_INVOKABLE QVariant squareMetersToAppSettingsAreaUnits(const QVariant& meters) const { return FactMetaData::squareMetersToAppSettingsAreaUnits(meters); } - - /// Converts from user specified area unit to square meters - Q_INVOKABLE QVariant appSettingsAreaUnitsToSquareMeters(const QVariant& area) const { return FactMetaData::appSettingsAreaUnitsToSquareMeters(area); } - - QString appSettingsAreaUnitsString(void) const { return FactMetaData::appSettingsAreaUnitsString(); } - /// Returns the list of available logging category names. Q_INVOKABLE QStringList loggingCategories(void) const { return QGCLoggingCategoryRegister::instance()->registeredCategories(); } @@ -167,9 +148,6 @@ public: Q_INVOKABLE bool linesIntersect(QPointF xLine1, QPointF yLine1, QPointF xLine2, QPointF yLine2); - Q_INVOKABLE double degreesToRadians(double degrees) { return qDegreesToRadians(degrees); } - Q_INVOKABLE double radiansToDegrees(double radians) { return qRadiansToDegrees(radians); } - // Property accesors QString appName () { return qgcApp()->applicationName(); } @@ -185,6 +163,7 @@ public: FactGroup* gpsRtkFactGroup () { return _gpsRtkFactGroup; } AirspaceManager* airspaceManager () { return _airspaceManager; } ADSBVehicleManager* adsbVehicleManager () { return _adsbVehicleManager; } + QmlUnitsConversion* unitsConversion () { return &_unitsConversion; } #if defined(QGC_ENABLE_PAIRING) bool supportsPairing () { return true; } PairingManager* pairingManager () { return _pairingManager; } @@ -283,6 +262,7 @@ private: MicrohardManager* _microhardManager = nullptr; ADSBVehicleManager* _adsbVehicleManager = nullptr; QGCPalette* _globalPalette = nullptr; + QmlUnitsConversion _unitsConversion; #if defined(QGC_ENABLE_PAIRING) PairingManager* _pairingManager = nullptr; #endif diff --git a/src/QmlControls/QmlUnitsConversion.h b/src/QmlControls/QmlUnitsConversion.h new file mode 100644 index 0000000000000000000000000000000000000000..09d47ffc8732f9bf7b477903d8d06b93bd62ee14 --- /dev/null +++ b/src/QmlControls/QmlUnitsConversion.h @@ -0,0 +1,65 @@ +/**************************************************************************** + * + * (c) 2009-2020 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#ifndef QMLUNITSCONVERSION_H +#define QMLUNITSCONVERSION_H + +#include +#include +#include "FactMetaData.h" + +class QmlUnitsConversion : public QObject +{ + Q_OBJECT +public: + QmlUnitsConversion(QObject *parent=nullptr): QObject(parent) {} + ~QmlUnitsConversion() = default; + + Q_PROPERTY(QString appSettingsHorizontalDistanceUnitsString READ appSettingsHorizontalDistanceUnitsString CONSTANT) + Q_PROPERTY(QString appSettingsVerticalDistanceUnitsString READ appSettingsVerticalDistanceUnitsString CONSTANT) + Q_PROPERTY(QString appSettingsAreaUnitsString READ appSettingsAreaUnitsString CONSTANT) + Q_PROPERTY(QString appSettingsWeightUnitsString READ appSettingsWeightUnitsString CONSTANT) + + /// Converts from meters to the user specified distance unit + Q_INVOKABLE QVariant metersToAppSettingsHorizontalDistanceUnits(const QVariant& meters) const { return FactMetaData::metersToAppSettingsHorizontalDistanceUnits(meters); } + + /// Converts from user specified distance unit to meters + Q_INVOKABLE QVariant appSettingsHorizontalDistanceUnitsToMeters(const QVariant& distance) const { return FactMetaData::appSettingsHorizontalDistanceUnitsToMeters(distance); } + + QString appSettingsHorizontalDistanceUnitsString(void) const { return FactMetaData::appSettingsHorizontalDistanceUnitsString(); } + + /// Converts from meters to the user specified distance unit + Q_INVOKABLE QVariant metersToAppSettingsVerticalDistanceUnits(const QVariant& meters) const { return FactMetaData::metersToAppSettingsVerticalDistanceUnits(meters); } + + /// Converts from user specified distance unit to meters + Q_INVOKABLE QVariant appSettingsVerticalDistanceUnitsToMeters(const QVariant& distance) const { return FactMetaData::appSettingsVerticalDistanceUnitsToMeters(distance); } + + QString appSettingsVerticalDistanceUnitsString(void) const { return FactMetaData::appSettingsVerticalDistanceUnitsString(); } + + /// Converts from grams to the user specified weight unit + Q_INVOKABLE QVariant gramsToAppSettingsWeightUnits(const QVariant& meters) const { return FactMetaData::gramsToAppSettingsWeightUnits(meters); } + + /// Converts from user specified weight unit to grams + Q_INVOKABLE QVariant appSettingsWeightUnitsToGrams(const QVariant& distance) const { return FactMetaData::appSettingsWeightUnitsToGrams(distance); } + + QString appSettingsWeightUnitsString(void) const { return FactMetaData::appSettingsWeightUnitsString(); } + + /// Converts from square meters to the user specified area unit + Q_INVOKABLE QVariant squareMetersToAppSettingsAreaUnits(const QVariant& meters) const { return FactMetaData::squareMetersToAppSettingsAreaUnits(meters); } + + /// Converts from user specified area unit to square meters + Q_INVOKABLE QVariant appSettingsAreaUnitsToSquareMeters(const QVariant& area) const { return FactMetaData::appSettingsAreaUnitsToSquareMeters(area); } + + QString appSettingsAreaUnitsString(void) const { return FactMetaData::appSettingsAreaUnitsString(); } + + Q_INVOKABLE double degreesToRadians(double degrees) { return qDegreesToRadians(degrees); } + Q_INVOKABLE double radiansToDegrees(double radians) { return qRadiansToDegrees(radians); } +}; + +#endif // QMLUNITSCONVERSION_H diff --git a/src/Settings/UnitsSettings.cc b/src/Settings/UnitsSettings.cc index 86ba175285a4aa602896e460d22db8567e88a533..2c226fc3a9f68f2ab2036f88572fcdf7a347c3f2 100644 --- a/src/Settings/UnitsSettings.cc +++ b/src/Settings/UnitsSettings.cc @@ -17,34 +17,65 @@ DECLARE_SETTINGGROUP(Units, "Units") qmlRegisterUncreatableType("QGroundControl.SettingsManager", 1, 0, "UnitsSettings", "Reference only"); } -DECLARE_SETTINGSFACT_NO_FUNC(UnitsSettings, distanceUnits) +DECLARE_SETTINGSFACT_NO_FUNC(UnitsSettings, horizontalDistanceUnits) { - if (!_distanceUnitsFact) { + if (!_horizontalDistanceUnitsFact) { // Distance/Area/Speed units settings can't be loaded from json since it creates an infinite loop of meta data loading. QStringList enumStrings; QVariantList enumValues; enumStrings << "Feet" << "Meters"; - enumValues << QVariant::fromValue(static_cast(DistanceUnitsFeet)) << QVariant::fromValue(static_cast(DistanceUnitsMeters)); + enumValues << QVariant::fromValue(static_cast(HorizontalDistanceUnitsFeet)) + << QVariant::fromValue(static_cast(HorizontalDistanceUnitsMeters)); FactMetaData* metaData = new FactMetaData(FactMetaData::valueTypeUint32, this); - metaData->setName(distanceUnitsName); + metaData->setName(horizontalDistanceUnitsName); metaData->setShortDescription("Distance units"); metaData->setEnumInfo(enumStrings, enumValues); - DistanceUnits defaultDistanceUnit = DistanceUnitsMeters; + HorizontalDistanceUnits defaultHorizontalDistanceUnit = HorizontalDistanceUnitsMeters; switch(QLocale::system().measurementSystem()) { case QLocale::MetricSystem: { - defaultDistanceUnit = DistanceUnitsMeters; + defaultHorizontalDistanceUnit = HorizontalDistanceUnitsMeters; } break; case QLocale::ImperialUSSystem: case QLocale::ImperialUKSystem: - defaultDistanceUnit = DistanceUnitsFeet; + defaultHorizontalDistanceUnit = HorizontalDistanceUnitsFeet; break; } - metaData->setRawDefaultValue(defaultDistanceUnit); + metaData->setRawDefaultValue(defaultHorizontalDistanceUnit); metaData->setQGCRebootRequired(true); - _distanceUnitsFact = new SettingsFact(_settingsGroup, metaData, this); + _horizontalDistanceUnitsFact = new SettingsFact(_settingsGroup, metaData, this); } - return _distanceUnitsFact; + return _horizontalDistanceUnitsFact; +} + +DECLARE_SETTINGSFACT_NO_FUNC(UnitsSettings, verticalDistanceUnits) +{ + if (!_verticalDistanceUnitsFact) { + // Distance/Area/Speed units settings can't be loaded from json since it creates an infinite loop of meta data loading. + QStringList enumStrings; + QVariantList enumValues; + enumStrings << "Feet" << "Meters"; + enumValues << QVariant::fromValue(static_cast(VerticalDistanceUnitsFeet)) + << QVariant::fromValue(static_cast(VerticalDistanceUnitsMeters)); + FactMetaData* metaData = new FactMetaData(FactMetaData::valueTypeUint32, this); + metaData->setName(verticalDistanceUnitsName); + metaData->setShortDescription("Altitude units"); + metaData->setEnumInfo(enumStrings, enumValues); + VerticalDistanceUnits defaultVerticalAltitudeUnit = VerticalDistanceUnitsMeters; + switch(QLocale::system().measurementSystem()) { + case QLocale::MetricSystem: { + defaultVerticalAltitudeUnit = VerticalDistanceUnitsMeters; + } break; + case QLocale::ImperialUSSystem: + case QLocale::ImperialUKSystem: + defaultVerticalAltitudeUnit = VerticalDistanceUnitsFeet; + break; + } + metaData->setRawDefaultValue(defaultVerticalAltitudeUnit); + metaData->setQGCRebootRequired(true); + _verticalDistanceUnitsFact = new SettingsFact(_settingsGroup, metaData, this); + } + return _verticalDistanceUnitsFact; } DECLARE_SETTINGSFACT_NO_FUNC(UnitsSettings, areaUnits) @@ -147,3 +178,36 @@ DECLARE_SETTINGSFACT_NO_FUNC(UnitsSettings, temperatureUnits) } return _temperatureUnitsFact; } + +DECLARE_SETTINGSFACT_NO_FUNC(UnitsSettings, weightUnits) +{ + if (!_weightUnitsFact) { + // Units settings can't be loaded from json since it creates an infinite loop of meta data loading. + QStringList enumStrings; + QVariantList enumValues; + enumStrings << "Grams" << "Kilograms" << "Ounces" << "Pounds"; + enumValues + << QVariant::fromValue(static_cast(WeightUnitsGrams)) + << QVariant::fromValue(static_cast(WeightUnitsKg)) + << QVariant::fromValue(static_cast(WeightUnitsOz)) + << QVariant::fromValue(static_cast(WeightUnitsLbs)); + FactMetaData* metaData = new FactMetaData(FactMetaData::valueTypeUint32, this); + metaData->setName(weightUnitsName); + metaData->setShortDescription(tr("Weight units")); + metaData->setEnumInfo(enumStrings, enumValues); + WeightUnits defaultWeightUnit = WeightUnitsGrams; + switch(QLocale::system().measurementSystem()) { + case QLocale::MetricSystem: + case QLocale::ImperialUKSystem: { + defaultWeightUnit = WeightUnitsGrams; + } break; + case QLocale::ImperialUSSystem: + defaultWeightUnit = WeightUnitsOz; + break; + } + metaData->setRawDefaultValue(defaultWeightUnit); + metaData->setQGCRebootRequired(true); + _weightUnitsFact = new SettingsFact(_settingsGroup, metaData, this); + } + return _weightUnitsFact; +} diff --git a/src/Settings/UnitsSettings.h b/src/Settings/UnitsSettings.h index dab67a32ac010b7e84fcaf89d7fd34efb482ce3c..d163c5cc7b88f1a8751780634b1161a592789f76 100644 --- a/src/Settings/UnitsSettings.h +++ b/src/Settings/UnitsSettings.h @@ -19,9 +19,14 @@ class UnitsSettings : public SettingsGroup public: UnitsSettings(QObject* parent = nullptr); - enum DistanceUnits { - DistanceUnitsFeet = 0, - DistanceUnitsMeters + enum HorizontalDistanceUnits { + HorizontalDistanceUnitsFeet = 0, + HorizontalDistanceUnitsMeters + }; + + enum VerticalDistanceUnits { + VerticalDistanceUnitsFeet = 0, + VerticalDistanceUnitsMeters }; enum AreaUnits { @@ -46,17 +51,28 @@ public: TemperatureUnitsFarenheit, }; - Q_ENUM(DistanceUnits) + enum WeightUnits { + WeightUnitsGrams = 0, + WeightUnitsKg, + WeightUnitsOz, + WeightUnitsLbs + }; + + Q_ENUM(HorizontalDistanceUnits) + Q_ENUM(VerticalDistanceUnits) Q_ENUM(AreaUnits) Q_ENUM(SpeedUnits) Q_ENUM(TemperatureUnits) + Q_ENUM(WeightUnits) DEFINE_SETTING_NAME_GROUP() - DEFINE_SETTINGFACT(distanceUnits) + DEFINE_SETTINGFACT(horizontalDistanceUnits) + DEFINE_SETTINGFACT(verticalDistanceUnits) DEFINE_SETTINGFACT(areaUnits) DEFINE_SETTINGFACT(speedUnits) DEFINE_SETTINGFACT(temperatureUnits) + DEFINE_SETTINGFACT(weightUnits) }; #endif diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 6d10196501379e82ea7c9b3f98e0ad57dae6e9b0..446dd984da2fd1e1308ab7d361a2419297c6ea36 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -3150,7 +3150,7 @@ void Vehicle::guidedModeGotoLocation(const QGeoCoordinate& gotoCoord) } double maxDistance = _settingsManager->flyViewSettings()->maxGoToLocationDistance()->rawValue().toDouble(); if (coordinate().distanceTo(gotoCoord) > maxDistance) { - qgcApp()->showAppMessage(QString("New location is too far. Must be less than %1 %2.").arg(qRound(FactMetaData::metersToAppSettingsDistanceUnits(maxDistance).toDouble())).arg(FactMetaData::appSettingsDistanceUnitsString())); + qgcApp()->showAppMessage(QString("New location is too far. Must be less than %1 %2.").arg(qRound(FactMetaData::metersToAppSettingsHorizontalDistanceUnits(maxDistance).toDouble())).arg(FactMetaData::appSettingsHorizontalDistanceUnitsString())); return; } _firmwarePlugin->guidedModeGotoLocation(this, gotoCoord); diff --git a/src/ui/preferences/GeneralSettings.qml b/src/ui/preferences/GeneralSettings.qml index 213202b432a815d79978063dad1baf0291adae09..0ace1bfbd01e2b4e32d46efd31ddf5ee9fcba9af 100644 --- a/src/ui/preferences/GeneralSettings.qml +++ b/src/ui/preferences/GeneralSettings.qml @@ -99,7 +99,7 @@ Rectangle { QGCLabel { text: modelData } } Repeater { - model: [ QGroundControl.settingsManager.unitsSettings.distanceUnits, QGroundControl.settingsManager.unitsSettings.areaUnits, QGroundControl.settingsManager.unitsSettings.speedUnits, QGroundControl.settingsManager.unitsSettings.temperatureUnits ] + model: [ QGroundControl.settingsManager.unitsSettings.horizontalDistanceUnits, QGroundControl.settingsManager.unitsSettings.areaUnits, QGroundControl.settingsManager.unitsSettings.speedUnits, QGroundControl.settingsManager.unitsSettings.temperatureUnits ] FactComboBox { Layout.preferredWidth: _comboFieldWidth fact: modelData @@ -162,7 +162,7 @@ Rectangle { text: qsTr("Map Provider") width: _labelWidth } - + QGCComboBox { id: mapCombo model: QGroundControl.mapEngineManager.mapProviderList diff --git a/src/ui/toolbar/GPSRTKIndicator.qml b/src/ui/toolbar/GPSRTKIndicator.qml index c323e82de5374779f922b5838e8cf8b8b90aab8e..9ff325c5f260ee4b6d711a9d4befc64d004a5576 100644 --- a/src/ui/toolbar/GPSRTKIndicator.qml +++ b/src/ui/toolbar/GPSRTKIndicator.qml @@ -71,7 +71,7 @@ Item { visible: QGroundControl.gpsRtk.currentAccuracy.value > 0 } QGCLabel { - text: QGroundControl.gpsRtk.currentAccuracy.valueString + " " + QGroundControl.appSettingsDistanceUnitsString + text: QGroundControl.gpsRtk.currentAccuracy.valueString + " " + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString visible: QGroundControl.gpsRtk.currentAccuracy.value > 0 } QGCLabel { text: qsTr("Satellites:") }