Skip to content

Commit

Permalink
Add/use new SettingsManager implementation
Browse files Browse the repository at this point in the history
* Holds all the settings for the app
* Allows core plugin to override default values
  • Loading branch information
DonLakeFlyer committed Feb 18, 2017
1 parent 4881b98 commit 616e113
Show file tree
Hide file tree
Showing 26 changed files with 424 additions and 291 deletions.
2 changes: 2 additions & 0 deletions qgroundcontrol.pro
Original file line number Diff line number Diff line change
Expand Up @@ -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 \
Expand Down Expand Up @@ -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 \
Expand Down
2 changes: 1 addition & 1 deletion qgroundcontrol.qrc
Original file line number Diff line number Diff line change
Expand Up @@ -168,7 +168,7 @@
<file alias="Vehicle/GPSFact.json">src/Vehicle/GPSFact.json</file>
<file alias="Vehicle/WindFact.json">src/Vehicle/WindFact.json</file>
<file alias="Vehicle/VibrationFact.json">src/Vehicle/VibrationFact.json</file>
<file alias="QGroundControlQmlGlobal.json">src/QmlControls/QGroundControlQmlGlobal.json</file>
<file alias="SettingsManager.json">src/SettingsManager.json</file>
<file alias="RallyPoint.FactMetaData.json">src/MissionManager/RallyPoint.FactMetaData.json</file>
<file alias="FWLandingPattern.FactMetaData.json">src/MissionManager/FWLandingPattern.FactMetaData.json</file>
<file alias="Survey.FactMetaData.json">src/MissionManager/Survey.FactMetaData.json</file>
Expand Down
41 changes: 21 additions & 20 deletions src/FactSystem/FactMetaData.cc
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,9 @@
/// @author Don Gagne <[email protected]>

#include "FactMetaData.h"
#include "QGroundControlQmlGlobal.h"
#include "SettingsManager.h"
#include "JsonHelper.h"
#include "QGCApplication.h"

#include <QDebug>
#include <QtMath>
Expand Down Expand Up @@ -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";
Expand Down Expand Up @@ -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;
Expand All @@ -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;
}
}
Expand All @@ -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;
}
Expand Down
11 changes: 8 additions & 3 deletions src/FactSystem/SettingsFact.cc
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@


#include "SettingsFact.h"
#include "QGCCorePlugin.h"
#include "QGCApplication.h"

#include <QSettings>

Expand All @@ -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;
Expand All @@ -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);
}
Expand Down
2 changes: 1 addition & 1 deletion src/FactSystem/SettingsFact.h
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
9 changes: 5 additions & 4 deletions src/FlightMap/MapScale.qml
Original file line number Diff line number Diff line change
Expand Up @@ -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 {
Expand Down Expand Up @@ -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)
Expand Down
23 changes: 12 additions & 11 deletions src/MissionEditor/MissionSettingsEditor.qml
Original file line number Diff line number Diff line change
Expand Up @@ -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 {
Expand Down Expand Up @@ -121,7 +122,7 @@ Rectangle {
Layout.fillWidth: true
}
FactComboBox {
fact: QGroundControl.offlineEditingFirmwareType
fact: QGroundControl.settingsManager.offlineEditingFirmwareType
indexModel: false
visible: _showOfflineEditingCombos
Layout.preferredWidth: _fieldWidth
Expand All @@ -145,7 +146,7 @@ Rectangle {
}
FactComboBox {
id: offlineVehicleCombo
fact: QGroundControl.offlineEditingVehicleType
fact: QGroundControl.settingsManager.offlineEditingVehicleType
indexModel: false
visible: _showOfflineEditingCombos
Layout.preferredWidth: _fieldWidth
Expand All @@ -169,7 +170,7 @@ Rectangle {
Layout.fillWidth: true
}
FactTextField {
fact: QGroundControl.offlineEditingCruiseSpeed
fact: QGroundControl.settingsManager.offlineEditingCruiseSpeed
visible: _showCruiseSpeed
Layout.preferredWidth: _fieldWidth
}
Expand All @@ -181,7 +182,7 @@ Rectangle {
Layout.fillWidth: true
}
FactTextField {
fact: QGroundControl.offlineEditingHoverSpeed
fact: QGroundControl.settingsManager.offlineEditingHoverSpeed
visible: _showHoverSpeed
Layout.preferredWidth: _fieldWidth
}
Expand All @@ -195,7 +196,7 @@ Rectangle {
QGCLabel { text: qsTr("Hover speed:"); Layout.fillWidth: true }
FactTextField {
Layout.preferredWidth: _fieldWidth
fact: QGroundControl.offlineEditingHoverSpeed
fact: QGroundControl.settingsManager.offlineEditingHoverSpeed
}
}

Expand Down
8 changes: 6 additions & 2 deletions src/MissionManager/MissionCommandTree.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,11 +17,13 @@
#include "QGroundControlQmlGlobal.h"
#include "MissionCommandUIInfo.h"
#include "MissionCommandList.h"
#include "SettingsManager.h"

#include <QQmlEngine>

MissionCommandTree::MissionCommandTree(QGCApplication* app, bool unitTest)
: QGCTool(app)
, _settingsManager(NULL)
, _unitTest(unitTest)
{
}
Expand All @@ -30,6 +32,8 @@ void MissionCommandTree::setToolbox(QGCToolbox* toolbox)
{
QGCTool::setToolbox(toolbox);

_settingsManager = toolbox->settingsManager();

#ifdef UNITTEST_BUILD
if (_unitTest) {
// Load unit testing tree
Expand Down Expand Up @@ -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());
}
}
4 changes: 3 additions & 1 deletion src/MissionManager/MissionCommandTree.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

class MissionCommandUIInfo;
class MissionCommandList;
class SettingsManager;
#ifdef UNITTEST_BUILD
class MissionCommandTreeTest;
#endif
Expand Down Expand Up @@ -87,7 +88,8 @@ class MissionCommandTree : public QGCTool
/// Collapsed hierarchy for specific vehicle type
QMap<MAV_AUTOPILOT, QMap<MAV_TYPE, QStringList>> _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;
Expand Down
8 changes: 5 additions & 3 deletions src/MissionManager/MissionController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include "JsonHelper.h"
#include "ParameterManager.h"
#include "QGroundControlQmlGlobal.h"
#include "SettingsManager.h"

#ifndef __mobile__
#include "MainWindow.h"
Expand Down Expand Up @@ -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);
Expand Down
3 changes: 2 additions & 1 deletion src/MissionManager/RallyPointController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include "JsonHelper.h"
#include "SimpleMissionItem.h"
#include "QGroundControlQmlGlobal.h"
#include "SettingsManager.h"

#ifndef __mobile__
#include "QGCFileDialog.h"
Expand Down Expand Up @@ -267,7 +268,7 @@ void RallyPointController::addPoint(QGeoCoordinate point)
if (_points.count()) {
defaultAlt = qobject_cast<RallyPoint*>(_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);
Expand Down
Loading

0 comments on commit 616e113

Please sign in to comment.