Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
616e1137
Commit
616e1137
authored
Feb 18, 2017
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Add/use new SettingsManager implementation
* Holds all the settings for the app * Allows core plugin to override default values
parent
4881b985
Changes
26
Hide whitespace changes
Inline
Side-by-side
Showing
26 changed files
with
424 additions
and
291 deletions
+424
-291
qgroundcontrol.pro
qgroundcontrol.pro
+2
-0
qgroundcontrol.qrc
qgroundcontrol.qrc
+1
-1
FactMetaData.cc
src/FactSystem/FactMetaData.cc
+21
-20
SettingsFact.cc
src/FactSystem/SettingsFact.cc
+8
-3
SettingsFact.h
src/FactSystem/SettingsFact.h
+1
-1
MapScale.qml
src/FlightMap/MapScale.qml
+5
-4
MissionSettingsEditor.qml
src/MissionEditor/MissionSettingsEditor.qml
+12
-11
MissionCommandTree.cc
src/MissionManager/MissionCommandTree.cc
+6
-2
MissionCommandTree.h
src/MissionManager/MissionCommandTree.h
+3
-1
MissionController.cc
src/MissionManager/MissionController.cc
+5
-3
RallyPointController.cc
src/MissionManager/RallyPointController.cc
+2
-1
SimpleMissionItem.cc
src/MissionManager/SimpleMissionItem.cc
+2
-1
SimpleMissionItemTest.cc
src/MissionManager/SimpleMissionItemTest.cc
+3
-2
QGCToolbox.cc
src/QGCToolbox.cc
+8
-0
QGCToolbox.h
src/QGCToolbox.h
+3
-0
QGroundControlQmlGlobal.cc
src/QmlControls/QGroundControlQmlGlobal.cc
+3
-148
QGroundControlQmlGlobal.h
src/QmlControls/QGroundControlQmlGlobal.h
+18
-77
SettingsManager.cc
src/SettingsManager.cc
+170
-0
SettingsManager.h
src/SettingsManager.h
+112
-0
SettingsManager.json
src/SettingsManager.json
+0
-0
MultiVehicleManager.cc
src/Vehicle/MultiVehicleManager.cc
+4
-2
Vehicle.cc
src/Vehicle/Vehicle.cc
+14
-9
Vehicle.h
src/Vehicle/Vehicle.h
+2
-0
QGCCorePlugin.cc
src/api/QGCCorePlugin.cc
+7
-0
QGCCorePlugin.h
src/api/QGCCorePlugin.h
+6
-0
GeneralSettings.qml
src/ui/preferences/GeneralSettings.qml
+6
-5
No files found.
qgroundcontrol.pro
View file @
616e1137
...
...
@@ -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 \
...
...
qgroundcontrol.qrc
View file @
616e1137
...
...
@@ -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>
...
...
src/FactSystem/FactMetaData.cc
View file @
616e1137
...
...
@@ -14,8 +14,9 @@
/// @author Don Gagne <don@thegagnes.com>
#include "FactMetaData.h"
#include "
QGroundControlQmlGlobal
.h"
#include "
SettingsManager
.h"
#include "JsonHelper.h"
#include "QGCApplication.h"
#include <QDebug>
#include <QtMath>
...
...
@@ -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
;
}
...
...
src/FactSystem/SettingsFact.cc
View file @
616e1137
...
...
@@ -9,6 +9,8 @@
#include "SettingsFact.h"
#include "QGCCorePlugin.h"
#include "QGCApplication.h"
#include <QSettings>
...
...
@@ -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
);
}
...
...
src/FactSystem/SettingsFact.h
View file @
616e1137
...
...
@@ -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
);
...
...
src/FlightMap/MapScale.qml
View file @
616e1137
...
...
@@ -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
)
...
...
src/MissionEditor/MissionSettingsEditor.qml
View file @
616e1137
...
...
@@ -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
}
}
...
...
src/MissionManager/MissionCommandTree.cc
View file @
616e1137
...
...
@@ -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
)
{
}
...
...
@@ -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
());
}
}
src/MissionManager/MissionCommandTree.h
View file @
616e1137
...
...
@@ -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
<
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
;
...
...
src/MissionManager/MissionController.cc
View file @
616e1137
...
...
@@ -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
);
...
...
src/MissionManager/RallyPointController.cc
View file @
616e1137
...
...
@@ -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
<
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
);
...
...
src/MissionManager/SimpleMissionItem.cc
View file @
616e1137
...
...
@@ -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
);
...
...
src/MissionManager/SimpleMissionItemTest.cc
View file @
616e1137
...
...
@@ -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
...
...
src/QGCToolbox.cc
View file @
616e1137
...
...
@@ -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
);
...
...
src/QGCToolbox.h
View file @
616e1137
...
...
@@ -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
;
};
...
...
src/QmlControls/QGroundControlQmlGlobal.cc
View file @
616e1137
...
...
@@ -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
<
QString
,
FactMetaData
*>&
QGroundControlQmlGlobal
::
nameToMetaDataMap
(
void
)
{
static
QMap
<
QString
,
FactMetaData
*>
map
;
if
(
map
.
isEmpty
())
{
map
=
FactMetaData
::
createMapFromJsonFile
(
":/json/QGroundControlQmlGlobal.json"
,
NULL
);
}
return
map
;
}
QString
QGroundControlQmlGlobal
::
missionAutoLoadDir
(
void
)
{
QSettings
settings
;
...
...
src/QmlControls/QGroundControlQmlGlobal.h
View file @
616e1137
...
...
@@ -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
;
}