Unverified Commit 68b26ee2 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #7368 from DonLakeFlyer/OfflineMapsSettings

Offline Maps: Allow custom build override of min/max zoom levels, max tile download
parents e6d214e3 3c008535
...@@ -601,6 +601,7 @@ HEADERS += \ ...@@ -601,6 +601,7 @@ HEADERS += \
src/Settings/BrandImageSettings.h \ src/Settings/BrandImageSettings.h \
src/Settings/FlightMapSettings.h \ src/Settings/FlightMapSettings.h \
src/Settings/FlyViewSettings.h \ src/Settings/FlyViewSettings.h \
src/Settings/OfflineMapsSettings.h \
src/Settings/PlanViewSettings.h \ src/Settings/PlanViewSettings.h \
src/Settings/RTKSettings.h \ src/Settings/RTKSettings.h \
src/Settings/SettingsGroup.h \ src/Settings/SettingsGroup.h \
...@@ -804,6 +805,7 @@ SOURCES += \ ...@@ -804,6 +805,7 @@ SOURCES += \
src/Settings/BrandImageSettings.cc \ src/Settings/BrandImageSettings.cc \
src/Settings/FlightMapSettings.cc \ src/Settings/FlightMapSettings.cc \
src/Settings/FlyViewSettings.cc \ src/Settings/FlyViewSettings.cc \
src/Settings/OfflineMapsSettings.cc \
src/Settings/PlanViewSettings.cc \ src/Settings/PlanViewSettings.cc \
src/Settings/RTKSettings.cc \ src/Settings/RTKSettings.cc \
src/Settings/SettingsGroup.cc \ src/Settings/SettingsGroup.cc \
......
...@@ -226,6 +226,7 @@ ...@@ -226,6 +226,7 @@
<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="FlyView.SettingsGroup.json">src/Settings/FlyView.SettingsGroup.json</file> <file alias="FlyView.SettingsGroup.json">src/Settings/FlyView.SettingsGroup.json</file>
<file alias="OfflineMaps.SettingsGroup.json">src/Settings/OfflineMaps.SettingsGroup.json</file>
<file alias="PlanView.SettingsGroup.json">src/Settings/PlanView.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>
......
...@@ -15,8 +15,7 @@ ...@@ -15,8 +15,7 @@
DECLARE_SETTINGGROUP(AirMap, "AirMap") DECLARE_SETTINGGROUP(AirMap, "AirMap")
{ {
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); \ qmlRegisterUncreatableType<AirMapSettings>("QGroundControl.SettingsManager", 1, 0, "AirMapSettings", "Reference only");
qmlRegisterUncreatableType<AirMapSettings>("QGroundControl.SettingsManager", 1, 0, "AirMapSettings", "Reference only"); \
} }
DECLARE_SETTINGSFACT(AirMapSettings, usePersonalApiKey) DECLARE_SETTINGSFACT(AirMapSettings, usePersonalApiKey)
......
...@@ -33,10 +33,13 @@ QGCView { ...@@ -33,10 +33,13 @@ QGCView {
property string mapKey: "lastMapType" property string mapKey: "lastMapType"
property Fact _mapboxFact: QGroundControl.settingsManager.appSettings.mapboxToken property var _settingsManager: QGroundControl.settingsManager
property Fact _esriFact: QGroundControl.settingsManager.appSettings.esriToken property var _settings: _settingsManager.offlineMapsSettings
property var _fmSettings: _settingsManager.flightMapSettings
property Fact _mapboxFact: _settingsManager.appSettings.mapboxToken
property Fact _esriFact: _settingsManager.appSettings.esriToken
property string mapType: _settings.mapProvider.enumStringValue + " " + _settings.mapType.enumStringValue property string mapType: _fmSettings.mapProvider.enumStringValue + " " + _fmSettings.mapType.enumStringValue
property bool isMapInteractive: false property bool isMapInteractive: false
property var savedCenter: undefined property var savedCenter: undefined
property real savedZoom: 3 property real savedZoom: 3
...@@ -52,13 +55,12 @@ QGCView { ...@@ -52,13 +55,12 @@ QGCView {
property var _mapAdjustedColor: _map.isSatelliteMap ? "white" : "black" property var _mapAdjustedColor: _map.isSatelliteMap ? "white" : "black"
property bool _tooManyTiles: QGroundControl.mapEngineManager.tileCount > _maxTilesForDownload property bool _tooManyTiles: QGroundControl.mapEngineManager.tileCount > _maxTilesForDownload
property var _settings: QGroundControl.settingsManager.flightMapSettings
readonly property real minZoomLevel: 1 readonly property real minZoomLevel: 1
readonly property real maxZoomLevel: 20 readonly property real maxZoomLevel: 20
readonly property real sliderTouchArea: ScreenTools.defaultFontPixelWidth * (ScreenTools.isTinyScreen ? 5 : (ScreenTools.isMobile ? 6 : 3)) readonly property real sliderTouchArea: ScreenTools.defaultFontPixelWidth * (ScreenTools.isTinyScreen ? 5 : (ScreenTools.isMobile ? 6 : 3))
readonly property int _maxTilesForDownload: 100000 readonly property int _maxTilesForDownload: _settings.maxTilesForDownload.rawValue
QGCPalette { id: qgcPal } QGCPalette { id: qgcPal }
...@@ -106,7 +108,7 @@ QGCView { ...@@ -106,7 +108,7 @@ QGCView {
function addNewSet() { function addNewSet() {
isMapInteractive = true isMapInteractive = true
mapType = _settings.mapProvider.enumStringValue + " " + _settings.mapType.enumStringValue mapType = _fmSettings.mapProvider.enumStringValue + " " + _fmSettings.mapType.enumStringValue
resetMapToDefaults() resetMapToDefaults()
handleChanges() handleChanges()
_map.visible = true _map.visible = true
...@@ -813,12 +815,22 @@ QGCView { ...@@ -813,12 +815,22 @@ QGCView {
maximumValue: maxZoomLevel maximumValue: maxZoomLevel
stepSize: 1 stepSize: 1
updateValueWhileDragging: true updateValueWhileDragging: true
property real _savedZoom
Component.onCompleted: Math.max(sliderMinZoom.value = _map.zoomLevel - 4, 2) property bool _updateSetting: false
Component.onCompleted: {
sliderMinZoom.value = _settings.minZoomLevelDownload.rawValue
_updateSetting = true
}
onValueChanged: { onValueChanged: {
if(sliderMinZoom.value > sliderMaxZoom.value) { if(sliderMinZoom.value > sliderMaxZoom.value) {
sliderMaxZoom.value = sliderMinZoom.value sliderMaxZoom.value = sliderMinZoom.value
} }
if (_updateSetting) {
// Don't update setting until after Component.onCompleted since bad values come through before that
_settings.minZoomLevelDownload.rawValue = value
}
handleChanges() handleChanges()
} }
style: SliderStyle { style: SliderStyle {
...@@ -856,12 +868,22 @@ QGCView { ...@@ -856,12 +868,22 @@ QGCView {
maximumValue: maxZoomLevel maximumValue: maxZoomLevel
stepSize: 1 stepSize: 1
updateValueWhileDragging: true updateValueWhileDragging: true
property real _savedZoom
Component.onCompleted: Math.min(sliderMaxZoom.value = _map.zoomLevel + 2, 20) property bool _updateSetting: false
Component.onCompleted: {
sliderMaxZoom.value = _settings.maxZoomLevelDownload.rawValue
_updateSetting = true
}
onValueChanged: { onValueChanged: {
if(sliderMaxZoom.value < sliderMinZoom.value) { if(sliderMaxZoom.value < sliderMinZoom.value) {
sliderMinZoom.value = sliderMaxZoom.value sliderMinZoom.value = sliderMaxZoom.value
} }
if (_updateSetting) {
// Don't update setting until after Component.onCompleted since bad values come through before that
_settings.maxZoomLevelDownload.rawValue = value
}
handleChanges() handleChanges()
} }
style: SliderStyle { style: SliderStyle {
......
...@@ -15,7 +15,6 @@ ...@@ -15,7 +15,6 @@
DECLARE_SETTINGGROUP(APMMavlinkStreamRate, "APMMavlinkStreamRate") DECLARE_SETTINGGROUP(APMMavlinkStreamRate, "APMMavlinkStreamRate")
{ {
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<APMMavlinkStreamRateSettings>("QGroundControl.SettingsManager", 1, 0, "APMMavlinkStreamRateSettings", "Reference only"); qmlRegisterUncreatableType<APMMavlinkStreamRateSettings>("QGroundControl.SettingsManager", 1, 0, "APMMavlinkStreamRateSettings", "Reference only");
connect(streamRateRawSensors(), &Fact::rawValueChanged, this, &APMMavlinkStreamRateSettings::_updateStreamRateRawSensors); connect(streamRateRawSensors(), &Fact::rawValueChanged, this, &APMMavlinkStreamRateSettings::_updateStreamRateRawSensors);
......
...@@ -36,7 +36,6 @@ const char* AppSettings::crashDirectory = "CrashLogs"; ...@@ -36,7 +36,6 @@ const char* AppSettings::crashDirectory = "CrashLogs";
DECLARE_SETTINGGROUP(App, "") DECLARE_SETTINGGROUP(App, "")
{ {
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<AppSettings>("QGroundControl.SettingsManager", 1, 0, "AppSettings", "Reference only"); qmlRegisterUncreatableType<AppSettings>("QGroundControl.SettingsManager", 1, 0, "AppSettings", "Reference only");
QGCPalette::setGlobalTheme(indoorPalette()->rawValue().toBool() ? QGCPalette::Dark : QGCPalette::Light); QGCPalette::setGlobalTheme(indoorPalette()->rawValue().toBool() ? QGCPalette::Dark : QGCPalette::Light);
......
...@@ -15,7 +15,6 @@ ...@@ -15,7 +15,6 @@
DECLARE_SETTINGGROUP(AutoConnect, "LinkManager") DECLARE_SETTINGGROUP(AutoConnect, "LinkManager")
{ {
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); \
qmlRegisterUncreatableType<AutoConnectSettings>("QGroundControl.SettingsManager", 1, 0, "AutoConnectSettings", "Reference only"); \ qmlRegisterUncreatableType<AutoConnectSettings>("QGroundControl.SettingsManager", 1, 0, "AutoConnectSettings", "Reference only"); \
} }
......
...@@ -14,7 +14,6 @@ ...@@ -14,7 +14,6 @@
DECLARE_SETTINGGROUP(BrandImage, "Branding") DECLARE_SETTINGGROUP(BrandImage, "Branding")
{ {
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); \
qmlRegisterUncreatableType<BrandImageSettings>("QGroundControl.SettingsManager", 1, 0, "BrandImageSettings", "Reference only"); \ qmlRegisterUncreatableType<BrandImageSettings>("QGroundControl.SettingsManager", 1, 0, "BrandImageSettings", "Reference only"); \
} }
......
...@@ -6,6 +6,7 @@ add_library(Settings ...@@ -6,6 +6,7 @@ add_library(Settings
BrandImageSettings.cc BrandImageSettings.cc
FlightMapSettings.cc FlightMapSettings.cc
FlyViewSettings.cc FlyViewSettings.cc
OfflineMapsSettings.cc
PlanViewSettings.cc PlanViewSettings.cc
RTKSettings.cc RTKSettings.cc
SettingsGroup.cc SettingsGroup.cc
......
...@@ -18,7 +18,6 @@ ...@@ -18,7 +18,6 @@
DECLARE_SETTINGGROUP(FlightMap, "FlightMap") DECLARE_SETTINGGROUP(FlightMap, "FlightMap")
{ {
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<FlightMapSettings>("QGroundControl.SettingsManager", 1, 0, "FlightMapSettings", "Reference only"); qmlRegisterUncreatableType<FlightMapSettings>("QGroundControl.SettingsManager", 1, 0, "FlightMapSettings", "Reference only");
// Save the original version since we modify based on map provider // Save the original version since we modify based on map provider
......
...@@ -14,7 +14,6 @@ ...@@ -14,7 +14,6 @@
DECLARE_SETTINGGROUP(FlyView, "FlyView") DECLARE_SETTINGGROUP(FlyView, "FlyView")
{ {
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); \
qmlRegisterUncreatableType<FlyViewSettings>("QGroundControl.SettingsManager", 1, 0, "FlyViewSettings", "Reference only"); \ qmlRegisterUncreatableType<FlyViewSettings>("QGroundControl.SettingsManager", 1, 0, "FlyViewSettings", "Reference only"); \
} }
......
[
{
"name": "minZoomLevelDownload",
"shortDescription": "Minimum zoom level for downloads.",
"type": "Uint32",
"min": 1,
"max": 20,
"defaultValue": 13
},
{
"name": "maxZoomLevelDownload",
"shortDescription": "Maximum zoom level for downloads.",
"type": "Uint32",
"min": 1,
"max": 20,
"defaultValue": 19
},
{
"name": "maxTilesForDownload",
"shortDescription": "Maximum number of tiles for download.",
"type": "Uint32",
"defaultValue": 100000
}
]
/****************************************************************************
*
* (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 "OfflineMapsSettings.h"
#include <QQmlEngine>
#include <QtQml>
DECLARE_SETTINGGROUP(OfflineMaps, "OfflineMaps")
{
qmlRegisterUncreatableType<OfflineMapsSettings>("QGroundControl.SettingsManager", 1, 0, "OfflineMapsSettings", "Reference only");
}
DECLARE_SETTINGSFACT(OfflineMapsSettings, minZoomLevelDownload)
DECLARE_SETTINGSFACT(OfflineMapsSettings, maxZoomLevelDownload)
DECLARE_SETTINGSFACT(OfflineMapsSettings, maxTilesForDownload)
/****************************************************************************
*
* (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 OfflineMapsSettings : public SettingsGroup
{
Q_OBJECT
public:
OfflineMapsSettings(QObject* parent = nullptr);
DEFINE_SETTING_NAME_GROUP()
DEFINE_SETTINGFACT(minZoomLevelDownload)
DEFINE_SETTINGFACT(maxZoomLevelDownload)
DEFINE_SETTINGFACT(maxTilesForDownload)
private:
};
...@@ -14,6 +14,5 @@ ...@@ -14,6 +14,5 @@
DECLARE_SETTINGGROUP(PlanView, "PlanView") DECLARE_SETTINGGROUP(PlanView, "PlanView")
{ {
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); \
qmlRegisterUncreatableType<PlanViewSettings>("QGroundControl.SettingsManager", 1, 0, "PlanViewSettings", "Reference only"); \ qmlRegisterUncreatableType<PlanViewSettings>("QGroundControl.SettingsManager", 1, 0, "PlanViewSettings", "Reference only"); \
} }
...@@ -14,7 +14,6 @@ ...@@ -14,7 +14,6 @@
DECLARE_SETTINGGROUP(RTK, "RTK") DECLARE_SETTINGGROUP(RTK, "RTK")
{ {
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); \
qmlRegisterUncreatableType<RTKSettings>("QGroundControl.SettingsManager", 1, 0, "RTKSettings", "Reference only"); \ qmlRegisterUncreatableType<RTKSettings>("QGroundControl.SettingsManager", 1, 0, "RTKSettings", "Reference only"); \
} }
......
...@@ -11,6 +11,9 @@ ...@@ -11,6 +11,9 @@
#include "QGCCorePlugin.h" #include "QGCCorePlugin.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include <QQmlEngine>
#include <QtQml>
static const char* kJsonFile = ":/json/%1.SettingsGroup.json"; static const char* kJsonFile = ":/json/%1.SettingsGroup.json";
SettingsGroup::SettingsGroup(const QString& name, const QString& settingsGroup, QObject* parent) SettingsGroup::SettingsGroup(const QString& name, const QString& settingsGroup, QObject* parent)
...@@ -19,6 +22,8 @@ SettingsGroup::SettingsGroup(const QString& name, const QString& settingsGroup, ...@@ -19,6 +22,8 @@ SettingsGroup::SettingsGroup(const QString& name, const QString& settingsGroup,
, _name (name) , _name (name)
, _settingsGroup(settingsGroup) , _settingsGroup(settingsGroup)
{ {
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
_nameToMetaDataMap = FactMetaData::createMapFromJsonFile(QString(kJsonFile).arg(name), this); _nameToMetaDataMap = FactMetaData::createMapFromJsonFile(QString(kJsonFile).arg(name), this);
} }
......
...@@ -26,6 +26,7 @@ SettingsManager::SettingsManager(QGCApplication* app, QGCToolbox* toolbox) ...@@ -26,6 +26,7 @@ SettingsManager::SettingsManager(QGCApplication* app, QGCToolbox* toolbox)
, _flyViewSettings (nullptr) , _flyViewSettings (nullptr)
, _planViewSettings (nullptr) , _planViewSettings (nullptr)
, _brandImageSettings (nullptr) , _brandImageSettings (nullptr)
, _offlineMapsSettings (nullptr)
#if !defined(NO_ARDUPILOT_DIALECT) #if !defined(NO_ARDUPILOT_DIALECT)
, _apmMavlinkStreamRateSettings (nullptr) , _apmMavlinkStreamRateSettings (nullptr)
#endif #endif
...@@ -48,6 +49,7 @@ void SettingsManager::setToolbox(QGCToolbox *toolbox) ...@@ -48,6 +49,7 @@ void SettingsManager::setToolbox(QGCToolbox *toolbox)
_flyViewSettings = new FlyViewSettings (this); _flyViewSettings = new FlyViewSettings (this);
_planViewSettings = new PlanViewSettings (this); _planViewSettings = new PlanViewSettings (this);
_brandImageSettings = new BrandImageSettings (this); _brandImageSettings = new BrandImageSettings (this);
_offlineMapsSettings = new OfflineMapsSettings (this);
#if !defined(NO_ARDUPILOT_DIALECT) #if !defined(NO_ARDUPILOT_DIALECT)
_apmMavlinkStreamRateSettings = new APMMavlinkStreamRateSettings (this); _apmMavlinkStreamRateSettings = new APMMavlinkStreamRateSettings (this);
#endif #endif
......
...@@ -23,6 +23,7 @@ ...@@ -23,6 +23,7 @@
#include "FlyViewSettings.h" #include "FlyViewSettings.h"
#include "PlanViewSettings.h" #include "PlanViewSettings.h"
#include "BrandImageSettings.h" #include "BrandImageSettings.h"
#include "OfflineMapsSettings.h"
#include "APMMavlinkStreamRateSettings.h" #include "APMMavlinkStreamRateSettings.h"
#if defined(QGC_AIRMAP_ENABLED) #if defined(QGC_AIRMAP_ENABLED)
#include "AirMapSettings.h" #include "AirMapSettings.h"
...@@ -49,6 +50,7 @@ public: ...@@ -49,6 +50,7 @@ public:
Q_PROPERTY(QObject* flyViewSettings READ flyViewSettings CONSTANT) Q_PROPERTY(QObject* flyViewSettings READ flyViewSettings CONSTANT)
Q_PROPERTY(QObject* planViewSettings READ planViewSettings CONSTANT) Q_PROPERTY(QObject* planViewSettings READ planViewSettings CONSTANT)
Q_PROPERTY(QObject* brandImageSettings READ brandImageSettings CONSTANT) Q_PROPERTY(QObject* brandImageSettings READ brandImageSettings CONSTANT)
Q_PROPERTY(QObject* offlineMapsSettings READ offlineMapsSettings CONSTANT)
#if !defined(NO_ARDUPILOT_DIALECT) #if !defined(NO_ARDUPILOT_DIALECT)
Q_PROPERTY(QObject* apmMavlinkStreamRateSettings READ apmMavlinkStreamRateSettings CONSTANT) Q_PROPERTY(QObject* apmMavlinkStreamRateSettings READ apmMavlinkStreamRateSettings CONSTANT)
#endif #endif
...@@ -67,6 +69,7 @@ public: ...@@ -67,6 +69,7 @@ public:
FlyViewSettings* flyViewSettings (void) { return _flyViewSettings; } FlyViewSettings* flyViewSettings (void) { return _flyViewSettings; }
PlanViewSettings* planViewSettings (void) { return _planViewSettings; } PlanViewSettings* planViewSettings (void) { return _planViewSettings; }
BrandImageSettings* brandImageSettings (void) { return _brandImageSettings; } BrandImageSettings* brandImageSettings (void) { return _brandImageSettings; }
OfflineMapsSettings* offlineMapsSettings (void) { return _offlineMapsSettings; }
#if !defined(NO_ARDUPILOT_DIALECT) #if !defined(NO_ARDUPILOT_DIALECT)
APMMavlinkStreamRateSettings* apmMavlinkStreamRateSettings(void) { return _apmMavlinkStreamRateSettings; } APMMavlinkStreamRateSettings* apmMavlinkStreamRateSettings(void) { return _apmMavlinkStreamRateSettings; }
#endif #endif
...@@ -83,6 +86,7 @@ private: ...@@ -83,6 +86,7 @@ private:
FlyViewSettings* _flyViewSettings; FlyViewSettings* _flyViewSettings;
PlanViewSettings* _planViewSettings; PlanViewSettings* _planViewSettings;
BrandImageSettings* _brandImageSettings; BrandImageSettings* _brandImageSettings;
OfflineMapsSettings* _offlineMapsSettings;
#if !defined(NO_ARDUPILOT_DIALECT) #if !defined(NO_ARDUPILOT_DIALECT)
APMMavlinkStreamRateSettings* _apmMavlinkStreamRateSettings; APMMavlinkStreamRateSettings* _apmMavlinkStreamRateSettings;
#endif #endif
......
...@@ -14,7 +14,6 @@ ...@@ -14,7 +14,6 @@
DECLARE_SETTINGGROUP(Units, "Units") DECLARE_SETTINGGROUP(Units, "Units")
{ {
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<UnitsSettings>("QGroundControl.SettingsManager", 1, 0, "UnitsSettings", "Reference only"); qmlRegisterUncreatableType<UnitsSettings>("QGroundControl.SettingsManager", 1, 0, "UnitsSettings", "Reference only");
} }
......
...@@ -28,7 +28,6 @@ const char* VideoSettings::videoSourceMPEGTS = "MPEG-TS (h.264) Video Stream" ...@@ -28,7 +28,6 @@ const char* VideoSettings::videoSourceMPEGTS = "MPEG-TS (h.264) Video Stream"
DECLARE_SETTINGGROUP(Video, "Video") DECLARE_SETTINGGROUP(Video, "Video")
{ {
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<VideoSettings>("QGroundControl.SettingsManager", 1, 0, "VideoSettings", "Reference only"); qmlRegisterUncreatableType<VideoSettings>("QGroundControl.SettingsManager", 1, 0, "VideoSettings", "Reference only");
// Setup enum values for videoSource settings into meta data // Setup enum values for videoSource settings into meta data
......
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