diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index 955bc2fef664c2597264fe89bf96b1114110bfbb..71fe844ff1f83c6cda39e919e78b579bc12d6e78 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -474,6 +474,7 @@ HEADERS += \
src/QmlControls/RCChannelMonitorController.h \
src/QmlControls/ScreenToolsController.h \
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h \
+ src/SettingsManager.h \
src/Vehicle/MAVLinkLogManager.h \
src/VehicleSetup/JoystickConfigController.h \
src/audio/QGCAudioWorker.h \
@@ -635,6 +636,7 @@ SOURCES += \
src/QmlControls/RCChannelMonitorController.cc \
src/QmlControls/ScreenToolsController.cc \
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc \
+ src/SettingsManager.cc \
src/Vehicle/MAVLinkLogManager.cc \
src/VehicleSetup/JoystickConfigController.cc \
src/audio/QGCAudioWorker.cpp \
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index 48fdc14627da7988352339d23ce4348b0c95441f..8e9e8fc779bc1bd68f8aeb06186d40bb819b27e3 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -168,7 +168,7 @@
src/Vehicle/GPSFact.json
src/Vehicle/WindFact.json
src/Vehicle/VibrationFact.json
- src/QmlControls/QGroundControlQmlGlobal.json
+ src/SettingsManager.json
src/MissionManager/RallyPoint.FactMetaData.json
src/MissionManager/FWLandingPattern.FactMetaData.json
src/MissionManager/Survey.FactMetaData.json
diff --git a/src/FactSystem/FactMetaData.cc b/src/FactSystem/FactMetaData.cc
index 51fe0d09f7ef0b267c80b1e7794125c0bce808d5..6d9f47f58b066e2a4c18819b6e60564873d7b98c 100644
--- a/src/FactSystem/FactMetaData.cc
+++ b/src/FactSystem/FactMetaData.cc
@@ -14,8 +14,9 @@
/// @author Don Gagne
#include "FactMetaData.h"
-#include "QGroundControlQmlGlobal.h"
+#include "SettingsManager.h"
#include "JsonHelper.h"
+#include "QGCApplication.h"
#include
#include
@@ -45,21 +46,21 @@ const FactMetaData::BuiltInTranslation_s FactMetaData::_rgBuiltInTranslations[]
// 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^2", "m^2", false, QGroundControlQmlGlobal::AreaUnitsSquareMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
- { "m", "ft", false, QGroundControlQmlGlobal::DistanceUnitsFeet, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters },
- { "meters", "ft", false, QGroundControlQmlGlobal::DistanceUnitsFeet, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters },
- { "m^2", "km^2", false, QGroundControlQmlGlobal::AreaUnitsSquareKilometers, FactMetaData::_squareMetersToSquareKilometers, FactMetaData::_squareKilometersToSquareMeters },
- { "m^2", "ha", false, QGroundControlQmlGlobal::AreaUnitsHectares, FactMetaData::_squareMetersToHectares, FactMetaData::_hectaresToSquareMeters },
- { "m^2", "ft^2", false, QGroundControlQmlGlobal::AreaUnitsSquareFeet, FactMetaData::_squareMetersToSquareFeet, FactMetaData::_squareFeetToSquareMeters },
- { "m^2", "ac", false, QGroundControlQmlGlobal::AreaUnitsAcres, FactMetaData::_squareMetersToAcres, FactMetaData::_acresToSquareMeters },
- { "m^2", "mi^2", false, QGroundControlQmlGlobal::AreaUnitsSquareMiles, FactMetaData::_squareMetersToSquareMiles, FactMetaData::_squareMilesToSquareMeters },
- { "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 },
+ { "m", "m", false, SettingsManager::DistanceUnitsMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
+ { "meters", "meters", false, SettingsManager::DistanceUnitsMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
+ { "m/s", "m/s", true, SettingsManager::SpeedUnitsMetersPerSecond, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
+ { "m^2", "m^2", false, SettingsManager::AreaUnitsSquareMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
+ { "m", "ft", false, SettingsManager::DistanceUnitsFeet, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters },
+ { "meters", "ft", false, SettingsManager::DistanceUnitsFeet, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters },
+ { "m^2", "km^2", false, SettingsManager::AreaUnitsSquareKilometers, FactMetaData::_squareMetersToSquareKilometers, FactMetaData::_squareKilometersToSquareMeters },
+ { "m^2", "ha", false, SettingsManager::AreaUnitsHectares, FactMetaData::_squareMetersToHectares, FactMetaData::_hectaresToSquareMeters },
+ { "m^2", "ft^2", false, SettingsManager::AreaUnitsSquareFeet, FactMetaData::_squareMetersToSquareFeet, FactMetaData::_squareFeetToSquareMeters },
+ { "m^2", "ac", false, SettingsManager::AreaUnitsAcres, FactMetaData::_squareMetersToAcres, FactMetaData::_acresToSquareMeters },
+ { "m^2", "mi^2", false, SettingsManager::AreaUnitsSquareMiles, FactMetaData::_squareMetersToSquareMiles, FactMetaData::_squareMilesToSquareMeters },
+ { "m/s", "ft/s", true, SettingsManager::SpeedUnitsFeetPerSecond, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters },
+ { "m/s", "mph", true, SettingsManager::SpeedUnitsMilesPerHour, FactMetaData::_metersPerSecondToMilesPerHour, FactMetaData::_milesPerHourToMetersPerSecond },
+ { "m/s", "km/h", true, SettingsManager::SpeedUnitsKilometersPerHour, FactMetaData::_metersPerSecondToKilometersPerHour, FactMetaData::_kilometersPerHourToMetersPerSecond },
+ { "m/s", "kn", true, SettingsManager::SpeedUnitsKnots, FactMetaData::_metersPerSecondToKnots, FactMetaData::_knotsToMetersPerSecond },
};
const char* FactMetaData::_decimalPlacesJsonKey = "decimalPlaces";
@@ -612,8 +613,8 @@ void FactMetaData::_setAppSettingsTranslators(void)
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()))) {
+ ((pAppSettingsTranslation->speed && pAppSettingsTranslation->speedOrDistanceUnits == qgcApp()->toolbox()->settingsManager()->speedUnits()->rawValue().toUInt()) ||
+ (!pAppSettingsTranslation->speed && pAppSettingsTranslation->speedOrDistanceUnits == qgcApp()->toolbox()->settingsManager()->distanceUnits()->rawValue().toUInt()))) {
_cookedUnits = pAppSettingsTranslation->cookedUnits;
setTranslators(pAppSettingsTranslation->rawTranslator, pAppSettingsTranslation->cookedTranslator);
return;
@@ -628,7 +629,7 @@ const FactMetaData::AppSettingsTranslation_s* FactMetaData::_findAppSettingsDist
const AppSettingsTranslation_s* pAppSettingsTranslation = &_rgAppSettingsTranslations[i];
if (pAppSettingsTranslation->rawUnits == rawUnits &&
- (!pAppSettingsTranslation->speed && pAppSettingsTranslation->speedOrDistanceUnits == QGroundControlQmlGlobal::distanceUnits()->rawValue().toUInt())) {
+ (!pAppSettingsTranslation->speed && pAppSettingsTranslation->speedOrDistanceUnits == qgcApp()->toolbox()->settingsManager()->distanceUnits()->rawValue().toUInt())) {
return pAppSettingsTranslation;
}
}
@@ -642,7 +643,7 @@ const FactMetaData::AppSettingsTranslation_s* FactMetaData::_findAppSettingsArea
const AppSettingsTranslation_s* pAppSettingsTranslation = &_rgAppSettingsTranslations[i];
if (pAppSettingsTranslation->rawUnits == rawUnits &&
- (!pAppSettingsTranslation->speed && pAppSettingsTranslation->speedOrDistanceUnits == QGroundControlQmlGlobal::areaUnits()->rawValue().toUInt())
+ (!pAppSettingsTranslation->speed && pAppSettingsTranslation->speedOrDistanceUnits == qgcApp()->toolbox()->settingsManager()->areaUnits()->rawValue().toUInt())
) {
return pAppSettingsTranslation;
}
diff --git a/src/FactSystem/SettingsFact.cc b/src/FactSystem/SettingsFact.cc
index a3fb1821b9e1e7d374f70958bfdde1627a5d2555..71b2ddca1e4b48320a1ca424ae580003cb53bd97 100644
--- a/src/FactSystem/SettingsFact.cc
+++ b/src/FactSystem/SettingsFact.cc
@@ -9,6 +9,8 @@
#include "SettingsFact.h"
+#include "QGCCorePlugin.h"
+#include "QGCApplication.h"
#include
@@ -18,8 +20,8 @@ SettingsFact::SettingsFact(QObject* parent)
}
-SettingsFact::SettingsFact(QString settingGroup, QString settingName, FactMetaData::ValueType_t type, const QVariant& defaultValue, QObject* parent)
- : Fact(0, settingName, type, parent)
+SettingsFact::SettingsFact(QString settingGroup, FactMetaData* metaData, QObject* parent)
+ : Fact(0, metaData->name(), metaData->type(), parent)
, _settingGroup(settingGroup)
{
QSettings settings;
@@ -28,7 +30,10 @@ SettingsFact::SettingsFact(QString settingGroup, QString settingName, FactMetaDa
settings.beginGroup(_settingGroup);
}
- _rawValue = settings.value(_name, defaultValue);
+ // Allow core plugin a chance to override the default value
+ metaData->setRawDefaultValue(qgcApp()->toolbox()->corePlugin()->overrideSettingsDefault(metaData->name(), metaData->rawDefaultValue()));
+ setMetaData(metaData);
+ _rawValue = settings.value(_name, metaData->rawDefaultValue());
connect(this, &Fact::rawValueChanged, this, &SettingsFact::_rawValueChanged);
}
diff --git a/src/FactSystem/SettingsFact.h b/src/FactSystem/SettingsFact.h
index 70582454ab0d6081a735e713fb40eac2beb06f1a..0984d4764e767d0698afc4e9b15538c38a317ddf 100644
--- a/src/FactSystem/SettingsFact.h
+++ b/src/FactSystem/SettingsFact.h
@@ -23,7 +23,7 @@ class SettingsFact : public Fact
public:
SettingsFact(QObject* parent = NULL);
- SettingsFact(QString settingGroup, QString settingName, FactMetaData::ValueType_t type, const QVariant& defaultValue, QObject* parent = NULL);
+ SettingsFact(QString settingGroup, FactMetaData* metaData, QObject* parent = NULL);
SettingsFact(const SettingsFact& other, QObject* parent = NULL);
const SettingsFact& operator=(const SettingsFact& other);
diff --git a/src/FlightMap/MapScale.qml b/src/FlightMap/MapScale.qml
index 26a5dfb6f42ec0d2531657f2c0254f95d21de3cd..a861e41d5439ff4cdc09e0e381026f5f137202e2 100644
--- a/src/FlightMap/MapScale.qml
+++ b/src/FlightMap/MapScale.qml
@@ -10,9 +10,10 @@
import QtQuick 2.4
import QtQuick.Controls 1.3
-import QGroundControl 1.0
-import QGroundControl.Controls 1.0
-import QGroundControl.ScreenTools 1.0
+import QGroundControl 1.0
+import QGroundControl.Controls 1.0
+import QGroundControl.ScreenTools 1.0
+import QGroundControl.SettingsManager 1.0
/// Map scale control
Item {
@@ -114,7 +115,7 @@ Item {
var rightCoord = mapControl.toCoordinate(Qt.point(scaleLinePixelLength, scale.y))
var scaleLineMeters = Math.round(leftCoord.distanceTo(rightCoord))
- if (QGroundControl.distanceUnits.value == QGroundControl.DistanceUnitsFeet) {
+ if (QGroundControl.settingsManager.distanceUnits.value == QGroundControl.settingsManager.DistanceUnitsFeet) {
calculateFeetRatio(scaleLineMeters, scaleLinePixelLength)
} else {
calculateMetersRatio(scaleLineMeters, scaleLinePixelLength)
diff --git a/src/MissionEditor/MissionSettingsEditor.qml b/src/MissionEditor/MissionSettingsEditor.qml
index a7805187f964f692fe34fb3e87098070562f988f..3e711443a5fff06c3d9cc45f407ee450ece39af9 100644
--- a/src/MissionEditor/MissionSettingsEditor.qml
+++ b/src/MissionEditor/MissionSettingsEditor.qml
@@ -2,12 +2,13 @@ import QtQuick 2.5
import QtQuick.Controls 1.2
import QtQuick.Layouts 1.2
-import QGroundControl 1.0
-import QGroundControl.ScreenTools 1.0
-import QGroundControl.Vehicle 1.0
-import QGroundControl.Controls 1.0
-import QGroundControl.FactControls 1.0
-import QGroundControl.Palette 1.0
+import QGroundControl 1.0
+import QGroundControl.ScreenTools 1.0
+import QGroundControl.Vehicle 1.0
+import QGroundControl.Controls 1.0
+import QGroundControl.FactControls 1.0
+import QGroundControl.Palette 1.0
+import QGroundControl.SettingsManager 1.0
// Editor for Mission Settings
Rectangle {
@@ -121,7 +122,7 @@ Rectangle {
Layout.fillWidth: true
}
FactComboBox {
- fact: QGroundControl.offlineEditingFirmwareType
+ fact: QGroundControl.settingsManager.offlineEditingFirmwareType
indexModel: false
visible: _showOfflineEditingCombos
Layout.preferredWidth: _fieldWidth
@@ -145,7 +146,7 @@ Rectangle {
}
FactComboBox {
id: offlineVehicleCombo
- fact: QGroundControl.offlineEditingVehicleType
+ fact: QGroundControl.settingsManager.offlineEditingVehicleType
indexModel: false
visible: _showOfflineEditingCombos
Layout.preferredWidth: _fieldWidth
@@ -169,7 +170,7 @@ Rectangle {
Layout.fillWidth: true
}
FactTextField {
- fact: QGroundControl.offlineEditingCruiseSpeed
+ fact: QGroundControl.settingsManager.offlineEditingCruiseSpeed
visible: _showCruiseSpeed
Layout.preferredWidth: _fieldWidth
}
@@ -181,7 +182,7 @@ Rectangle {
Layout.fillWidth: true
}
FactTextField {
- fact: QGroundControl.offlineEditingHoverSpeed
+ fact: QGroundControl.settingsManager.offlineEditingHoverSpeed
visible: _showHoverSpeed
Layout.preferredWidth: _fieldWidth
}
@@ -195,7 +196,7 @@ Rectangle {
QGCLabel { text: qsTr("Hover speed:"); Layout.fillWidth: true }
FactTextField {
Layout.preferredWidth: _fieldWidth
- fact: QGroundControl.offlineEditingHoverSpeed
+ fact: QGroundControl.settingsManager.offlineEditingHoverSpeed
}
}
diff --git a/src/MissionManager/MissionCommandTree.cc b/src/MissionManager/MissionCommandTree.cc
index 1a261c18facf058331f65e01979646ba676c06f8..31f69f52fd38ac5573b4c9454df5d9fba349e04a 100644
--- a/src/MissionManager/MissionCommandTree.cc
+++ b/src/MissionManager/MissionCommandTree.cc
@@ -17,11 +17,13 @@
#include "QGroundControlQmlGlobal.h"
#include "MissionCommandUIInfo.h"
#include "MissionCommandList.h"
+#include "SettingsManager.h"
#include
MissionCommandTree::MissionCommandTree(QGCApplication* app, bool unitTest)
: QGCTool(app)
+ , _settingsManager(NULL)
, _unitTest(unitTest)
{
}
@@ -30,6 +32,8 @@ void MissionCommandTree::setToolbox(QGCToolbox* toolbox)
{
QGCTool::setToolbox(toolbox);
+ _settingsManager = toolbox->settingsManager();
+
#ifdef UNITTEST_BUILD
if (_unitTest) {
// Load unit testing tree
@@ -249,7 +253,7 @@ void MissionCommandTree::_baseVehicleInfo(Vehicle* vehicle, MAV_AUTOPILOT& baseF
baseVehicleType = _baseVehicleType(vehicle->vehicleType());
} else {
// No Vehicle means offline editing
- baseFirmwareType = _baseFirmwareType((MAV_AUTOPILOT)QGroundControlQmlGlobal::offlineEditingFirmwareType()->rawValue().toInt());
- baseVehicleType = _baseVehicleType((MAV_TYPE)QGroundControlQmlGlobal::offlineEditingVehicleType()->rawValue().toInt());
+ baseFirmwareType = _baseFirmwareType((MAV_AUTOPILOT)_settingsManager->offlineEditingFirmwareType()->rawValue().toInt());
+ baseVehicleType = _baseVehicleType((MAV_TYPE)_settingsManager->offlineEditingVehicleType()->rawValue().toInt());
}
}
diff --git a/src/MissionManager/MissionCommandTree.h b/src/MissionManager/MissionCommandTree.h
index 624bada907b435f2782e3320d272bba7d6353b45..2ac32379306139cc249efbe0e1296a370c993002 100644
--- a/src/MissionManager/MissionCommandTree.h
+++ b/src/MissionManager/MissionCommandTree.h
@@ -19,6 +19,7 @@
class MissionCommandUIInfo;
class MissionCommandList;
+class SettingsManager;
#ifdef UNITTEST_BUILD
class MissionCommandTreeTest;
#endif
@@ -87,7 +88,8 @@ private:
/// Collapsed hierarchy for specific vehicle type
QMap> _availableCategories;
- bool _unitTest; ///< true: running in unit test mode
+ SettingsManager* _settingsManager;
+ bool _unitTest; ///< true: running in unit test mode
#ifdef UNITTEST_BUILD
friend class MissionCommandTreeTest;
diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc
index 70011b715ddbf620287c76875d87f5c0fb75713d..53a209823badefbd21bdfcb52d7374a6eda8c049 100644
--- a/src/MissionManager/MissionController.cc
+++ b/src/MissionManager/MissionController.cc
@@ -20,6 +20,7 @@
#include "JsonHelper.h"
#include "ParameterManager.h"
#include "QGroundControlQmlGlobal.h"
+#include "SettingsManager.h"
#ifndef __mobile__
#include "MainWindow.h"
@@ -431,17 +432,18 @@ bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObje
// Mission Settings
QGeoCoordinate homeCoordinate;
+ SettingsManager* settingsManager = qgcApp()->toolbox()->settingsManager();
if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
return false;
}
if (json.contains(_jsonVehicleTypeKey) && vehicle->isOfflineEditingVehicle()) {
- QGroundControlQmlGlobal::offlineEditingVehicleType()->setRawValue(json[_jsonVehicleTypeKey].toDouble());
+ settingsManager->offlineEditingVehicleType()->setRawValue(json[_jsonVehicleTypeKey].toDouble());
}
if (json.contains(_jsonCruiseSpeedKey)) {
- QGroundControlQmlGlobal::offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
+ settingsManager->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
}
if (json.contains(_jsonHoverSpeedKey)) {
- QGroundControlQmlGlobal::offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
+ settingsManager->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
}
SimpleMissionItem* homeItem = new SimpleMissionItem(vehicle, visualItems);
diff --git a/src/MissionManager/RallyPointController.cc b/src/MissionManager/RallyPointController.cc
index 5a6a090aad67ec12f940403445342dd6e8b55585..66e0b76672e6dc42166b00186fd6aa4e67ba774d 100644
--- a/src/MissionManager/RallyPointController.cc
+++ b/src/MissionManager/RallyPointController.cc
@@ -21,6 +21,7 @@
#include "JsonHelper.h"
#include "SimpleMissionItem.h"
#include "QGroundControlQmlGlobal.h"
+#include "SettingsManager.h"
#ifndef __mobile__
#include "QGCFileDialog.h"
@@ -267,7 +268,7 @@ void RallyPointController::addPoint(QGeoCoordinate point)
if (_points.count()) {
defaultAlt = qobject_cast(_points[_points.count() - 1])->coordinate().altitude();
} else {
- defaultAlt = QGroundControlQmlGlobal::defaultMissionItemAltitude()->rawValue().toDouble();
+ defaultAlt = qgcApp()->toolbox()->settingsManager()->defaultMissionItemAltitude()->rawValue().toDouble();
}
point.setAltitude(defaultAlt);
RallyPoint* newPoint = new RallyPoint(point, this);
diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc
index 5464ddfd3e5326ba6c33619afba2440330cfa4dd..3d6c0de22ea6e89c9775cc4d99de815653c358c0 100644
--- a/src/MissionManager/SimpleMissionItem.cc
+++ b/src/MissionManager/SimpleMissionItem.cc
@@ -18,6 +18,7 @@
#include "MissionCommandTree.h"
#include "MissionCommandUIInfo.h"
#include "QGroundControlQmlGlobal.h"
+#include "SettingsManager.h"
FactMetaData* SimpleMissionItem::_altitudeMetaData = NULL;
FactMetaData* SimpleMissionItem::_commandMetaData = NULL;
@@ -529,7 +530,7 @@ void SimpleMissionItem::_syncFrameToAltitudeRelativeToHome(void)
void SimpleMissionItem::setDefaultsForCommand(void)
{
// We set these global defaults first, then if there are param defaults they will get reset
- _missionItem.setParam7(QGroundControlQmlGlobal::defaultMissionItemAltitude()->rawValue().toDouble());
+ _missionItem.setParam7(qgcApp()->toolbox()->settingsManager()->defaultMissionItemAltitude()->rawValue().toDouble());
MAV_CMD command = (MAV_CMD)this->command();
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, command);
diff --git a/src/MissionManager/SimpleMissionItemTest.cc b/src/MissionManager/SimpleMissionItemTest.cc
index a5172881579269714a422cf3d3e7aecb9c209f50..cf453d34edcdabf162de647672ac2c83185d324b 100644
--- a/src/MissionManager/SimpleMissionItemTest.cc
+++ b/src/MissionManager/SimpleMissionItemTest.cc
@@ -12,6 +12,7 @@
#include "SimpleMissionItem.h"
#include "QGCApplication.h"
#include "QGroundControlQmlGlobal.h"
+#include "SettingsManager.h"
const SimpleMissionItemTest::ItemInfo_t SimpleMissionItemTest::_rgItemInfo[] = {
{ MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT },
@@ -140,7 +141,7 @@ void SimpleMissionItemTest::_testDefaultValues(void)
item.missionItem().setCommand(MAV_CMD_NAV_WAYPOINT);
item.missionItem().setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
- QCOMPARE(item.missionItem().param7(), QGroundControlQmlGlobal::defaultMissionItemAltitude()->rawValue().toDouble());
+ QCOMPARE(item.missionItem().param7(), qgcApp()->toolbox()->settingsManager()->defaultMissionItemAltitude()->rawValue().toDouble());
}
void SimpleMissionItemTest::_testSignals(void)
@@ -225,7 +226,7 @@ void SimpleMissionItemTest::_testSignals(void)
// dirtyChanged
// Check that changing to the same coordinate does not signal
- simpleMissionItem.setCoordinate(QGeoCoordinate(50.1234567, 60.1234567, QGroundControlQmlGlobal::defaultMissionItemAltitude()->rawValue().toDouble()));
+ simpleMissionItem.setCoordinate(QGeoCoordinate(50.1234567, 60.1234567, qgcApp()->toolbox()->settingsManager()->defaultMissionItemAltitude()->rawValue().toDouble()));
QVERIFY(multiSpy->checkNoSignals());
// Check that actually changing coordinate signals correctly
diff --git a/src/QGCToolbox.cc b/src/QGCToolbox.cc
index 5ca81d981322f0508fdca4920c12ccc45213a974..f67e57bae205a62072ebe9769b9ee3be564c1753 100644
--- a/src/QGCToolbox.cc
+++ b/src/QGCToolbox.cc
@@ -29,6 +29,7 @@
#include "MAVLinkLogManager.h"
#include "QGCCorePlugin.h"
#include "QGCOptions.h"
+#include "SettingsManager.h"
#if defined(QGC_CUSTOM_BUILD)
#include CUSTOMHEADER
@@ -55,7 +56,11 @@ QGCToolbox::QGCToolbox(QGCApplication* app)
, _videoManager(NULL)
, _mavlinkLogManager(NULL)
, _corePlugin(NULL)
+ , _settingsManager(NULL)
{
+ // SettingsManager must be first so settings are available to any subsequent tools
+ _settingsManager = new SettingsManager(app);
+
//-- Scan and load plugins
_scanAndLoadPlugins(app);
_audioOutput = new GAudioOutput(app);
@@ -81,6 +86,9 @@ QGCToolbox::QGCToolbox(QGCApplication* app)
void QGCToolbox::setChildToolboxes(void)
{
+ // SettingsManager must be first so settings are available to any subsequent tools
+ _settingsManager->setToolbox(this);
+
_corePlugin->setToolbox(this);
_audioOutput->setToolbox(this);
_factSystem->setToolbox(this);
diff --git a/src/QGCToolbox.h b/src/QGCToolbox.h
index 717bae81acc2cf496c7bccdf34bc8ad91f9cd0f5..762996fd522828ae76db1c10366cbdcc37774427 100644
--- a/src/QGCToolbox.h
+++ b/src/QGCToolbox.h
@@ -32,6 +32,7 @@ class QGCPositionManager;
class VideoManager;
class MAVLinkLogManager;
class QGCCorePlugin;
+class SettingsManager;
/// This is used to manage all of our top level services/tools
class QGCToolbox {
@@ -56,6 +57,7 @@ public:
VideoManager* videoManager(void) { return _videoManager; }
MAVLinkLogManager* mavlinkLogManager(void) { return _mavlinkLogManager; }
QGCCorePlugin* corePlugin(void) { return _corePlugin; }
+ SettingsManager* settingsManager(void) { return _settingsManager; }
#ifndef __mobile__
GPSManager* gpsManager(void) { return _gpsManager; }
@@ -86,6 +88,7 @@ private:
VideoManager* _videoManager;
MAVLinkLogManager* _mavlinkLogManager;
QGCCorePlugin* _corePlugin;
+ SettingsManager* _settingsManager;
friend class QGCApplication;
};
diff --git a/src/QmlControls/QGroundControlQmlGlobal.cc b/src/QmlControls/QGroundControlQmlGlobal.cc
index fab97270ec637f5673ee58b987ae0082c48e41b3..df23461f73424279d6053e3decef11493da78a88 100644
--- a/src/QmlControls/QGroundControlQmlGlobal.cc
+++ b/src/QmlControls/QGroundControlQmlGlobal.cc
@@ -19,19 +19,6 @@
static const char* kQmlGlobalKeyName = "QGCQml";
-SettingsFact* QGroundControlQmlGlobal::_distanceUnitsFact = NULL;
-FactMetaData* QGroundControlQmlGlobal::_distanceUnitsMetaData = NULL;
-SettingsFact* QGroundControlQmlGlobal::_areaUnitsFact = NULL;
-FactMetaData* QGroundControlQmlGlobal::_areaUnitsMetaData = NULL;
-SettingsFact* QGroundControlQmlGlobal::_speedUnitsFact = NULL;
-FactMetaData* QGroundControlQmlGlobal::_speedUnitsMetaData = NULL;
-SettingsFact* QGroundControlQmlGlobal::_offlineEditingFirmwareTypeFact = NULL;
-SettingsFact* QGroundControlQmlGlobal::_offlineEditingVehicleTypeFact = NULL;
-SettingsFact* QGroundControlQmlGlobal::_offlineEditingCruiseSpeedFact = NULL;
-SettingsFact* QGroundControlQmlGlobal::_offlineEditingHoverSpeedFact = NULL;
-SettingsFact* QGroundControlQmlGlobal::_batteryPercentRemainingAnnounceFact = NULL;
-SettingsFact* QGroundControlQmlGlobal::_defaultMissionItemAltitudeFact = NULL;
-
const char* QGroundControlQmlGlobal::_virtualTabletJoystickKey = "VirtualTabletJoystick";
const char* QGroundControlQmlGlobal::_baseFontPointSizeKey = "BaseDeviceFontPointSize";
const char* QGroundControlQmlGlobal::_missionAutoLoadDirKey = "MissionAutoLoadDir";
@@ -48,6 +35,7 @@ QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app)
, _mavlinkLogManager(NULL)
, _corePlugin(NULL)
, _firmwarePluginManager(NULL)
+ , _settingsManager(NULL)
, _virtualTabletJoystick(false)
, _baseFontPointSize(0.0)
{
@@ -67,6 +55,7 @@ QGroundControlQmlGlobal::~QGroundControlQmlGlobal()
void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox)
{
QGCTool::setToolbox(toolbox);
+
_flightMapSettings = toolbox->flightMapSettings();
_linkManager = toolbox->linkManager();
_multiVehicleManager = toolbox->multiVehicleManager();
@@ -77,6 +66,7 @@ void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox)
_mavlinkLogManager = toolbox->mavlinkLogManager();
_corePlugin = toolbox->corePlugin();
_firmwarePluginManager = toolbox->firmwarePluginManager();
+ _settingsManager = toolbox->settingsManager();
}
void QGroundControlQmlGlobal::saveGlobalSetting (const QString& key, const QString& value)
@@ -224,131 +214,6 @@ void QGroundControlQmlGlobal::setBaseFontPointSize(qreal size)
}
}
-SettingsFact* QGroundControlQmlGlobal::_createSettingsFact(const QString& name)
-{
- SettingsFact* fact;
- FactMetaData* metaData = nameToMetaDataMap()[name];
-
- fact = new SettingsFact(QString(), name, metaData->type(), metaData->rawDefaultValue());
- fact->setMetaData(metaData);
-
- return fact;
-}
-
-Fact* QGroundControlQmlGlobal::offlineEditingFirmwareType(void)
-{
- if (!_offlineEditingFirmwareTypeFact) {
- _offlineEditingFirmwareTypeFact = _createSettingsFact(QStringLiteral("OfflineEditingFirmwareType"));
- }
-
- return _offlineEditingFirmwareTypeFact;
-}
-
-Fact* QGroundControlQmlGlobal::offlineEditingVehicleType(void)
-{
- if (!_offlineEditingVehicleTypeFact) {
- _offlineEditingVehicleTypeFact = _createSettingsFact(QStringLiteral("OfflineEditingVehicleType"));
- }
-
- return _offlineEditingVehicleTypeFact;
-}
-
-Fact* QGroundControlQmlGlobal::offlineEditingCruiseSpeed(void)
-{
- if (!_offlineEditingCruiseSpeedFact) {
- _offlineEditingCruiseSpeedFact = _createSettingsFact(QStringLiteral("OfflineEditingCruiseSpeed"));
- }
- return _offlineEditingCruiseSpeedFact;
-}
-
-Fact* QGroundControlQmlGlobal::offlineEditingHoverSpeed(void)
-{
- if (!_offlineEditingHoverSpeedFact) {
- _offlineEditingHoverSpeedFact = _createSettingsFact(QStringLiteral("OfflineEditingHoverSpeed"));
- }
- return _offlineEditingHoverSpeedFact;
-}
-
-Fact* QGroundControlQmlGlobal::distanceUnits(void)
-{
- if (!_distanceUnitsFact) {
- // 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;
-
- _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::areaUnits(void)
-{
- if (!_areaUnitsFact) {
- // 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;
-
- _areaUnitsFact = new SettingsFact(QString(), "AreaUnits", FactMetaData::valueTypeUint32, AreaUnitsSquareMeters);
- _areaUnitsMetaData = new FactMetaData(FactMetaData::valueTypeUint32);
-
- enumStrings << "SquareFeet" << "SquareMeters" << "SquareKilometers" << "Hectares" << "Acres" << "SquareMiles";
- enumValues << QVariant::fromValue((uint32_t)AreaUnitsSquareFeet) << QVariant::fromValue((uint32_t)AreaUnitsSquareMeters) << QVariant::fromValue((uint32_t)AreaUnitsSquareKilometers) << QVariant::fromValue((uint32_t)AreaUnitsHectares) << QVariant::fromValue((uint32_t)AreaUnitsAcres) << QVariant::fromValue((uint32_t)AreaUnitsSquareMiles);
-
- _areaUnitsMetaData->setEnumInfo(enumStrings, enumValues);
- _areaUnitsFact->setMetaData(_areaUnitsMetaData);
- }
-
- return _areaUnitsFact;
-
-}
-
-Fact* QGroundControlQmlGlobal::speedUnits(void)
-{
- if (!_speedUnitsFact) {
- // 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;
-
- _speedUnitsFact = new SettingsFact(QString(), "SpeedUnits", FactMetaData::valueTypeUint32, SpeedUnitsMetersPerSecond);
- _speedUnitsMetaData = new FactMetaData(FactMetaData::valueTypeUint32);
-
- enumStrings << "Feet/second" << "Meters/second" << "Miles/hour" << "Kilometers/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;
-}
-
-Fact* QGroundControlQmlGlobal::batteryPercentRemainingAnnounce(void)
-{
- if (!_batteryPercentRemainingAnnounceFact) {
- _batteryPercentRemainingAnnounceFact = _createSettingsFact(QStringLiteral("batteryPercentRemainingAnnounce"));
- }
-
- return _batteryPercentRemainingAnnounceFact;
-}
-
-Fact* QGroundControlQmlGlobal::defaultMissionItemAltitude(void)
-{
- if (!_defaultMissionItemAltitudeFact) {
- _defaultMissionItemAltitudeFact = _createSettingsFact(QStringLiteral("DefaultMissionItemAltitude"));
- }
-
- return _defaultMissionItemAltitudeFact;
-}
-
int QGroundControlQmlGlobal::supportedFirmwareCount()
{
return _firmwarePluginManager->knownFirmwareTypes().count();
@@ -363,16 +228,6 @@ bool QGroundControlQmlGlobal::linesIntersect(QPointF line1A, QPointF line1B, QPo
intersectPoint != line1A && intersectPoint != line1B;
}
-QMap& QGroundControlQmlGlobal::nameToMetaDataMap(void) {
- static QMap map;
-
- if (map.isEmpty()) {
- map = FactMetaData::createMapFromJsonFile(":/json/QGroundControlQmlGlobal.json", NULL);
- }
-
- return map;
-}
-
QString QGroundControlQmlGlobal::missionAutoLoadDir(void)
{
QSettings settings;
diff --git a/src/QmlControls/QGroundControlQmlGlobal.h b/src/QmlControls/QGroundControlQmlGlobal.h
index 7a912e5746427ef4a0c3de0a95af9f8d7b257fe2..bbd04899774f070935d57b9a45f731e4b42c5673 100644
--- a/src/QmlControls/QGroundControlQmlGlobal.h
+++ b/src/QmlControls/QGroundControlQmlGlobal.h
@@ -37,32 +37,6 @@ public:
QGroundControlQmlGlobal(QGCApplication* app);
~QGroundControlQmlGlobal();
- enum DistanceUnits {
- DistanceUnitsFeet = 0,
- DistanceUnitsMeters
- };
-
- enum AreaUnits {
- AreaUnitsSquareFeet = 0,
- AreaUnitsSquareMeters,
- AreaUnitsSquareKilometers,
- AreaUnitsHectares,
- AreaUnitsAcres,
- AreaUnitsSquareMiles,
- };
-
- enum SpeedUnits {
- SpeedUnitsFeetPerSecond = 0,
- SpeedUnitsMetersPerSecond,
- SpeedUnitsMilesPerHour,
- SpeedUnitsKilometersPerHour,
- SpeedUnitsKnots,
- };
-
- Q_ENUMS(DistanceUnits)
- Q_ENUMS(AreaUnits)
- Q_ENUMS(SpeedUnits)
-
Q_PROPERTY(FlightMapSettings* flightMapSettings READ flightMapSettings CONSTANT)
Q_PROPERTY(LinkManager* linkManager READ linkManager CONSTANT)
Q_PROPERTY(MultiVehicleManager* multiVehicleManager READ multiVehicleManager CONSTANT)
@@ -72,6 +46,9 @@ public:
Q_PROPERTY(VideoManager* videoManager READ videoManager CONSTANT)
Q_PROPERTY(MAVLinkLogManager* mavlinkLogManager READ mavlinkLogManager CONSTANT)
Q_PROPERTY(QGCCorePlugin* corePlugin READ corePlugin CONSTANT)
+ Q_PROPERTY(SettingsManager* settingsManager READ settingsManager CONSTANT)
+
+ Q_PROPERTY(int supportedFirmwareCount READ supportedFirmwareCount CONSTANT)
Q_PROPERTY(qreal zOrderTopMost READ zOrderTopMost CONSTANT) ///< z order for top most items, toolbar, main window sub view
Q_PROPERTY(qreal zOrderWidgets READ zOrderWidgets CONSTANT) ///< z order value to widgets, for example: zoom controls, hud widgetss
@@ -91,17 +68,6 @@ public:
Q_PROPERTY(bool isVersionCheckEnabled READ isVersionCheckEnabled WRITE setIsVersionCheckEnabled NOTIFY isVersionCheckEnabledChanged)
Q_PROPERTY(int mavlinkSystemID READ mavlinkSystemID WRITE setMavlinkSystemID NOTIFY mavlinkSystemIDChanged)
- Q_PROPERTY(Fact* offlineEditingFirmwareType READ offlineEditingFirmwareType CONSTANT)
- Q_PROPERTY(Fact* offlineEditingVehicleType READ offlineEditingVehicleType CONSTANT)
- Q_PROPERTY(Fact* offlineEditingCruiseSpeed READ offlineEditingCruiseSpeed CONSTANT)
- Q_PROPERTY(Fact* offlineEditingHoverSpeed READ offlineEditingHoverSpeed CONSTANT)
- Q_PROPERTY(Fact* distanceUnits READ distanceUnits CONSTANT)
- Q_PROPERTY(Fact* areaUnits READ areaUnits CONSTANT)
- Q_PROPERTY(Fact* speedUnits READ speedUnits CONSTANT)
- Q_PROPERTY(Fact* batteryPercentRemainingAnnounce READ batteryPercentRemainingAnnounce CONSTANT)
- Q_PROPERTY(Fact* defaultMissionItemAltitude READ defaultMissionItemAltitude CONSTANT)
- Q_PROPERTY(int supportedFirmwareCount READ supportedFirmwareCount CONSTANT)
-
Q_PROPERTY(QGeoCoordinate lastKnownHomePosition READ lastKnownHomePosition CONSTANT)
Q_PROPERTY(QGeoCoordinate flightMapPosition MEMBER _flightMapPosition NOTIFY flightMapPositionChanged)
Q_PROPERTY(double flightMapZoom MEMBER _flightMapZoom NOTIFY flightMapZoomChanged)
@@ -163,19 +129,20 @@ public:
// Property accesors
- FlightMapSettings* flightMapSettings () { return _flightMapSettings; }
- LinkManager* linkManager () { return _linkManager; }
- MultiVehicleManager* multiVehicleManager () { return _multiVehicleManager; }
- QGCMapEngineManager* mapEngineManager () { return _mapEngineManager; }
- QGCPositionManager* qgcPositionManger () { return _qgcPositionManager; }
- MissionCommandTree* missionCommandTree () { return _missionCommandTree; }
- VideoManager* videoManager () { return _videoManager; }
- MAVLinkLogManager* mavlinkLogManager () { return _mavlinkLogManager; }
- QGCCorePlugin* corePlugin () { return _corePlugin; }
-
- qreal zOrderTopMost () { return 1000; }
- qreal zOrderWidgets () { return 100; }
- qreal zOrderMapItems () { return 50; }
+ FlightMapSettings* flightMapSettings () { return _flightMapSettings; }
+ LinkManager* linkManager () { return _linkManager; }
+ MultiVehicleManager* multiVehicleManager () { return _multiVehicleManager; }
+ QGCMapEngineManager* mapEngineManager () { return _mapEngineManager; }
+ QGCPositionManager* qgcPositionManger () { return _qgcPositionManager; }
+ MissionCommandTree* missionCommandTree () { return _missionCommandTree; }
+ VideoManager* videoManager () { return _videoManager; }
+ MAVLinkLogManager* mavlinkLogManager () { return _mavlinkLogManager; }
+ QGCCorePlugin* corePlugin () { return _corePlugin; }
+ SettingsManager* settingsManager () { return _settingsManager; }
+
+ qreal zOrderTopMost () { return 1000; }
+ qreal zOrderWidgets () { return 100; }
+ qreal zOrderMapItems () { return 50; }
bool isDarkStyle () { return _app->styleIsDark(); }
bool isAudioMuted () { return _toolbox->audioOutput()->isMuted(); }
@@ -189,16 +156,6 @@ public:
QGeoCoordinate lastKnownHomePosition() { return qgcApp()->lastKnownHomePosition(); }
- static Fact* offlineEditingFirmwareType (void);
- static Fact* offlineEditingVehicleType (void);
- static Fact* offlineEditingCruiseSpeed (void);
- static Fact* offlineEditingHoverSpeed (void);
- static Fact* distanceUnits (void);
- static Fact* areaUnits (void);
- static Fact* speedUnits (void);
- static Fact* batteryPercentRemainingAnnounce(void);
- static Fact* defaultMissionItemAltitude (void);
-
int supportedFirmwareCount ();
void setIsDarkStyle (bool dark);
@@ -238,9 +195,6 @@ signals:
void missionAutoLoadDirChanged (QString missionAutoLoadDir);
private:
- static SettingsFact* _createSettingsFact(const QString& name);
- static QMap& nameToMetaDataMap(void);
-
FlightMapSettings* _flightMapSettings;
LinkManager* _linkManager;
MultiVehicleManager* _multiVehicleManager;
@@ -251,26 +205,13 @@ private:
MAVLinkLogManager* _mavlinkLogManager;
QGCCorePlugin* _corePlugin;
FirmwarePluginManager* _firmwarePluginManager;
+ SettingsManager* _settingsManager;
bool _virtualTabletJoystick;
qreal _baseFontPointSize;
QGeoCoordinate _flightMapPosition;
double _flightMapZoom;
- // These are static so they are available to C++ code as well as Qml
- static SettingsFact* _offlineEditingFirmwareTypeFact;
- static SettingsFact* _offlineEditingVehicleTypeFact;
- static SettingsFact* _offlineEditingCruiseSpeedFact;
- static SettingsFact* _offlineEditingHoverSpeedFact;
- static SettingsFact* _distanceUnitsFact;
- static FactMetaData* _distanceUnitsMetaData;
- static SettingsFact* _areaUnitsFact;
- static FactMetaData* _areaUnitsMetaData;
- static SettingsFact* _speedUnitsFact;
- static FactMetaData* _speedUnitsMetaData;
- static SettingsFact* _batteryPercentRemainingAnnounceFact;
- static SettingsFact* _defaultMissionItemAltitudeFact;
-
static const char* _virtualTabletJoystickKey;
static const char* _baseFontPointSizeKey;
static const char* _missionAutoLoadDirKey;
diff --git a/src/SettingsManager.cc b/src/SettingsManager.cc
new file mode 100644
index 0000000000000000000000000000000000000000..0408440f950f2774e1572ad1e2cfe51dfeee9071
--- /dev/null
+++ b/src/SettingsManager.cc
@@ -0,0 +1,170 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#include "SettingsManager.h"
+#include "QGCApplication.h"
+
+QGC_LOGGING_CATEGORY(SettingsManagerLog, "SettingsManagerLog")
+
+const char* SettingsManager::offlineEditingFirmwareTypeSettingsName = "OfflineEditingFirmwareType";
+const char* SettingsManager::offlineEditingVehicleTypeSettingsName = "OfflineEditingVehicleType";
+const char* SettingsManager::offlineEditingCruiseSpeedSettingsName = "OfflineEditingCruiseSpeed";
+const char* SettingsManager::offlineEditingHoverSpeedSettingsName = "OfflineEditingHoverSpeed";
+const char* SettingsManager::distanceUnitsSettingsName = "DistanceUnits";
+const char* SettingsManager::areaUnitsSettingsName = "AreaUnits";
+const char* SettingsManager::speedUnitsSettingsName = "SpeedUnits";
+const char* SettingsManager::batteryPercentRemainingAnnounceSettingsName = "batteryPercentRemainingAnnounce";
+const char* SettingsManager::defaultMissionItemAltitudeSettingsName = "DefaultMissionItemAltitude";
+
+SettingsManager::SettingsManager(QGCApplication* app)
+ : QGCTool(app)
+ , _offlineEditingFirmwareTypeFact(NULL)
+ , _offlineEditingVehicleTypeFact(NULL)
+ , _offlineEditingCruiseSpeedFact(NULL)
+ , _offlineEditingHoverSpeedFact(NULL)
+ , _distanceUnitsFact(NULL)
+ , _areaUnitsFact(NULL)
+ , _speedUnitsFact(NULL)
+ , _batteryPercentRemainingAnnounceFact(NULL)
+ , _defaultMissionItemAltitudeFact(NULL)
+{
+
+}
+
+void SettingsManager::setToolbox(QGCToolbox *toolbox)
+{
+ QGCTool::setToolbox(toolbox);
+ QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
+ qmlRegisterUncreatableType("QGroundControl.SettingsManager", 1, 0, "SettingsManager", "Reference only");
+
+ _nameToMetaDataMap = FactMetaData::createMapFromJsonFile(":/json/SettingsManager.json", this);
+}
+
+SettingsFact* SettingsManager::_createSettingsFact(const QString& name)
+{
+ return new SettingsFact(QString() /* no settings group */, _nameToMetaDataMap[name], this);
+}
+
+Fact* SettingsManager::offlineEditingFirmwareType(void)
+{
+ if (!_offlineEditingFirmwareTypeFact) {
+ _offlineEditingFirmwareTypeFact = _createSettingsFact(offlineEditingFirmwareTypeSettingsName);
+ }
+
+ return _offlineEditingFirmwareTypeFact;
+}
+
+Fact* SettingsManager::offlineEditingVehicleType(void)
+{
+ if (!_offlineEditingVehicleTypeFact) {
+ _offlineEditingVehicleTypeFact = _createSettingsFact(offlineEditingVehicleTypeSettingsName);
+ }
+
+ return _offlineEditingVehicleTypeFact;
+}
+
+Fact* SettingsManager::offlineEditingCruiseSpeed(void)
+{
+ if (!_offlineEditingCruiseSpeedFact) {
+ _offlineEditingCruiseSpeedFact = _createSettingsFact(offlineEditingCruiseSpeedSettingsName);
+ }
+ return _offlineEditingCruiseSpeedFact;
+}
+
+Fact* SettingsManager::offlineEditingHoverSpeed(void)
+{
+ if (!_offlineEditingHoverSpeedFact) {
+ _offlineEditingHoverSpeedFact = _createSettingsFact(offlineEditingHoverSpeedSettingsName);
+ }
+ return _offlineEditingHoverSpeedFact;
+}
+
+Fact* SettingsManager::batteryPercentRemainingAnnounce(void)
+{
+ if (!_batteryPercentRemainingAnnounceFact) {
+ _batteryPercentRemainingAnnounceFact = _createSettingsFact(batteryPercentRemainingAnnounceSettingsName);
+ }
+
+ return _batteryPercentRemainingAnnounceFact;
+}
+
+Fact* SettingsManager::defaultMissionItemAltitude(void)
+{
+ if (!_defaultMissionItemAltitudeFact) {
+ _defaultMissionItemAltitudeFact = _createSettingsFact(defaultMissionItemAltitudeSettingsName);
+ }
+
+ return _defaultMissionItemAltitudeFact;
+}
+
+Fact* SettingsManager::distanceUnits(void)
+{
+ if (!_distanceUnitsFact) {
+ // 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((uint32_t)DistanceUnitsFeet) << QVariant::fromValue((uint32_t)DistanceUnitsMeters);
+
+ FactMetaData* metaData = new FactMetaData(FactMetaData::valueTypeUint32, this);
+ metaData->setName(distanceUnitsSettingsName);
+ metaData->setEnumInfo(enumStrings, enumValues);
+ metaData->setRawDefaultValue(DistanceUnitsMeters);
+
+ _distanceUnitsFact = new SettingsFact(QString() /* no settings group */, metaData, this);
+
+ }
+
+ return _distanceUnitsFact;
+
+}
+
+Fact* SettingsManager::areaUnits(void)
+{
+ if (!_areaUnitsFact) {
+ // 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 << "SquareFeet" << "SquareMeters" << "SquareKilometers" << "Hectares" << "Acres" << "SquareMiles";
+ enumValues << QVariant::fromValue((uint32_t)AreaUnitsSquareFeet) << QVariant::fromValue((uint32_t)AreaUnitsSquareMeters) << QVariant::fromValue((uint32_t)AreaUnitsSquareKilometers) << QVariant::fromValue((uint32_t)AreaUnitsHectares) << QVariant::fromValue((uint32_t)AreaUnitsAcres) << QVariant::fromValue((uint32_t)AreaUnitsSquareMiles);
+
+ FactMetaData* metaData = new FactMetaData(FactMetaData::valueTypeUint32, this);
+ metaData->setName(areaUnitsSettingsName);
+ metaData->setEnumInfo(enumStrings, enumValues);
+ metaData->setRawDefaultValue(AreaUnitsSquareMeters);
+
+ _areaUnitsFact = new SettingsFact(QString() /* no settings group */, metaData, this);
+ }
+
+ return _areaUnitsFact;
+
+}
+
+Fact* SettingsManager::speedUnits(void)
+{
+ if (!_speedUnitsFact) {
+ // 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/second" << "Meters/second" << "Miles/hour" << "Kilometers/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);
+
+ FactMetaData* metaData = new FactMetaData(FactMetaData::valueTypeUint32, this);
+ metaData->setName(speedUnitsSettingsName);
+ metaData->setEnumInfo(enumStrings, enumValues);
+ metaData->setRawDefaultValue(SpeedUnitsMetersPerSecond);
+
+ _speedUnitsFact = new SettingsFact(QString() /* no settings group */, metaData, this);
+ }
+
+ return _speedUnitsFact;
+}
diff --git a/src/SettingsManager.h b/src/SettingsManager.h
new file mode 100644
index 0000000000000000000000000000000000000000..bae2fd3b9183a9960986540f66342681adc6423f
--- /dev/null
+++ b/src/SettingsManager.h
@@ -0,0 +1,112 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+
+#ifndef SettingsManager_H
+#define SettingsManager_H
+
+#include "QGCLoggingCategory.h"
+#include "Joystick.h"
+#include "MultiVehicleManager.h"
+#include "QGCToolbox.h"
+
+#include
+
+Q_DECLARE_LOGGING_CATEGORY(SettingsManagerLog)
+
+/// Provides access to all app settings
+class SettingsManager : public QGCTool
+{
+ Q_OBJECT
+
+public:
+ SettingsManager(QGCApplication* app);
+
+ enum DistanceUnits {
+ DistanceUnitsFeet = 0,
+ DistanceUnitsMeters
+ };
+
+ enum AreaUnits {
+ AreaUnitsSquareFeet = 0,
+ AreaUnitsSquareMeters,
+ AreaUnitsSquareKilometers,
+ AreaUnitsHectares,
+ AreaUnitsAcres,
+ AreaUnitsSquareMiles,
+ };
+
+ enum SpeedUnits {
+ SpeedUnitsFeetPerSecond = 0,
+ SpeedUnitsMetersPerSecond,
+ SpeedUnitsMilesPerHour,
+ SpeedUnitsKilometersPerHour,
+ SpeedUnitsKnots,
+ };
+
+ Q_ENUMS(DistanceUnits)
+ Q_ENUMS(AreaUnits)
+ Q_ENUMS(SpeedUnits)
+
+ Q_PROPERTY(Fact* offlineEditingFirmwareType READ offlineEditingFirmwareType CONSTANT)
+ Q_PROPERTY(Fact* offlineEditingVehicleType READ offlineEditingVehicleType CONSTANT)
+ Q_PROPERTY(Fact* offlineEditingCruiseSpeed READ offlineEditingCruiseSpeed CONSTANT)
+ Q_PROPERTY(Fact* offlineEditingHoverSpeed READ offlineEditingHoverSpeed CONSTANT)
+ Q_PROPERTY(Fact* distanceUnits READ distanceUnits CONSTANT)
+ Q_PROPERTY(Fact* areaUnits READ areaUnits CONSTANT)
+ Q_PROPERTY(Fact* speedUnits READ speedUnits CONSTANT)
+ Q_PROPERTY(Fact* batteryPercentRemainingAnnounce READ batteryPercentRemainingAnnounce CONSTANT)
+ Q_PROPERTY(Fact* defaultMissionItemAltitude READ defaultMissionItemAltitude CONSTANT)
+
+ Fact* offlineEditingFirmwareType (void);
+ Fact* offlineEditingVehicleType (void);
+ Fact* offlineEditingCruiseSpeed (void);
+ Fact* offlineEditingHoverSpeed (void);
+ Fact* distanceUnits (void);
+ Fact* areaUnits (void);
+ Fact* speedUnits (void);
+ Fact* batteryPercentRemainingAnnounce(void);
+ Fact* defaultMissionItemAltitude (void);
+
+ // Override from QGCTool
+ virtual void setToolbox(QGCToolbox *toolbox);
+
+ static const char* offlineEditingFirmwareTypeSettingsName;
+ static const char* offlineEditingVehicleTypeSettingsName;
+ static const char* offlineEditingCruiseSpeedSettingsName;
+ static const char* offlineEditingHoverSpeedSettingsName;
+ static const char* distanceUnitsSettingsName;
+ static const char* areaUnitsSettingsName;
+ static const char* speedUnitsSettingsName;
+ static const char* batteryPercentRemainingAnnounceSettingsName;
+ static const char* defaultMissionItemAltitudeSettingsName;
+
+public slots:
+
+signals:
+
+private slots:
+
+private:
+ SettingsFact* _createSettingsFact(const QString& name);
+
+ QMap _nameToMetaDataMap;
+
+ SettingsFact* _offlineEditingFirmwareTypeFact;
+ SettingsFact* _offlineEditingVehicleTypeFact;
+ SettingsFact* _offlineEditingCruiseSpeedFact;
+ SettingsFact* _offlineEditingHoverSpeedFact;
+ SettingsFact* _distanceUnitsFact;
+ SettingsFact* _areaUnitsFact;
+ SettingsFact* _speedUnitsFact;
+ SettingsFact* _batteryPercentRemainingAnnounceFact;
+ SettingsFact* _defaultMissionItemAltitudeFact;
+};
+
+#endif
diff --git a/src/QmlControls/QGroundControlQmlGlobal.json b/src/SettingsManager.json
similarity index 100%
rename from src/QmlControls/QGroundControlQmlGlobal.json
rename to src/SettingsManager.json
diff --git a/src/Vehicle/MultiVehicleManager.cc b/src/Vehicle/MultiVehicleManager.cc
index fdab658a1849e6930b6640ce1a083c12ef31777f..45d3656c0ec5fa869f470fd5758177e44abbdedb 100644
--- a/src/Vehicle/MultiVehicleManager.cc
+++ b/src/Vehicle/MultiVehicleManager.cc
@@ -15,6 +15,7 @@
#include "FollowMe.h"
#include "QGroundControlQmlGlobal.h"
#include "ParameterManager.h"
+#include "SettingsManager.h"
#if defined (__ios__) || defined(__android__)
#include "MobileScreenMgr.h"
@@ -62,8 +63,9 @@ void MultiVehicleManager::setToolbox(QGCToolbox *toolbox)
connect(_mavlinkProtocol, &MAVLinkProtocol::vehicleHeartbeatInfo, this, &MultiVehicleManager::_vehicleHeartbeatInfo);
- _offlineEditingVehicle = new Vehicle(static_cast(QGroundControlQmlGlobal::offlineEditingFirmwareType()->rawValue().toInt()),
- static_cast(QGroundControlQmlGlobal::offlineEditingVehicleType()->rawValue().toInt()),
+ SettingsManager* settingsManager = toolbox->settingsManager();
+ _offlineEditingVehicle = new Vehicle(static_cast(settingsManager->offlineEditingFirmwareType()->rawValue().toInt()),
+ static_cast(settingsManager->offlineEditingVehicleType()->rawValue().toInt()),
_firmwarePluginManager,
this);
}
diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc
index 349e3054c473c96eea32e4de2385cde09982bb0a..0ad9378c59588aa1b07642d204c7a410ec484a8e 100644
--- a/src/Vehicle/Vehicle.cc
+++ b/src/Vehicle/Vehicle.cc
@@ -27,6 +27,7 @@
#include "FollowMe.h"
#include "MissionCommandTree.h"
#include "QGroundControlQmlGlobal.h"
+#include "SettingsManager.h"
QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog")
@@ -75,6 +76,7 @@ Vehicle::Vehicle(LinkInterface* link,
, _autopilotPlugin(NULL)
, _mavlink(NULL)
, _soloFirmware(false)
+ , _settingsManager(qgcApp()->toolbox()->settingsManager())
, _joystickMode(JoystickModeRC)
, _joystickEnabled(false)
, _uas(NULL)
@@ -99,8 +101,8 @@ Vehicle::Vehicle(LinkInterface* link,
, _onboardControlSensorsUnhealthy(0)
, _gpsRawIntMessageAvailable(false)
, _globalPositionIntMessageAvailable(false)
- , _cruiseSpeed(QGroundControlQmlGlobal::offlineEditingCruiseSpeed()->rawValue().toDouble())
- , _hoverSpeed(QGroundControlQmlGlobal::offlineEditingHoverSpeed()->rawValue().toDouble())
+ , _cruiseSpeed(_settingsManager->offlineEditingCruiseSpeed()->rawValue().toDouble())
+ , _hoverSpeed(_settingsManager->offlineEditingHoverSpeed()->rawValue().toDouble())
, _telemetryRRSSI(0)
, _telemetryLRSSI(0)
, _telemetryRXErrors(0)
@@ -231,6 +233,9 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _firmwarePlugin(NULL)
, _firmwarePluginInstanceData(NULL)
, _autopilotPlugin(NULL)
+ , _mavlink(NULL)
+ , _soloFirmware(false)
+ , _settingsManager(qgcApp()->toolbox()->settingsManager())
, _joystickMode(JoystickModeRC)
, _joystickEnabled(false)
, _uas(NULL)
@@ -255,8 +260,8 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _onboardControlSensorsUnhealthy(0)
, _gpsRawIntMessageAvailable(false)
, _globalPositionIntMessageAvailable(false)
- , _cruiseSpeed(QGroundControlQmlGlobal::offlineEditingCruiseSpeed()->rawValue().toDouble())
- , _hoverSpeed(QGroundControlQmlGlobal::offlineEditingHoverSpeed()->rawValue().toDouble())
+ , _cruiseSpeed(_settingsManager->offlineEditingCruiseSpeed()->rawValue().toDouble())
+ , _hoverSpeed(_settingsManager->offlineEditingHoverSpeed()->rawValue().toDouble())
, _connectionLost(false)
, _connectionLostEnabled(true)
, _missionManager(NULL)
@@ -318,10 +323,10 @@ void Vehicle::_commonInit(void)
connect(_rallyPointManager, &RallyPointManager::error, this, &Vehicle::_rallyPointManagerError);
// Offline editing vehicle tracks settings changes for offline editing settings
- connect(QGroundControlQmlGlobal::offlineEditingFirmwareType(), &Fact::rawValueChanged, this, &Vehicle::_offlineFirmwareTypeSettingChanged);
- connect(QGroundControlQmlGlobal::offlineEditingVehicleType(), &Fact::rawValueChanged, this, &Vehicle::_offlineVehicleTypeSettingChanged);
- connect(QGroundControlQmlGlobal::offlineEditingCruiseSpeed(), &Fact::rawValueChanged, this, &Vehicle::_offlineCruiseSpeedSettingChanged);
- connect(QGroundControlQmlGlobal::offlineEditingHoverSpeed(), &Fact::rawValueChanged, this, &Vehicle::_offlineHoverSpeedSettingChanged);
+ connect(_settingsManager->offlineEditingFirmwareType(), &Fact::rawValueChanged, this, &Vehicle::_offlineFirmwareTypeSettingChanged);
+ connect(_settingsManager->offlineEditingVehicleType(), &Fact::rawValueChanged, this, &Vehicle::_offlineVehicleTypeSettingChanged);
+ connect(_settingsManager->offlineEditingCruiseSpeed(), &Fact::rawValueChanged, this, &Vehicle::_offlineCruiseSpeedSettingChanged);
+ connect(_settingsManager->offlineEditingHoverSpeed(), &Fact::rawValueChanged, this, &Vehicle::_offlineHoverSpeedSettingChanged);
// Build FactGroup object model
@@ -786,7 +791,7 @@ void Vehicle::_handleSysStatus(mavlink_message_t& message)
}
_batteryFactGroup.percentRemaining()->setRawValue(sysStatus.battery_remaining);
- if (sysStatus.battery_remaining > 0 && sysStatus.battery_remaining < QGroundControlQmlGlobal::batteryPercentRemainingAnnounce()->rawValue().toInt()) {
+ if (sysStatus.battery_remaining > 0 && sysStatus.battery_remaining < _settingsManager->batteryPercentRemainingAnnounce()->rawValue().toInt()) {
if (!_lowBatteryAnnounceTimer.isValid() || _lowBatteryAnnounceTimer.elapsed() > _lowBatteryAnnounceRepeatMSecs) {
_lowBatteryAnnounceTimer.restart();
_say(QString("%1 low battery: %2 percent remaining").arg(_vehicleIdSpeech()).arg(sysStatus.battery_remaining));
diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h
index 29d8b1350770729fc90e5815bec5ddfb08847a37..8a8fea4fcdb079f20708f5a654ce4db4f70a2791 100644
--- a/src/Vehicle/Vehicle.h
+++ b/src/Vehicle/Vehicle.h
@@ -37,6 +37,7 @@ class RallyPointManager;
class ParameterManager;
class JoystickManager;
class UASMessage;
+class SettingsManager;
Q_DECLARE_LOGGING_CATEGORY(VehicleLog)
@@ -775,6 +776,7 @@ private:
AutoPilotPlugin* _autopilotPlugin;
MAVLinkProtocol* _mavlink;
bool _soloFirmware;
+ SettingsManager* _settingsManager;
QList _links;
diff --git a/src/api/QGCCorePlugin.cc b/src/api/QGCCorePlugin.cc
index 89eac8c4c39131f4f55d9af9c511cb00f91a49cf..eab76cc0f684325029845d9ab3e7f3b66e96178b 100644
--- a/src/api/QGCCorePlugin.cc
+++ b/src/api/QGCCorePlugin.cc
@@ -139,3 +139,10 @@ QGCOptions* QGCCorePlugin::options()
return _p->defaultOptions;
}
+QVariant QGCCorePlugin::overrideSettingsDefault(QString name, QVariant defaultValue)
+{
+ Q_UNUSED(name);
+
+ // No overrides for base plugin
+ return defaultValue;
+}
diff --git a/src/api/QGCCorePlugin.h b/src/api/QGCCorePlugin.h
index 492da621de138335e2138704fdb1ac29fcf1c925..b668a9d7cba0cc8440f38a082373bb5fc22aa768 100644
--- a/src/api/QGCCorePlugin.h
+++ b/src/api/QGCCorePlugin.h
@@ -54,6 +54,12 @@ public:
*/
virtual QGCOptions* options ();
+ /// Allows the core plugin to override the default value for the specified setting
+ /// @param name - Setting name
+ /// @param defaultValue - Standard default value for setting
+ /// @return New default value for setting, if no override just return passed in defaultValue
+ virtual QVariant overrideSettingsDefault(QString name, QVariant defaultValue);
+
// Override from QGCTool
void setToolbox (QGCToolbox *toolbox);
private:
diff --git a/src/ui/preferences/GeneralSettings.qml b/src/ui/preferences/GeneralSettings.qml
index a02c919ebec4ba90296215b59c2ac661b95f62a8..f0f231b2422ff6b6ae60c2f9390e6aaa2dca3896 100644
--- a/src/ui/preferences/GeneralSettings.qml
+++ b/src/ui/preferences/GeneralSettings.qml
@@ -23,6 +23,7 @@ import QGroundControl.ScreenTools 1.0
import QGroundControl.MultiVehicleManager 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controllers 1.0
+import QGroundControl.SettingsManager 1.0
QGCView {
id: qgcView
@@ -31,7 +32,7 @@ QGCView {
anchors.fill: parent
anchors.margins: ScreenTools.defaultFontPixelWidth
- property Fact _percentRemainingAnnounce: QGroundControl.batteryPercentRemainingAnnounce
+ property Fact _percentRemainingAnnounce: QGroundControl.settingsManager.batteryPercentRemainingAnnounce
property real _labelWidth: ScreenTools.defaultFontPixelWidth * 15
property real _editFieldWidth: ScreenTools.defaultFontPixelWidth * 30
@@ -93,7 +94,7 @@ QGCView {
FactComboBox {
id: distanceUnitsCombo
width: _editFieldWidth
- fact: QGroundControl.distanceUnits
+ fact: QGroundControl.settingsManager.distanceUnits
indexModel: false
}
}
@@ -107,7 +108,7 @@ QGCView {
FactComboBox {
id: areaUnitsCombo
width: _editFieldWidth
- fact: QGroundControl.areaUnits
+ fact: QGroundControl.settingsManager.areaUnits
indexModel: false
}
}
@@ -121,7 +122,7 @@ QGCView {
FactComboBox {
id: speedUnitsCombo
width: _editFieldWidth
- fact: QGroundControl.speedUnits
+ fact: QGroundControl.settingsManager.speedUnits
indexModel: false
}
}
@@ -326,7 +327,7 @@ QGCView {
}
FactTextField {
id: defaultItemAltitudeField
- fact: QGroundControl.defaultMissionItemAltitude
+ fact: QGroundControl.settingsManager.defaultMissionItemAltitude
}
}
//-----------------------------------------------------------------