Commit 1e1b7d87 authored by Don Gagne's avatar Don Gagne

Unit conversion for FactGroup and Mission Items

parent bbdf6dde
...@@ -247,6 +247,9 @@ void FactGroup::_loadMetaData(const QString& jsonFilename) ...@@ -247,6 +247,9 @@ void FactGroup::_loadMetaData(const QString& jsonFilename)
} }
} }
// All FactGroup Facts use translator based on app settings
metaData->setAppSettingsTranslators();
_nameToFactMetaDataMap[name] = metaData; _nameToFactMetaDataMap[name] = metaData;
} }
} }
...@@ -27,17 +27,32 @@ ...@@ -27,17 +27,32 @@
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
#include "FactMetaData.h" #include "FactMetaData.h"
#include "QGroundControlQmlGlobal.h"
#include <QDebug> #include <QDebug>
#include <limits> #include <limits>
#include <cmath> #include <cmath>
const FactMetaData::BuiltInTranslation_s FactMetaData::_rgBuildInTranslations[] = { // Built in translations for all Facts
const FactMetaData::BuiltInTranslation_s FactMetaData::_rgBuiltInTranslations[] = {
{ "centi-degrees", "degrees", FactMetaData::_centiDegreesToDegrees, FactMetaData::_degreesToCentiDegrees }, { "centi-degrees", "degrees", FactMetaData::_centiDegreesToDegrees, FactMetaData::_degreesToCentiDegrees },
{ "radians", "degrees", FactMetaData::_radiansToDegrees, FactMetaData::_degreesToRadians }, { "radians", "degrees", FactMetaData::_radiansToDegrees, FactMetaData::_degreesToRadians },
}; };
// Translations driven by app settings
const FactMetaData::AppSettingsTranslation_s FactMetaData::_rgAppSettingsTranslations[] = {
{ "m", "m", false, QGroundControlQmlGlobal::DistanceUnitsMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
{ "meters", "meters", false, QGroundControlQmlGlobal::DistanceUnitsMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
{ "m/s", "m/s", true, QGroundControlQmlGlobal::SpeedUnitsMetersPerSecond, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
{ "m", "ft", false, QGroundControlQmlGlobal::DistanceUnitsFeet, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters },
{ "meters", "ft", false, QGroundControlQmlGlobal::DistanceUnitsFeet, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters },
{ "m/s", "ft/s", true, QGroundControlQmlGlobal::SpeedUnitsFeetPerSecond, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters },
{ "m/s", "mph", true, QGroundControlQmlGlobal::SpeedUnitsMilesPerHour, FactMetaData::_metersPerSecondToMilesPerHour, FactMetaData::_milesPerHourToMetersPerSecond },
{ "m/s", "km/h", true, QGroundControlQmlGlobal::SpeedUnitsKilometersPerHour, FactMetaData::_metersPerSecondToKilometersPerHour, FactMetaData::_kilometersPerHourToMetersPerSecond },
{ "m/s", "kn", true, QGroundControlQmlGlobal::SpeedUnitsKnots, FactMetaData::_metersPerSecondToKnots, FactMetaData::_knotsToMetersPerSecond },
};
FactMetaData::FactMetaData(QObject* parent) FactMetaData::FactMetaData(QObject* parent)
: QObject(parent) : QObject(parent)
, _type(valueTypeInt32) , _type(valueTypeInt32)
...@@ -323,7 +338,7 @@ void FactMetaData::setBitmaskInfo(const QStringList& strings, const QVariantList ...@@ -323,7 +338,7 @@ void FactMetaData::setBitmaskInfo(const QStringList& strings, const QVariantList
_bitmaskStrings = strings; _bitmaskStrings = strings;
_bitmaskValues = values; _bitmaskValues = values;
_setBuiltInTranslator(); setBuiltInTranslator();
} }
void FactMetaData::addBitmaskInfo(const QString& name, const QVariant& value) void FactMetaData::addBitmaskInfo(const QString& name, const QVariant& value)
...@@ -341,7 +356,7 @@ void FactMetaData::setEnumInfo(const QStringList& strings, const QVariantList& v ...@@ -341,7 +356,7 @@ void FactMetaData::setEnumInfo(const QStringList& strings, const QVariantList& v
_enumStrings = strings; _enumStrings = strings;
_enumValues = values; _enumValues = values;
_setBuiltInTranslator(); setBuiltInTranslator();
} }
void FactMetaData::addEnumInfo(const QString& name, const QVariant& value) void FactMetaData::addEnumInfo(const QString& name, const QVariant& value)
...@@ -356,15 +371,15 @@ void FactMetaData::setTranslators(Translator rawTranslator, Translator cookedTra ...@@ -356,15 +371,15 @@ void FactMetaData::setTranslators(Translator rawTranslator, Translator cookedTra
_cookedTranslator = cookedTranslator; _cookedTranslator = cookedTranslator;
} }
void FactMetaData::_setBuiltInTranslator(void) void FactMetaData::setBuiltInTranslator(void)
{ {
if (_enumStrings.count()) { if (_enumStrings.count()) {
// No translation if enum // No translation if enum
setTranslators(_defaultTranslator, _defaultTranslator); setTranslators(_defaultTranslator, _defaultTranslator);
_cookedUnits = _rawUnits; _cookedUnits = _rawUnits;
} else { } else {
for (size_t i=0; i<sizeof(_rgBuildInTranslations)/sizeof(_rgBuildInTranslations[0]); i++) { for (size_t i=0; i<sizeof(_rgBuiltInTranslations)/sizeof(_rgBuiltInTranslations[0]); i++) {
const BuiltInTranslation_s* pBuiltInTranslation = &_rgBuildInTranslations[i]; const BuiltInTranslation_s* pBuiltInTranslation = &_rgBuiltInTranslations[i];
if (pBuiltInTranslation->rawUnits == _rawUnits.toLower()) { if (pBuiltInTranslation->rawUnits == _rawUnits.toLower()) {
_cookedUnits = pBuiltInTranslation->cookedUnits; _cookedUnits = pBuiltInTranslation->cookedUnits;
...@@ -394,12 +409,52 @@ QVariant FactMetaData::_degreesToCentiDegrees(const QVariant& degrees) ...@@ -394,12 +409,52 @@ QVariant FactMetaData::_degreesToCentiDegrees(const QVariant& degrees)
return QVariant((unsigned int)(degrees.toFloat() * 100.0f)); return QVariant((unsigned int)(degrees.toFloat() * 100.0f));
} }
QVariant FactMetaData::_metersToFeet(const QVariant& meters)
{
return QVariant(meters.toDouble() * 3.28083989501);
}
QVariant FactMetaData::_feetToMeters(const QVariant& feet)
{
return QVariant(feet.toDouble() * 0.305);
}
QVariant FactMetaData::_metersPerSecondToMilesPerHour(const QVariant& metersPerSecond)
{
return QVariant((metersPerSecond.toDouble() * 0.000621371192) * 60.0 * 60.0);
}
QVariant FactMetaData::_milesPerHourToMetersPerSecond(const QVariant& milesPerHour)
{
return QVariant((milesPerHour.toDouble() * 1609.344) / (60.0 * 60.0));
}
QVariant FactMetaData::_metersPerSecondToKilometersPerHour(const QVariant& metersPerSecond)
{
return QVariant((metersPerSecond.toDouble() / 1000.0) * 60.0 * 60.0);
}
QVariant FactMetaData::_kilometersPerHourToMetersPerSecond(const QVariant& kilometersPerHour)
{
return QVariant((kilometersPerHour.toDouble() * 1000.0) / (60.0 * 60.0));
}
QVariant FactMetaData::_metersPerSecondToKnots(const QVariant& metersPerSecond)
{
return QVariant(metersPerSecond.toDouble() * 1.94384449244);
}
QVariant FactMetaData::_knotsToMetersPerSecond(const QVariant& knots)
{
return QVariant(knots.toDouble() * 0.51444444444);
}
void FactMetaData::setRawUnits(const QString& rawUnits) void FactMetaData::setRawUnits(const QString& rawUnits)
{ {
_rawUnits = rawUnits; _rawUnits = rawUnits;
_cookedUnits = rawUnits; _cookedUnits = rawUnits;
_setBuiltInTranslator(); setBuiltInTranslator();
} }
FactMetaData::ValueType_t FactMetaData::stringToType(const QString& typeString, bool& unknownType) FactMetaData::ValueType_t FactMetaData::stringToType(const QString& typeString, bool& unknownType)
...@@ -462,3 +517,20 @@ size_t FactMetaData::typeToSize(ValueType_t type) ...@@ -462,3 +517,20 @@ size_t FactMetaData::typeToSize(ValueType_t type)
return 4; return 4;
} }
} }
void FactMetaData::setAppSettingsTranslators(void)
{
if (!_enumStrings.count()) {
for (size_t i=0; i<sizeof(_rgAppSettingsTranslations)/sizeof(_rgAppSettingsTranslations[0]); i++) {
const AppSettingsTranslation_s* pAppSettingsTranslation = &_rgAppSettingsTranslations[i];
if (pAppSettingsTranslation->rawUnits == _rawUnits.toLower() &&
((pAppSettingsTranslation->speed && pAppSettingsTranslation->speedOrDistanceUnits == QGroundControlQmlGlobal::speedUnits()->rawValue().toUInt()) ||
(!pAppSettingsTranslation->speed && pAppSettingsTranslation->speedOrDistanceUnits == QGroundControlQmlGlobal::distanceUnits()->rawValue().toUInt()))) {
_cookedUnits = pAppSettingsTranslation->cookedUnits;
setTranslators(pAppSettingsTranslation->rawTranslator, pAppSettingsTranslation->cookedTranslator);
return;
}
}
}
}
...@@ -31,6 +31,7 @@ ...@@ -31,6 +31,7 @@
#include <QString> #include <QString>
#include <QVariant> #include <QVariant>
/// Holds the meta data associated with a Fact. /// Holds the meta data associated with a Fact.
/// ///
/// Holds the meta data associated with a Fact. This is kept in a seperate object from the Fact itself /// Holds the meta data associated with a Fact. This is kept in a seperate object from the Fact itself
...@@ -112,6 +113,12 @@ public: ...@@ -112,6 +113,12 @@ public:
void setTranslators(Translator rawTranslator, Translator cookedTranslator); void setTranslators(Translator rawTranslator, Translator cookedTranslator);
/// Set the translators to the standard built in versions
void setBuiltInTranslator(void);
/// Set translators according to app settings
void setAppSettingsTranslators(void);
/// Converts the specified raw value, validating against meta data /// Converts the specified raw value, validating against meta data
/// @param rawValue Value to convert, can be string /// @param rawValue Value to convert, can be string
/// @param convertOnly true: convert to correct type only, do not validate against meta data /// @param convertOnly true: convert to correct type only, do not validate against meta data
...@@ -131,7 +138,6 @@ public: ...@@ -131,7 +138,6 @@ public:
private: private:
QVariant _minForType(void) const; QVariant _minForType(void) const;
QVariant _maxForType(void) const; QVariant _maxForType(void) const;
void _setBuiltInTranslator(void);
// Built in translators // Built in translators
static QVariant _defaultTranslator(const QVariant& from) { return from; } static QVariant _defaultTranslator(const QVariant& from) { return from; }
...@@ -139,6 +145,14 @@ private: ...@@ -139,6 +145,14 @@ private:
static QVariant _radiansToDegrees(const QVariant& radians); static QVariant _radiansToDegrees(const QVariant& radians);
static QVariant _centiDegreesToDegrees(const QVariant& centiDegrees); static QVariant _centiDegreesToDegrees(const QVariant& centiDegrees);
static QVariant _degreesToCentiDegrees(const QVariant& degrees); static QVariant _degreesToCentiDegrees(const QVariant& degrees);
static QVariant _metersToFeet(const QVariant& meters);
static QVariant _feetToMeters(const QVariant& feet);
static QVariant _metersPerSecondToMilesPerHour(const QVariant& metersPerSecond);
static QVariant _milesPerHourToMetersPerSecond(const QVariant& milesPerHour);
static QVariant _metersPerSecondToKilometersPerHour(const QVariant& metersPerSecond);
static QVariant _kilometersPerHourToMetersPerSecond(const QVariant& kilometersPerHour);
static QVariant _metersPerSecondToKnots(const QVariant& metersPerSecond);
static QVariant _knotsToMetersPerSecond(const QVariant& knots);
ValueType_t _type; // must be first for correct constructor init ValueType_t _type; // must be first for correct constructor init
int _decimalPlaces; int _decimalPlaces;
...@@ -170,8 +184,18 @@ private: ...@@ -170,8 +184,18 @@ private:
Translator cookedTranslator; Translator cookedTranslator;
}; };
static const BuiltInTranslation_s _rgBuiltInTranslations[];
static const BuiltInTranslation_s _rgBuildInTranslations[]; struct AppSettingsTranslation_s {
const char* rawUnits;
const char* cookedUnits;
bool speed;
uint32_t speedOrDistanceUnits;
Translator rawTranslator;
Translator cookedTranslator;
};
static const AppSettingsTranslation_s _rgAppSettingsTranslations[];
}; };
#endif #endif
...@@ -204,6 +204,7 @@ void SimpleMissionItem::_setupMetaData(void) ...@@ -204,6 +204,7 @@ void SimpleMissionItem::_setupMetaData(void)
_altitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble); _altitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble);
_altitudeMetaData->setRawUnits("meters"); _altitudeMetaData->setRawUnits("meters");
_altitudeMetaData->setDecimalPlaces(2); _altitudeMetaData->setDecimalPlaces(2);
_altitudeMetaData->setAppSettingsTranslators();
enumStrings.clear(); enumStrings.clear();
enumValues.clear(); enumValues.clear();
...@@ -306,12 +307,16 @@ void SimpleMissionItem::_clearParamMetaData(void) ...@@ -306,12 +307,16 @@ void SimpleMissionItem::_clearParamMetaData(void)
{ {
_param1MetaData.setRawUnits(""); _param1MetaData.setRawUnits("");
_param1MetaData.setDecimalPlaces(FactMetaData::defaultDecimalPlaces); _param1MetaData.setDecimalPlaces(FactMetaData::defaultDecimalPlaces);
_param1MetaData.setBuiltInTranslator();
_param2MetaData.setRawUnits(""); _param2MetaData.setRawUnits("");
_param2MetaData.setDecimalPlaces(FactMetaData::defaultDecimalPlaces); _param2MetaData.setDecimalPlaces(FactMetaData::defaultDecimalPlaces);
_param2MetaData.setBuiltInTranslator();
_param3MetaData.setRawUnits(""); _param3MetaData.setRawUnits("");
_param3MetaData.setDecimalPlaces(FactMetaData::defaultDecimalPlaces); _param3MetaData.setDecimalPlaces(FactMetaData::defaultDecimalPlaces);
_param3MetaData.setBuiltInTranslator();
_param4MetaData.setRawUnits(""); _param4MetaData.setRawUnits("");
_param4MetaData.setDecimalPlaces(FactMetaData::defaultDecimalPlaces); _param4MetaData.setDecimalPlaces(FactMetaData::defaultDecimalPlaces);
_param4MetaData.setBuiltInTranslator();
} }
QmlObjectListModel* SimpleMissionItem::textFieldFacts(void) QmlObjectListModel* SimpleMissionItem::textFieldFacts(void)
...@@ -366,6 +371,7 @@ QmlObjectListModel* SimpleMissionItem::textFieldFacts(void) ...@@ -366,6 +371,7 @@ QmlObjectListModel* SimpleMissionItem::textFieldFacts(void)
paramMetaData->setDecimalPlaces(paramInfo->decimalPlaces()); paramMetaData->setDecimalPlaces(paramInfo->decimalPlaces());
paramMetaData->setEnumInfo(paramInfo->enumStrings(), paramInfo->enumValues()); paramMetaData->setEnumInfo(paramInfo->enumStrings(), paramInfo->enumValues());
paramMetaData->setRawUnits(paramInfo->units()); paramMetaData->setRawUnits(paramInfo->units());
paramMetaData->setAppSettingsTranslators();
paramFact->setMetaData(paramMetaData); paramFact->setMetaData(paramMetaData);
model->append(paramFact); model->append(paramFact);
......
...@@ -157,7 +157,7 @@ static QObject* mavlinkQmlSingletonFactory(QQmlEngine*, QJSEngine*) ...@@ -157,7 +157,7 @@ static QObject* mavlinkQmlSingletonFactory(QQmlEngine*, QJSEngine*)
static QObject* qgroundcontrolQmlGlobalSingletonFactory(QQmlEngine*, QJSEngine*) static QObject* qgroundcontrolQmlGlobalSingletonFactory(QQmlEngine*, QJSEngine*)
{ {
// We create this object as a QGCTool even though it isn't int he toolbox // We create this object as a QGCTool even though it isn't in the toolbox
QGroundControlQmlGlobal* qmlGlobal = new QGroundControlQmlGlobal(qgcApp()); QGroundControlQmlGlobal* qmlGlobal = new QGroundControlQmlGlobal(qgcApp());
qmlGlobal->setToolbox(qgcApp()->toolbox()); qmlGlobal->setToolbox(qgcApp()->toolbox());
......
...@@ -30,6 +30,13 @@ ...@@ -30,6 +30,13 @@
static const char* kQmlGlobalKeyName = "QGCQml"; static const char* kQmlGlobalKeyName = "QGCQml";
SettingsFact* QGroundControlQmlGlobal::_offlineEditingFirmwareTypeFact = NULL;
FactMetaData* QGroundControlQmlGlobal::_offlineEditingFirmwareTypeMetaData = NULL;
SettingsFact* QGroundControlQmlGlobal::_distanceUnitsFact = NULL;
FactMetaData* QGroundControlQmlGlobal::_distanceUnitsMetaData = NULL;
SettingsFact* QGroundControlQmlGlobal::_speedUnitsFact = NULL;
FactMetaData* QGroundControlQmlGlobal::_speedUnitsMetaData = NULL;
const char* QGroundControlQmlGlobal::_virtualTabletJoystickKey = "VirtualTabletJoystick"; const char* QGroundControlQmlGlobal::_virtualTabletJoystickKey = "VirtualTabletJoystick";
QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app) QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app)
...@@ -41,21 +48,10 @@ QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app) ...@@ -41,21 +48,10 @@ QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app)
, _multiVehicleManager(NULL) , _multiVehicleManager(NULL)
, _mapEngineManager(NULL) , _mapEngineManager(NULL)
, _virtualTabletJoystick(false) , _virtualTabletJoystick(false)
, _offlineEditingFirmwareTypeFact(QString(), "OfflineEditingFirmwareType", FactMetaData::valueTypeUint32, (uint32_t)MAV_AUTOPILOT_ARDUPILOTMEGA)
, _offlineEditingFirmwareTypeMetaData(FactMetaData::valueTypeUint32)
{ {
QSettings settings; QSettings settings;
_virtualTabletJoystick = settings.value(_virtualTabletJoystickKey, false). toBool(); _virtualTabletJoystick = settings.value(_virtualTabletJoystickKey, false). toBool();
QStringList firmwareEnumStrings;
QVariantList firmwareEnumValues;
firmwareEnumStrings << "ArduPilot Flight Stack" << "PX4 Flight Stack" << "Mavlink Generic Flight Stack";
firmwareEnumValues << QVariant::fromValue((uint32_t)MAV_AUTOPILOT_ARDUPILOTMEGA) << QVariant::fromValue((uint32_t)MAV_AUTOPILOT_PX4) << QVariant::fromValue((uint32_t)MAV_AUTOPILOT_GENERIC);
_offlineEditingFirmwareTypeMetaData.setEnumInfo(firmwareEnumStrings, firmwareEnumValues);
_offlineEditingFirmwareTypeFact.setMetaData(&_offlineEditingFirmwareTypeMetaData);
// We clear the parent on this object since we run into shutdown problems caused by hybrid qml app. Instead we let it leak on shutdown. // We clear the parent on this object since we run into shutdown problems caused by hybrid qml app. Instead we let it leak on shutdown.
setParent(NULL); setParent(NULL);
} }
...@@ -224,3 +220,61 @@ void QGroundControlQmlGlobal::setExperimentalSurvey(bool experimentalSurvey) ...@@ -224,3 +220,61 @@ void QGroundControlQmlGlobal::setExperimentalSurvey(bool experimentalSurvey)
settings.setValue("ExperimentalSurvey", experimentalSurvey); settings.setValue("ExperimentalSurvey", experimentalSurvey);
emit experimentalSurveyChanged(experimentalSurvey); emit experimentalSurveyChanged(experimentalSurvey);
} }
Fact* QGroundControlQmlGlobal::offlineEditingFirmwareType(void)
{
if (!_offlineEditingFirmwareTypeFact) {
QStringList enumStrings;
QVariantList enumValues;
_offlineEditingFirmwareTypeFact = new SettingsFact(QString(), "OfflineEditingFirmwareType", FactMetaData::valueTypeUint32, (uint32_t)MAV_AUTOPILOT_ARDUPILOTMEGA);
_offlineEditingFirmwareTypeMetaData = new FactMetaData(FactMetaData::valueTypeUint32);
enumStrings << "ArduPilot Flight Stack" << "PX4 Flight Stack" << "Mavlink Generic Flight Stack";
enumValues << QVariant::fromValue((uint32_t)MAV_AUTOPILOT_ARDUPILOTMEGA) << QVariant::fromValue((uint32_t)MAV_AUTOPILOT_PX4) << QVariant::fromValue((uint32_t)MAV_AUTOPILOT_GENERIC);
_offlineEditingFirmwareTypeMetaData->setEnumInfo(enumStrings, enumValues);
_offlineEditingFirmwareTypeFact->setMetaData(_offlineEditingFirmwareTypeMetaData);
}
return _offlineEditingFirmwareTypeFact;
}
Fact* QGroundControlQmlGlobal::distanceUnits(void)
{
if (!_distanceUnitsFact) {
QStringList enumStrings;
QVariantList enumValues;
_distanceUnitsFact = new SettingsFact(QString(), "DistanceUnits", FactMetaData::valueTypeUint32, DistanceUnitsMeters);
_distanceUnitsMetaData = new FactMetaData(FactMetaData::valueTypeUint32);
enumStrings << "Feet" << "Meters";
enumValues << QVariant::fromValue((uint32_t)DistanceUnitsFeet) << QVariant::fromValue((uint32_t)DistanceUnitsMeters);
_distanceUnitsMetaData->setEnumInfo(enumStrings, enumValues);
_distanceUnitsFact->setMetaData(_distanceUnitsMetaData);
}
return _distanceUnitsFact;
}
Fact* QGroundControlQmlGlobal::speedUnits(void)
{
if (!_speedUnitsFact) {
QStringList enumStrings;
QVariantList enumValues;
_speedUnitsFact = new SettingsFact(QString(), "SpeedUnits", FactMetaData::valueTypeUint32, SpeedUnitsMetersPerSecond);
_speedUnitsMetaData = new FactMetaData(FactMetaData::valueTypeUint32);
enumStrings << "Feet per second" << "Meters per second" << "Miles per hour" << "Kilometers per hour" << "Knots";
enumValues << QVariant::fromValue((uint32_t)SpeedUnitsFeetPerSecond) << QVariant::fromValue((uint32_t)SpeedUnitsMetersPerSecond) << QVariant::fromValue((uint32_t)SpeedUnitsMilesPerHour) << QVariant::fromValue((uint32_t)SpeedUnitsKilometersPerHour) << QVariant::fromValue((uint32_t)SpeedUnitsKnots);
_speedUnitsMetaData->setEnumInfo(enumStrings, enumValues);
_speedUnitsFact->setMetaData(_speedUnitsMetaData);
}
return _speedUnitsFact;
}
...@@ -49,6 +49,21 @@ public: ...@@ -49,6 +49,21 @@ public:
QGroundControlQmlGlobal(QGCApplication* app); QGroundControlQmlGlobal(QGCApplication* app);
~QGroundControlQmlGlobal(); ~QGroundControlQmlGlobal();
enum DistanceUnits {
DistanceUnitsFeet = 0,
DistanceUnitsMeters
};
enum SpeedUnits {
SpeedUnitsFeetPerSecond = 0,
SpeedUnitsMetersPerSecond,
SpeedUnitsMilesPerHour,
SpeedUnitsKilometersPerHour,
SpeedUnitsKnots,
};
Q_ENUMS(DistanceUnits)
Q_ENUMS(SpeedUnits)
Q_PROPERTY(FlightMapSettings* flightMapSettings READ flightMapSettings CONSTANT) Q_PROPERTY(FlightMapSettings* flightMapSettings READ flightMapSettings CONSTANT)
Q_PROPERTY(HomePositionManager* homePositionManager READ homePositionManager CONSTANT) Q_PROPERTY(HomePositionManager* homePositionManager READ homePositionManager CONSTANT)
...@@ -75,6 +90,8 @@ public: ...@@ -75,6 +90,8 @@ public:
Q_PROPERTY(int mavlinkSystemID READ mavlinkSystemID WRITE setMavlinkSystemID NOTIFY mavlinkSystemIDChanged) Q_PROPERTY(int mavlinkSystemID READ mavlinkSystemID WRITE setMavlinkSystemID NOTIFY mavlinkSystemIDChanged)
Q_PROPERTY(Fact* offlineEditingFirmwareType READ offlineEditingFirmwareType CONSTANT) Q_PROPERTY(Fact* offlineEditingFirmwareType READ offlineEditingFirmwareType CONSTANT)
Q_PROPERTY(Fact* distanceUnits READ distanceUnits CONSTANT)
Q_PROPERTY(Fact* speedUnits READ speedUnits CONSTANT)
Q_PROPERTY(QGeoCoordinate lastKnownHomePosition READ lastKnownHomePosition CONSTANT) Q_PROPERTY(QGeoCoordinate lastKnownHomePosition READ lastKnownHomePosition CONSTANT)
Q_PROPERTY(QGeoCoordinate flightMapPosition MEMBER _flightMapPosition NOTIFY flightMapPositionChanged) Q_PROPERTY(QGeoCoordinate flightMapPosition MEMBER _flightMapPosition NOTIFY flightMapPositionChanged)
...@@ -126,7 +143,9 @@ public: ...@@ -126,7 +143,9 @@ public:
QGeoCoordinate lastKnownHomePosition() { return qgcApp()->lastKnownHomePosition(); } QGeoCoordinate lastKnownHomePosition() { return qgcApp()->lastKnownHomePosition(); }
Fact* offlineEditingFirmwareType () { return &_offlineEditingFirmwareTypeFact; } static Fact* offlineEditingFirmwareType (void);
static Fact* distanceUnits (void);
static Fact* speedUnits (void);
//-- TODO: Make this into an actual preference. //-- TODO: Make this into an actual preference.
bool isAdvancedMode () { return false; } bool isAdvancedMode () { return false; }
...@@ -177,8 +196,13 @@ private: ...@@ -177,8 +196,13 @@ private:
QGeoCoordinate _flightMapPosition; QGeoCoordinate _flightMapPosition;
double _flightMapZoom; double _flightMapZoom;
SettingsFact _offlineEditingFirmwareTypeFact; // These are static so they are available to C++ code as well as Qml
FactMetaData _offlineEditingFirmwareTypeMetaData; static SettingsFact* _offlineEditingFirmwareTypeFact;
static FactMetaData* _offlineEditingFirmwareTypeMetaData;
static SettingsFact* _distanceUnitsFact;
static FactMetaData* _distanceUnitsMetaData;
static SettingsFact* _speedUnitsFact;
static FactMetaData* _speedUnitsMetaData;
static const char* _virtualTabletJoystickKey; static const char* _virtualTabletJoystickKey;
}; };
......
...@@ -72,6 +72,54 @@ Rectangle { ...@@ -72,6 +72,54 @@ Rectangle {
width: parent.width width: parent.width
} }
//-----------------------------------------------------------------
//-- Units
Row {
spacing: ScreenTools.defaultFontPixelWidth
QGCLabel {
id: distanceUnitsLabel
anchors.baseline: distanceUnitsCombo.baseline
text: "Distance units:"
}
FactComboBox {
id: distanceUnitsCombo
width: ScreenTools.defaultFontPixelWidth * 10
fact: QGroundControl.distanceUnits
indexModel: false
}
QGCLabel {
anchors.baseline: distanceUnitsCombo.baseline
text: "(requires reboot to take affect)"
}
}
Row {
spacing: ScreenTools.defaultFontPixelWidth
QGCLabel {
anchors.baseline: speedUnitsCombo.baseline
width: distanceUnitsLabel.width
text: "Speed units:"
}
FactComboBox {
id: speedUnitsCombo
width: ScreenTools.defaultFontPixelWidth * 20
fact: QGroundControl.speedUnits
indexModel: false
}
QGCLabel {
anchors.baseline: distanceUnitsCombo.baseline
text: "(requires reboot to take affect)"
}
}
//----------------------------------------------------------------- //-----------------------------------------------------------------
//-- Audio preferences //-- Audio preferences
QGCCheckBox { QGCCheckBox {
...@@ -165,8 +213,9 @@ Rectangle { ...@@ -165,8 +213,9 @@ Rectangle {
Row { Row {
spacing: ScreenTools.defaultFontPixelWidth spacing: ScreenTools.defaultFontPixelWidth
QGCLabel { QGCLabel {
anchors.baseline: mapProviders.baseline
width: ScreenTools.defaultFontPixelWidth * 16 width: ScreenTools.defaultFontPixelWidth * 16
text: "Map Providers" text: "Map Providers:"
} }
QGCComboBox { QGCComboBox {
id: mapProviders id: mapProviders
...@@ -194,10 +243,12 @@ Rectangle { ...@@ -194,10 +243,12 @@ Rectangle {
Row { Row {
spacing: ScreenTools.defaultFontPixelWidth spacing: ScreenTools.defaultFontPixelWidth
QGCLabel { QGCLabel {
anchors.baseline: paletteCombo.baseline
width: ScreenTools.defaultFontPixelWidth * 16 width: ScreenTools.defaultFontPixelWidth * 16
text: "Style" text: "Style:"
} }
QGCComboBox { QGCComboBox {
id: paletteCombo
width: ScreenTools.defaultFontPixelWidth * 16 width: ScreenTools.defaultFontPixelWidth * 16
model: [ "Dark", "Light" ] model: [ "Dark", "Light" ]
currentIndex: QGroundControl.isDarkStyle ? 0 : 1 currentIndex: QGroundControl.isDarkStyle ? 0 : 1
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment