Commit 703c7d41 authored by Don Gagne's avatar Don Gagne

Alt slider min/max from settings

parent 3217c367
[
{
"name": "FixedWingMinimumAltitude",
"type": "double",
"units": "m",
"defaultValue": 10
},
{
"name": "FixedWingMaximumAltitude",
"type": "double",
"units": "m",
"defaultValue": 121.92
},
{
"name": "VehicleMinimumAltitude",
"type": "double",
"units": "m",
"defaultValue": 2
},
{
"name": "VehicleMaximumAltitude",
"type": "double",
"units": "m",
"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 "GuidedSettings.h"
#include "QGCPalette.h"
#include "QGCApplication.h"
#include <QQmlEngine>
#include <QtQml>
#include <QStandardPaths>
const char* GuidedSettings::guidedSettingsGroupName = "Guided";
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(guidedSettingsGroupName, QString() /* root settings group */, 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* guidedSettingsGroupName;
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
......@@ -14,12 +14,13 @@
SettingsManager::SettingsManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox)
, _appSettings(NULL)
, _unitsSettings(NULL)
, _autoConnectSettings(NULL)
, _videoSettings(NULL)
, _flightMapSettings(NULL)
, _rtkSettings(NULL)
, _appSettings (NULL)
, _unitsSettings (NULL)
, _autoConnectSettings (NULL)
, _videoSettings (NULL)
, _flightMapSettings (NULL)
, _rtkSettings (NULL)
, _guidedSettings (NULL)
{
}
......@@ -36,4 +37,5 @@ void SettingsManager::setToolbox(QGCToolbox *toolbox)
_videoSettings = new VideoSettings(this);
_flightMapSettings = new FlightMapSettings(this);
_rtkSettings = new RTKSettings(this);
_guidedSettings = new GuidedSettings(this);
}
......@@ -20,6 +20,7 @@
#include "VideoSettings.h"
#include "FlightMapSettings.h"
#include "RTKSettings.h"
#include "GuidedSettings.h"
#include <QVariantList>
......@@ -36,7 +37,8 @@ public:
Q_PROPERTY(QObject* autoConnectSettings READ autoConnectSettings CONSTANT)
Q_PROPERTY(QObject* videoSettings READ videoSettings 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)
// Override from QGCTool
virtual void setToolbox(QGCToolbox *toolbox);
......@@ -47,6 +49,7 @@ public:
VideoSettings* videoSettings (void) { return _videoSettings; }
FlightMapSettings* flightMapSettings (void) { return _flightMapSettings; }
RTKSettings* rtkSettings (void) { return _rtkSettings; }
GuidedSettings* guidedSettings (void) { return _guidedSettings; }
private:
AppSettings* _appSettings;
......@@ -55,6 +58,7 @@ private:
VideoSettings* _videoSettings;
FlightMapSettings* _flightMapSettings;
RTKSettings* _rtkSettings;
GuidedSettings* _guidedSettings;
};
#endif
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