Commit ad064b52 authored by Don Gagne's avatar Don Gagne

parent 0599c6a3
...@@ -599,7 +599,8 @@ HEADERS += \ ...@@ -599,7 +599,8 @@ HEADERS += \
src/Settings/AutoConnectSettings.h \ src/Settings/AutoConnectSettings.h \
src/Settings/BrandImageSettings.h \ src/Settings/BrandImageSettings.h \
src/Settings/FlightMapSettings.h \ src/Settings/FlightMapSettings.h \
src/Settings/GuidedSettings.h \ src/Settings/FlyViewSettings.h \
src/Settings/PlanViewSettings.h \
src/Settings/RTKSettings.h \ src/Settings/RTKSettings.h \
src/Settings/SettingsGroup.h \ src/Settings/SettingsGroup.h \
src/Settings/SettingsManager.h \ src/Settings/SettingsManager.h \
...@@ -797,7 +798,8 @@ SOURCES += \ ...@@ -797,7 +798,8 @@ SOURCES += \
src/Settings/AutoConnectSettings.cc \ src/Settings/AutoConnectSettings.cc \
src/Settings/BrandImageSettings.cc \ src/Settings/BrandImageSettings.cc \
src/Settings/FlightMapSettings.cc \ src/Settings/FlightMapSettings.cc \
src/Settings/GuidedSettings.cc \ src/Settings/FlyViewSettings.cc \
src/Settings/PlanViewSettings.cc \
src/Settings/RTKSettings.cc \ src/Settings/RTKSettings.cc \
src/Settings/SettingsGroup.cc \ src/Settings/SettingsGroup.cc \
src/Settings/SettingsManager.cc \ src/Settings/SettingsManager.cc \
......
...@@ -220,7 +220,8 @@ ...@@ -220,7 +220,8 @@
<file alias="CameraSection.FactMetaData.json">src/MissionManager/CameraSection.FactMetaData.json</file> <file alias="CameraSection.FactMetaData.json">src/MissionManager/CameraSection.FactMetaData.json</file>
<file alias="FlightMap.SettingsGroup.json">src/Settings/FlightMap.SettingsGroup.json</file> <file alias="FlightMap.SettingsGroup.json">src/Settings/FlightMap.SettingsGroup.json</file>
<file alias="FWLandingPattern.FactMetaData.json">src/MissionManager/FWLandingPattern.FactMetaData.json</file> <file alias="FWLandingPattern.FactMetaData.json">src/MissionManager/FWLandingPattern.FactMetaData.json</file>
<file alias="Guided.SettingsGroup.json">src/Settings/Guided.SettingsGroup.json</file> <file alias="FlyView.SettingsGroup.json">src/Settings/FlyView.SettingsGroup.json</file>
<file alias="PlanView.SettingsGroup.json">src/Settings/PlanView.SettingsGroup.json</file>
<file alias="MavCmdInfoCommon.json">src/MissionManager/MavCmdInfoCommon.json</file> <file alias="MavCmdInfoCommon.json">src/MissionManager/MavCmdInfoCommon.json</file>
<file alias="MavCmdInfoFixedWing.json">src/MissionManager/MavCmdInfoFixedWing.json</file> <file alias="MavCmdInfoFixedWing.json">src/MissionManager/MavCmdInfoFixedWing.json</file>
<file alias="MavCmdInfoMultiRotor.json">src/MissionManager/MavCmdInfoMultiRotor.json</file> <file alias="MavCmdInfoMultiRotor.json">src/MissionManager/MavCmdInfoMultiRotor.json</file>
......
...@@ -21,12 +21,12 @@ Rectangle { ...@@ -21,12 +21,12 @@ Rectangle {
readonly property real _maxAlt: 121.92 // 400 feet readonly property real _maxAlt: 121.92 // 400 feet
readonly property real _minAlt: 3 readonly property real _minAlt: 3
property var _guidedSettings: QGroundControl.settingsManager.guidedSettings property var _flyViewSettings: QGroundControl.settingsManager.flyViewSettings
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property real _vehicleAltitude: _activeVehicle ? _activeVehicle.altitudeRelative.rawValue : 0 property real _vehicleAltitude: _activeVehicle ? _activeVehicle.altitudeRelative.rawValue : 0
property bool _fixedWing: _activeVehicle ? _activeVehicle.fixedWing : false property bool _fixedWing: _activeVehicle ? _activeVehicle.fixedWing : false
property real _sliderMaxAlt: _guidedSettings ? (_fixedWing ? _guidedSettings.fixedWingMaximumAltitude.rawValue : _guidedSettings.vehicleMaximumAltitude.rawValue) : 0 property real _sliderMaxAlt: _flyViewSettings ? _flyViewSettings.guidedMaximumAltitude.rawValue : 0
property real _sliderMinAlt: _guidedSettings ? (_fixedWing ? _guidedSettings.fixedWingMinimumAltitude.rawValue : _guidedSettings.vehicleMinimumAltitude.rawValue) : 0 property real _sliderMinAlt: _flyViewSettings ? _flyViewSettings.guidedMinimumAltitude.rawValue : 0
function reset() { function reset() {
altSlider.value = 0 altSlider.value = 0
......
[ [
{ {
"name": "FixedWingMinimumAltitude", "name": "GuidedMinimumAltitude",
"type": "double", "shortDescription": "Minimum altitude for guided actions altitude slider.",
"units": "m",
"defaultValue": 10
},
{
"name": "FixedWingMaximumAltitude",
"type": "double",
"units": "m",
"defaultValue": 121.92
},
{
"name": "VehicleMinimumAltitude",
"type": "double", "type": "double",
"units": "m", "units": "m",
"defaultValue": 2 "defaultValue": 2
}, },
{ {
"name": "VehicleMaximumAltitude", "name": "GuidedMaximumAltitude",
"shortDescription": "Maximum altitude for guided actions altitude slider.",
"type": "double", "type": "double",
"units": "m", "units": "m",
"defaultValue": 121.92 "defaultValue": 121.92
......
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "FlyViewSettings.h"
#include "QGCPalette.h"
#include "QGCApplication.h"
#include <QQmlEngine>
#include <QtQml>
#include <QStandardPaths>
const char* FlyViewSettings::name = "FlyView";
const char* FlyViewSettings::settingsGroup = "FlyView";
const char* FlyViewSettings::guidedMinimumAltitudeName = "GuidedMinimumAltitude";
const char* FlyViewSettings::guidedMaximumAltitudeName = "GuidedMaximumAltitude";
FlyViewSettings::FlyViewSettings(QObject* parent)
: SettingsGroup (name, settingsGroup, parent)
, _guidedMinimumAltitudeFact(NULL)
, _guidedMaximumAltitudeFact(NULL)
{
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<FlyViewSettings>("QGroundControl.SettingsManager", 1, 0, "FlyViewSettings", "Reference only");
}
Fact* FlyViewSettings::guidedMinimumAltitude(void)
{
if (!_guidedMinimumAltitudeFact) {
_guidedMinimumAltitudeFact = _createSettingsFact(guidedMinimumAltitudeName);
}
return _guidedMinimumAltitudeFact;
}
Fact* FlyViewSettings::guidedMaximumAltitude(void)
{
if (!_guidedMaximumAltitudeFact) {
_guidedMaximumAltitudeFact = _createSettingsFact(guidedMaximumAltitudeName);
}
return _guidedMaximumAltitudeFact;
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "SettingsGroup.h"
class FlyViewSettings : public SettingsGroup
{
Q_OBJECT
public:
FlyViewSettings(QObject* parent = NULL);
Q_PROPERTY(Fact* guidedMinimumAltitude READ guidedMinimumAltitude CONSTANT)
Q_PROPERTY(Fact* guidedMaximumAltitude READ guidedMaximumAltitude CONSTANT)
Fact* guidedMinimumAltitude(void);
Fact* guidedMaximumAltitude(void);
static const char* name;
static const char* settingsGroup;
static const char* guidedMinimumAltitudeName;
static const char* guidedMaximumAltitudeName;
private:
SettingsFact* _guidedMinimumAltitudeFact;
SettingsFact* _guidedMaximumAltitudeFact;
};
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "GuidedSettings.h"
#include "QGCPalette.h"
#include "QGCApplication.h"
#include <QQmlEngine>
#include <QtQml>
#include <QStandardPaths>
const char* GuidedSettings::name = "Guided";
const char* GuidedSettings::settingsGroup = ""; // settings are in root group
const char* GuidedSettings::fixedWingMinimumAltitudeName = "FixedWingMinimumAltitude";
const char* GuidedSettings::fixedWingMaximumAltitudeName = "FixedWingMaximumAltitude";
const char* GuidedSettings::vehicleMinimumAltitudeName = "VehicleMinimumAltitude";
const char* GuidedSettings::vehicleMaximumAltitudeName = "VehicleMaximumAltitude";
GuidedSettings::GuidedSettings(QObject* parent)
: SettingsGroup(name, settingsGroup, parent)
, _fixedWingMinimumAltitudeFact (NULL)
, _fixedWingMaximumAltitudeFact (NULL)
, _vehicleMinimumAltitudeFact (NULL)
, _vehicleMaximumAltitudeFact (NULL)
{
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<GuidedSettings>("QGroundControl.SettingsManager", 1, 0, "GuidedSettings", "Reference only");
}
Fact* GuidedSettings::fixedWingMinimumAltitude(void)
{
if (!_fixedWingMinimumAltitudeFact) {
_fixedWingMinimumAltitudeFact = _createSettingsFact(fixedWingMinimumAltitudeName);
}
return _fixedWingMinimumAltitudeFact;
}
Fact* GuidedSettings::fixedWingMaximumAltitude(void)
{
if (!_fixedWingMaximumAltitudeFact) {
_fixedWingMaximumAltitudeFact = _createSettingsFact(fixedWingMaximumAltitudeName);
}
return _fixedWingMaximumAltitudeFact;
}
Fact* GuidedSettings::vehicleMinimumAltitude(void)
{
if (!_vehicleMinimumAltitudeFact) {
_vehicleMinimumAltitudeFact = _createSettingsFact(vehicleMinimumAltitudeName);
}
return _vehicleMinimumAltitudeFact;
}
Fact* GuidedSettings::vehicleMaximumAltitude(void)
{
if (!_vehicleMaximumAltitudeFact) {
_vehicleMaximumAltitudeFact = _createSettingsFact(vehicleMaximumAltitudeName);
}
return _vehicleMaximumAltitudeFact;
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#ifndef GuidedSettings_H
#define GuidedSettings_H
#include "SettingsGroup.h"
#include "QGCMAVLink.h"
class GuidedSettings : public SettingsGroup
{
Q_OBJECT
public:
GuidedSettings(QObject* parent = NULL);
// These min/max altitudes are used by the guided altitude slider
Q_PROPERTY(Fact* fixedWingMinimumAltitude READ fixedWingMinimumAltitude CONSTANT)
Q_PROPERTY(Fact* fixedWingMaximumAltitude READ fixedWingMaximumAltitude CONSTANT)
Q_PROPERTY(Fact* vehicleMinimumAltitude READ vehicleMinimumAltitude CONSTANT)
Q_PROPERTY(Fact* vehicleMaximumAltitude READ vehicleMaximumAltitude CONSTANT)
Fact* fixedWingMinimumAltitude (void);
Fact* fixedWingMaximumAltitude (void);
Fact* vehicleMinimumAltitude (void);
Fact* vehicleMaximumAltitude (void);
static const char* name;
static const char* settingsGroup;
static const char* fixedWingMinimumAltitudeName;
static const char* fixedWingMaximumAltitudeName;
static const char* vehicleMinimumAltitudeName;
static const char* vehicleMaximumAltitudeName;
private:
SettingsFact* _fixedWingMinimumAltitudeFact;
SettingsFact* _fixedWingMaximumAltitudeFact;
SettingsFact* _vehicleMinimumAltitudeFact;
SettingsFact* _vehicleMaximumAltitudeFact;
};
#endif
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "PlanViewSettings.h"
#include <QQmlEngine>
#include <QtQml>
const char* PlanViewSettings::name = "PlanView";
const char* PlanViewSettings::settingsGroup = "PlanView";
PlanViewSettings::PlanViewSettings(QObject* parent)
: SettingsGroup(name, settingsGroup, parent)
{
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<PlanViewSettings>("QGroundControl.SettingsManager", 1, 0, "PlanViewSettings", "Reference only");
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "SettingsGroup.h"
class PlanViewSettings : public SettingsGroup
{
Q_OBJECT
public:
PlanViewSettings(QObject* parent = NULL);
// This is currently only used to set custom build visibility of the Plan view settings ui.
// The settings themselves related to PlanView are in still in AppSettings due to historical reasons.
static const char* name;
static const char* settingsGroup;
};
...@@ -23,7 +23,8 @@ SettingsManager::SettingsManager(QGCApplication* app, QGCToolbox* toolbox) ...@@ -23,7 +23,8 @@ SettingsManager::SettingsManager(QGCApplication* app, QGCToolbox* toolbox)
, _videoSettings (NULL) , _videoSettings (NULL)
, _flightMapSettings (NULL) , _flightMapSettings (NULL)
, _rtkSettings (NULL) , _rtkSettings (NULL)
, _guidedSettings (NULL) , _flyViewSettings (NULL)
, _planViewSettings (NULL)
, _brandImageSettings (NULL) , _brandImageSettings (NULL)
{ {
...@@ -35,15 +36,16 @@ void SettingsManager::setToolbox(QGCToolbox *toolbox) ...@@ -35,15 +36,16 @@ void SettingsManager::setToolbox(QGCToolbox *toolbox)
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<SettingsManager>("QGroundControl.SettingsManager", 1, 0, "SettingsManager", "Reference only"); qmlRegisterUncreatableType<SettingsManager>("QGroundControl.SettingsManager", 1, 0, "SettingsManager", "Reference only");
_unitsSettings = new UnitsSettings(this); // Must be first since AppSettings references it _unitsSettings = new UnitsSettings (this); // Must be first since AppSettings references it
_appSettings = new AppSettings(this); _appSettings = new AppSettings (this);
_autoConnectSettings = new AutoConnectSettings(this); _autoConnectSettings = new AutoConnectSettings (this);
_videoSettings = new VideoSettings(this); _videoSettings = new VideoSettings (this);
_flightMapSettings = new FlightMapSettings(this); _flightMapSettings = new FlightMapSettings (this);
_rtkSettings = new RTKSettings(this); _rtkSettings = new RTKSettings (this);
_guidedSettings = new GuidedSettings(this); _flyViewSettings = new FlyViewSettings (this);
_brandImageSettings = new BrandImageSettings(this); _planViewSettings = new PlanViewSettings (this);
_brandImageSettings = new BrandImageSettings (this);
#if defined(QGC_AIRMAP_ENABLED) #if defined(QGC_AIRMAP_ENABLED)
_airMapSettings = new AirMapSettings(this); _airMapSettings = new AirMapSettings (this);
#endif #endif
} }
...@@ -20,7 +20,8 @@ ...@@ -20,7 +20,8 @@
#include "VideoSettings.h" #include "VideoSettings.h"
#include "FlightMapSettings.h" #include "FlightMapSettings.h"
#include "RTKSettings.h" #include "RTKSettings.h"
#include "GuidedSettings.h" #include "FlyViewSettings.h"
#include "PlanViewSettings.h"
#include "BrandImageSettings.h" #include "BrandImageSettings.h"
#if defined(QGC_AIRMAP_ENABLED) #if defined(QGC_AIRMAP_ENABLED)
#include "AirMapSettings.h" #include "AirMapSettings.h"
...@@ -44,7 +45,8 @@ public: ...@@ -44,7 +45,8 @@ public:
Q_PROPERTY(QObject* videoSettings READ videoSettings CONSTANT) Q_PROPERTY(QObject* videoSettings READ videoSettings CONSTANT)
Q_PROPERTY(QObject* flightMapSettings READ flightMapSettings CONSTANT) Q_PROPERTY(QObject* flightMapSettings READ flightMapSettings CONSTANT)
Q_PROPERTY(QObject* rtkSettings READ rtkSettings CONSTANT) Q_PROPERTY(QObject* rtkSettings READ rtkSettings CONSTANT)
Q_PROPERTY(QObject* guidedSettings READ guidedSettings CONSTANT) Q_PROPERTY(QObject* flyViewSettings READ flyViewSettings CONSTANT)
Q_PROPERTY(QObject* planViewSettings READ planViewSettings CONSTANT)
Q_PROPERTY(QObject* brandImageSettings READ brandImageSettings CONSTANT) Q_PROPERTY(QObject* brandImageSettings READ brandImageSettings CONSTANT)
// Override from QGCTool // Override from QGCTool
...@@ -59,7 +61,8 @@ public: ...@@ -59,7 +61,8 @@ public:
VideoSettings* videoSettings (void) { return _videoSettings; } VideoSettings* videoSettings (void) { return _videoSettings; }
FlightMapSettings* flightMapSettings (void) { return _flightMapSettings; } FlightMapSettings* flightMapSettings (void) { return _flightMapSettings; }
RTKSettings* rtkSettings (void) { return _rtkSettings; } RTKSettings* rtkSettings (void) { return _rtkSettings; }
GuidedSettings* guidedSettings (void) { return _guidedSettings; } FlyViewSettings* flyViewSettings (void) { return _flyViewSettings; }
PlanViewSettings* planViewSettings (void) { return _planViewSettings; }
BrandImageSettings* brandImageSettings (void) { return _brandImageSettings; } BrandImageSettings* brandImageSettings (void) { return _brandImageSettings; }
private: private:
...@@ -72,7 +75,8 @@ private: ...@@ -72,7 +75,8 @@ private:
VideoSettings* _videoSettings; VideoSettings* _videoSettings;
FlightMapSettings* _flightMapSettings; FlightMapSettings* _flightMapSettings;
RTKSettings* _rtkSettings; RTKSettings* _rtkSettings;
GuidedSettings* _guidedSettings; FlyViewSettings* _flyViewSettings;
PlanViewSettings* _planViewSettings;
BrandImageSettings* _brandImageSettings; BrandImageSettings* _brandImageSettings;
}; };
......
This diff is collapsed.
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