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
24d9dc9b
Unverified
Commit
24d9dc9b
authored
Sep 27, 2019
by
Don Gagne
Committed by
GitHub
Sep 27, 2019
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #7834 from DonLakeFlyer/Presets
Plan: Rework presets
parents
673b9be7
90ec26a5
Changes
12
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
12 changed files
with
56 additions
and
539 deletions
+56
-539
qgroundcontrol.qrc
qgroundcontrol.qrc
+2
-3
CameraCalc.cc
src/MissionManager/CameraCalc.cc
+11
-32
CameraCalc.h
src/MissionManager/CameraCalc.h
+1
-1
ComplexMissionItem.cc
src/MissionManager/ComplexMissionItem.cc
+6
-70
ComplexMissionItem.h
src/MissionManager/ComplexMissionItem.h
+3
-24
StructureScanComplexItem.cc
src/MissionManager/StructureScanComplexItem.cc
+1
-1
TransectStyleComplexItem.cc
src/MissionManager/TransectStyleComplexItem.cc
+1
-5
CameraCalc.qml
src/PlanView/CameraCalc.qml
+0
-296
CameraCalcCamera.qml
src/PlanView/CameraCalcCamera.qml
+0
-4
CameraCalcGrid.qml
src/PlanView/CameraCalcGrid.qml
+0
-8
SurveyItemEditor.qml
src/PlanView/SurveyItemEditor.qml
+31
-94
qmldir
src/QmlControls/QGroundControl/Controls/qmldir
+0
-1
No files found.
qgroundcontrol.qrc
View file @
24d9dc9b
...
...
@@ -65,9 +65,8 @@
<file alias="QGroundControl/Controls/AnalyzePage.qml">src/AnalyzeView/AnalyzePage.qml</file>
<file alias="QGroundControl/Controls/AppMessages.qml">src/QmlControls/AppMessages.qml</file>
<file alias="QGroundControl/Controls/AxisMonitor.qml">src/QmlControls/AxisMonitor.qml</file>
<file alias="QGroundControl/Controls/CameraCalc.qml">src/PlanView/CameraCalc.qml</file>
<file alias="QGroundControl/Controls/CameraCalcCamera.qml">src/PlanView/CameraCalcCamera.qml</file>
<file alias="QGroundControl/Controls/CameraCalcGrid.qml">src/PlanView/CameraCalcGrid.qml</file>
<file alias="QGroundControl/Controls/CameraCalcCamera.qml">src/PlanView/CameraCalcCamera.qml</file>
<file alias="QGroundControl/Controls/CameraCalcGrid.qml">src/PlanView/CameraCalcGrid.qml</file>
<file alias="QGroundControl/Controls/CameraSection.qml">src/PlanView/CameraSection.qml</file>
<file alias="QGroundControl/Controls/ClickableColor.qml">src/QmlControls/ClickableColor.qml</file>
<file alias="QGroundControl/Controls/CorridorScanMapVisual.qml">src/PlanView/CorridorScanMapVisual.qml</file>
...
...
src/MissionManager/CameraCalc.cc
View file @
24d9dc9b
...
...
@@ -201,9 +201,8 @@ void CameraCalc::save(QJsonObject& json) const
}
}
bool
CameraCalc
::
load
(
const
QJsonObject
&
json
,
bool
forPresets
,
bool
cameraSpecInPreset
,
QString
&
errorString
)
bool
CameraCalc
::
load
(
const
QJsonObject
&
json
,
QString
&
errorString
)
{
qDebug
()
<<
"CameraCalc::load"
<<
forPresets
<<
cameraSpecInPreset
;
QJsonObject
v1Json
=
json
;
if
(
!
json
.
contains
(
JsonHelper
::
jsonVersionKey
))
{
...
...
@@ -238,7 +237,7 @@ bool CameraCalc::load(const QJsonObject& json, bool forPresets, bool cameraSpecI
return
false
;
}
_disableRecalc
=
!
forPresets
;
_disableRecalc
=
true
;
_distanceToSurfaceRelative
=
v1Json
[
distanceToSurfaceRelativeName
].
toBool
();
...
...
@@ -259,36 +258,16 @@ bool CameraCalc::load(const QJsonObject& json, bool forPresets, bool cameraSpecI
_sideOverlapFact
.
setRawValue
(
v1Json
[
sideOverlapName
].
toDouble
());
}
if
(
forPresets
)
{
if
(
isManualCamera
())
{
_distanceToSurfaceFact
.
setRawValue
(
v1Json
[
distanceToSurfaceName
].
toDouble
());
}
else
{
if
(
_valueSetIsDistanceFact
.
rawValue
().
toBool
())
{
_distanceToSurfaceFact
.
setRawValue
(
v1Json
[
distanceToSurfaceName
].
toDouble
());
}
else
{
_imageDensityFact
.
setRawValue
(
v1Json
[
imageDensityName
].
toDouble
());
}
_cameraNameFact
.
setRawValue
(
v1Json
[
cameraNameName
].
toString
());
_adjustedFootprintSideFact
.
setRawValue
(
v1Json
[
adjustedFootprintSideName
].
toDouble
());
_adjustedFootprintFrontalFact
.
setRawValue
(
v1Json
[
adjustedFootprintFrontalName
].
toDouble
());
_distanceToSurfaceFact
.
setRawValue
(
v1Json
[
distanceToSurfaceName
].
toDouble
());
if
(
!
isManualCamera
())
{
_imageDensityFact
.
setRawValue
(
v1Json
[
imageDensityName
].
toDouble
());
if
(
cameraSpecInPreset
)
{
_cameraNameFact
.
setRawValue
(
v1Json
[
cameraNameName
].
toString
());
if
(
!
CameraSpec
::
load
(
v1Json
,
errorString
))
{
_disableRecalc
=
false
;
return
false
;
}
}
}
}
else
{
_cameraNameFact
.
setRawValue
(
v1Json
[
cameraNameName
].
toString
());
_adjustedFootprintSideFact
.
setRawValue
(
v1Json
[
adjustedFootprintSideName
].
toDouble
());
_adjustedFootprintFrontalFact
.
setRawValue
(
v1Json
[
adjustedFootprintFrontalName
].
toDouble
());
_distanceToSurfaceFact
.
setRawValue
(
v1Json
[
distanceToSurfaceName
].
toDouble
());
if
(
!
isManualCamera
())
{
_imageDensityFact
.
setRawValue
(
v1Json
[
imageDensityName
].
toDouble
());
if
(
!
CameraSpec
::
load
(
v1Json
,
errorString
))
{
_disableRecalc
=
false
;
return
false
;
}
if
(
!
CameraSpec
::
load
(
v1Json
,
errorString
))
{
_disableRecalc
=
false
;
return
false
;
}
}
...
...
src/MissionManager/CameraCalc.h
View file @
24d9dc9b
...
...
@@ -70,7 +70,7 @@ public:
void
setDistanceToSurfaceRelative
(
bool
distanceToSurfaceRelative
);
void
save
(
QJsonObject
&
json
)
const
;
bool
load
(
const
QJsonObject
&
json
,
bool
forPresets
,
bool
cameraSpecInPreset
,
QString
&
errorString
);
bool
load
(
const
QJsonObject
&
json
,
QString
&
errorString
);
static
const
char
*
cameraNameName
;
static
const
char
*
valueSetIsDistanceName
;
...
...
src/MissionManager/ComplexMissionItem.cc
View file @
24d9dc9b
...
...
@@ -15,14 +15,9 @@
const
char
*
ComplexMissionItem
::
jsonComplexItemTypeKey
=
"complexItemType"
;
const
char
*
ComplexMissionItem
::
_presetSettingsKey
=
"_presets"
;
const
char
*
ComplexMissionItem
::
_presetNameKey
=
"complexItemPresetName"
;
const
char
*
ComplexMissionItem
::
_saveCameraInPresetKey
=
"complexItemCameraSavedInPreset"
;
const
char
*
ComplexMissionItem
::
_builtInPresetKey
=
"complexItemBuiltInPreset"
;
ComplexMissionItem
::
ComplexMissionItem
(
Vehicle
*
vehicle
,
bool
flyView
,
QObject
*
parent
)
:
VisualMissionItem
(
vehicle
,
flyView
,
parent
)
,
_cameraInPreset
(
true
)
,
_builtInPreset
(
false
)
{
}
...
...
@@ -31,10 +26,6 @@ const ComplexMissionItem& ComplexMissionItem::operator=(const ComplexMissionItem
{
VisualMissionItem
::
operator
=
(
other
);
_currentPreset
=
other
.
_currentPreset
;
_cameraInPreset
=
other
.
_cameraInPreset
;
_builtInPreset
=
other
.
_builtInPreset
;
return
*
this
;
}
...
...
@@ -61,39 +52,23 @@ void ComplexMissionItem::savePreset(const QString& name)
qgcApp
()
->
showMessage
(
tr
(
"This Pattern does not support Presets."
));
}
void
ComplexMissionItem
::
clearCurrentPreset
(
void
)
{
_currentPreset
.
clear
();
emit
currentPresetChanged
(
_currentPreset
);
}
void
ComplexMissionItem
::
deleteCurrentPreset
(
void
)
void
ComplexMissionItem
::
deletePreset
(
const
QString
&
name
)
{
qDebug
()
<<
"deleteCurrentPreset"
<<
_currentPreset
;
if
(
!
_currentPreset
.
isEmpty
())
{
QSettings
settings
;
settings
.
beginGroup
(
presetsSettingsGroup
());
settings
.
beginGroup
(
_presetSettingsKey
);
settings
.
remove
(
_currentPreset
);
emit
presetNamesChanged
();
QSettings
settings
;
clearCurrentPreset
();
}
settings
.
beginGroup
(
presetsSettingsGroup
());
settings
.
beginGroup
(
_presetSettingsKey
);
settings
.
remove
(
name
);
emit
presetNamesChanged
();
}
void
ComplexMissionItem
::
_savePresetJson
(
const
QString
&
name
,
QJsonObject
&
presetObject
)
{
presetObject
[
_presetNameKey
]
=
name
;
QSettings
settings
;
settings
.
beginGroup
(
presetsSettingsGroup
());
settings
.
beginGroup
(
_presetSettingsKey
);
settings
.
setValue
(
name
,
QJsonDocument
(
presetObject
).
toBinaryData
());
emit
presetNamesChanged
();
_currentPreset
=
name
;
emit
currentPresetChanged
(
name
);
}
QJsonObject
ComplexMissionItem
::
_loadPresetJson
(
const
QString
&
name
)
...
...
@@ -103,42 +78,3 @@ QJsonObject ComplexMissionItem::_loadPresetJson(const QString& name)
settings
.
beginGroup
(
_presetSettingsKey
);
return
QJsonDocument
::
fromBinaryData
(
settings
.
value
(
name
).
toByteArray
()).
object
();
}
void
ComplexMissionItem
::
_saveItem
(
QJsonObject
&
saveObject
)
{
qDebug
()
<<
"_saveItem"
<<
_cameraInPreset
;
saveObject
[
_presetNameKey
]
=
_currentPreset
;
saveObject
[
_saveCameraInPresetKey
]
=
_cameraInPreset
;
saveObject
[
_builtInPresetKey
]
=
_builtInPreset
;
}
void
ComplexMissionItem
::
_loadItem
(
const
QJsonObject
&
saveObject
)
{
_currentPreset
=
saveObject
[
_presetNameKey
].
toString
();
_cameraInPreset
=
saveObject
[
_saveCameraInPresetKey
].
toBool
(
false
);
_builtInPreset
=
saveObject
[
_builtInPresetKey
].
toBool
(
false
);
if
(
!
presetNames
().
contains
(
_currentPreset
))
{
_currentPreset
.
clear
();
}
emit
cameraInPresetChanged
(
_cameraInPreset
);
emit
currentPresetChanged
(
_currentPreset
);
emit
builtInPresetChanged
(
_builtInPreset
);
}
void
ComplexMissionItem
::
setCameraInPreset
(
bool
cameraInPreset
)
{
if
(
cameraInPreset
!=
_cameraInPreset
)
{
_cameraInPreset
=
cameraInPreset
;
emit
cameraInPresetChanged
(
_cameraInPreset
);
}
}
void
ComplexMissionItem
::
setBuiltInPreset
(
bool
builtInPreset
)
{
if
(
builtInPreset
!=
_builtInPreset
)
{
_builtInPreset
=
builtInPreset
;
emit
builtInPresetChanged
(
_builtInPreset
);
}
}
src/MissionManager/ComplexMissionItem.h
View file @
24d9dc9b
...
...
@@ -27,9 +27,6 @@ public:
Q_PROPERTY
(
double
complexDistance
READ
complexDistance
NOTIFY
complexDistanceChanged
)
Q_PROPERTY
(
bool
presetsSupported
READ
presetsSupported
CONSTANT
)
Q_PROPERTY
(
QStringList
presetNames
READ
presetNames
NOTIFY
presetNamesChanged
)
Q_PROPERTY
(
QString
currentPreset
READ
currentPreset
NOTIFY
currentPresetChanged
)
Q_PROPERTY
(
bool
cameraInPreset
READ
cameraInPreset
WRITE
setCameraInPreset
NOTIFY
cameraInPresetChanged
)
Q_PROPERTY
(
bool
builtInPreset
READ
builtInPreset
WRITE
setBuiltInPreset
NOTIFY
builtInPresetChanged
)
/// @return The distance covered the complex mission item in meters.
/// Signals complexDistanceChanged
...
...
@@ -50,8 +47,8 @@ public:
/// @param name User visible name for preset. Will replace existing preset if already exists.
Q_INVOKABLE
virtual
void
savePreset
(
const
QString
&
name
);
Q_INVOKABLE
void
clearCurrentPreset
(
void
);
Q_INVOKABLE
void
deleteCurrentPreset
(
void
);
Q_INVOKABLE
void
deletePreset
(
const
QString
&
name
);
/// Get the point of complex mission item furthest away from a coordinate
/// @param other QGeoCoordinate to which distance is calculated
...
...
@@ -67,12 +64,7 @@ public:
/// Empty string signals no support for presets.
virtual
QString
presetsSettingsGroup
(
void
)
{
return
QString
();
}
bool
presetsSupported
(
void
)
{
return
!
presetsSettingsGroup
().
isEmpty
();
}
QString
currentPreset
(
void
)
const
{
return
_currentPreset
;
}
bool
cameraInPreset
(
void
)
const
{
return
_cameraInPreset
;
}
bool
builtInPreset
(
void
)
const
{
return
_builtInPreset
;
}
void
setCameraInPreset
(
bool
cameraInPreset
);
void
setBuiltInPreset
(
bool
builtInPreset
);
bool
presetsSupported
(
void
)
{
return
!
presetsSettingsGroup
().
isEmpty
();
}
/// This mission item attribute specifies the type of the complex item.
static
const
char
*
jsonComplexItemTypeKey
;
...
...
@@ -82,28 +74,15 @@ signals:
void
boundingCubeChanged
(
void
);
void
greatestDistanceToChanged
(
void
);
void
presetNamesChanged
(
void
);
void
currentPresetChanged
(
QString
currentPreset
);
void
cameraInPresetChanged
(
bool
cameraInPreset
);
void
builtInPresetChanged
(
bool
builtInPreset
);
protected:
void
_saveItem
(
QJsonObject
&
saveObject
);
void
_loadItem
(
const
QJsonObject
&
saveObject
);
void
_savePresetJson
(
const
QString
&
name
,
QJsonObject
&
presetObject
);
QJsonObject
_loadPresetJson
(
const
QString
&
name
);
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
QString
_currentPreset
;
SettingsFact
_saveCameraInPresetFact
;
bool
_cameraInPreset
;
bool
_builtInPreset
;
static
const
char
*
_presetSettingsKey
;
static
const
char
*
_presetNameKey
;
static
const
char
*
_saveCameraInPresetKey
;
static
const
char
*
_builtInPresetKey
;
};
#endif
src/MissionManager/StructureScanComplexItem.cc
View file @
24d9dc9b
...
...
@@ -213,7 +213,7 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen
setSequenceNumber
(
sequenceNumber
);
// Load CameraCalc first since it will trigger camera name change which will trounce gimbal angles
if
(
!
_cameraCalc
.
load
(
complexObject
[
_jsonCameraCalcKey
].
toObject
(),
false
/* forPresets */
,
false
/* cameraSpecInPreset */
,
errorString
))
{
if
(
!
_cameraCalc
.
load
(
complexObject
[
_jsonCameraCalcKey
].
toObject
(),
errorString
))
{
return
false
;
}
...
...
src/MissionManager/TransectStyleComplexItem.cc
View file @
24d9dc9b
...
...
@@ -134,8 +134,6 @@ void TransectStyleComplexItem::setDirty(bool dirty)
void
TransectStyleComplexItem
::
_save
(
QJsonObject
&
complexObject
)
{
ComplexMissionItem
::
_saveItem
(
complexObject
);
QJsonObject
innerObject
;
innerObject
[
JsonHelper
::
jsonVersionKey
]
=
1
;
...
...
@@ -189,8 +187,6 @@ void TransectStyleComplexItem::setSequenceNumber(int sequenceNumber)
bool
TransectStyleComplexItem
::
_load
(
const
QJsonObject
&
complexObject
,
bool
forPresets
,
QString
&
errorString
)
{
ComplexMissionItem
::
_loadItem
(
complexObject
);
QList
<
JsonHelper
::
KeyValidateInfo
>
keyInfoList
=
{
{
_jsonTransectStyleComplexItemKey
,
QJsonValue
::
Object
,
true
},
};
...
...
@@ -248,7 +244,7 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, bool forP
}
// Load CameraCalc data
if
(
!
_cameraCalc
.
load
(
innerObject
[
_jsonCameraCalcKey
].
toObject
(),
forPresets
,
cameraInPreset
(),
errorString
))
{
if
(
!
_cameraCalc
.
load
(
innerObject
[
_jsonCameraCalcKey
].
toObject
(),
errorString
))
{
return
false
;
}
...
...
src/PlanView/CameraCalc.qml
deleted
100644 → 0
View file @
673b9be7
This diff is collapsed.
Click to expand it.
src/PlanView/CameraCalcCamera.qml
View file @
24d9dc9b
...
...
@@ -14,16 +14,12 @@ Column {
anchors.right
:
parent
.
right
spacing
:
_margin
visible
:
!
usingPreset
||
!
cameraSpecifiedInPreset
property
var
cameraCalc
property
bool
vehicleFlightIsFrontal
:
true
property
string
distanceToSurfaceLabel
property
int
distanceToSurfaceAltitudeMode
:
QGroundControl
.
AltitudeModeNone
property
string
frontalDistanceLabel
property
string
sideDistanceLabel
property
bool
usingPreset
:
false
property
bool
cameraSpecifiedInPreset
:
false
property
real
_margin
:
ScreenTools
.
defaultFontPixelWidth
/
2
property
string
_cameraName
:
cameraCalc
.
cameraName
.
value
...
...
src/PlanView/CameraCalcGrid.qml
View file @
24d9dc9b
...
...
@@ -14,16 +14,12 @@ Column {
anchors.right
:
parent
.
right
spacing
:
_margin
visible
:
!
usingPreset
||
!
cameraSpecifiedInPreset
property
var
cameraCalc
property
bool
vehicleFlightIsFrontal
:
true
property
string
distanceToSurfaceLabel
property
int
distanceToSurfaceAltitudeMode
:
QGroundControl
.
AltitudeModeNone
property
string
frontalDistanceLabel
property
string
sideDistanceLabel
property
bool
usingPreset
:
false
property
bool
cameraSpecifiedInPreset
:
false
property
real
_margin
:
ScreenTools
.
defaultFontPixelWidth
/
2
property
string
_cameraName
:
cameraCalc
.
cameraName
.
value
...
...
@@ -49,7 +45,6 @@ Column {
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
_margin
visible
:
!
usingPreset
Item
{
Layout.fillWidth
:
true
}
QGCLabel
{
Layout.preferredWidth
:
_root
.
_fieldWidth
...
...
@@ -65,7 +60,6 @@ Column {
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
_margin
visible
:
!
usingPreset
QGCLabel
{
text
:
qsTr
(
"
Overlap
"
);
Layout.fillWidth
:
true
}
FactTextField
{
Layout.preferredWidth
:
_root
.
_fieldWidth
...
...
@@ -82,7 +76,6 @@ Column {
text
:
qsTr
(
"
Select one:
"
)
Layout.preferredWidth
:
parent
.
width
Layout.columnSpan
:
2
visible
:
!
usingPreset
}
GridLayout
{
...
...
@@ -91,7 +84,6 @@ Column {
columnSpacing
:
_margin
rowSpacing
:
_margin
columns
:
2
visible
:
!
usingPreset
QGCRadioButton
{
id
:
fixedDistanceRadio
...
...
src/PlanView/SurveyItemEditor.qml
View file @
24d9dc9b
...
...
@@ -28,8 +28,6 @@ Rectangle {
property
real
_fieldWidth
:
ScreenTools
.
defaultFontPixelWidth
*
10.5
property
var
_vehicle
:
QGroundControl
.
multiVehicleManager
.
activeVehicle
?
QGroundControl
.
multiVehicleManager
.
activeVehicle
:
QGroundControl
.
multiVehicleManager
.
offlineEditingVehicle
property
real
_cameraMinTriggerInterval
:
missionItem
.
cameraCalc
.
minTriggerInterval
.
rawValue
property
string
_currentPreset
:
missionItem
.
currentPreset
property
bool
_usingPreset
:
_currentPreset
!==
""
function
polygonCaptureStarted
()
{
missionItem
.
clearPolygon
()
...
...
@@ -94,8 +92,6 @@ Rectangle {
missionItem
.
cameraCalc
.
distanceToSurfaceRelative
frontalDistanceLabel
:
qsTr
(
"
Trigger Dist
"
)
sideDistanceLabel
:
qsTr
(
"
Spacing
"
)
usingPreset
:
_usingPreset
cameraSpecifiedInPreset
:
missionItem
.
cameraInPreset
}
SectionHeader
{
...
...
@@ -134,12 +130,10 @@ Rectangle {
QGCLabel
{
text
:
qsTr
(
"
Turnaround dist
"
)
visible
:
!
_usingPreset
}
FactTextField
{
fact
:
missionItem
.
turnAroundDistance
Layout.fillWidth
:
true
visible
:
!
_usingPreset
}
}
...
...
@@ -152,7 +146,7 @@ Rectangle {
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
_margin
visible
:
transectsHeader
.
checked
&&
!
_usingPreset
visible
:
transectsHeader
.
checked
/*
Temporarily removed due to bug https://github.com/mavlink/qgroundcontrol/issues/7005
...
...
@@ -213,14 +207,13 @@ Rectangle {
id
:
terrainHeader
text
:
qsTr
(
"
Terrain
"
)
checked
:
missionItem
.
followTerrain
visible
:
!
_usingPreset
}
ColumnLayout
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
_margin
visible
:
terrainHeader
.
checked
&&
!
_usingPreset
visible
:
terrainHeader
.
checked
QGCCheckBox
{
...
...
@@ -280,102 +273,53 @@ Rectangle {
missionItem
.
cameraCalc
.
distanceToSurfaceRelative
frontalDistanceLabel
:
qsTr
(
"
Trigger Dist
"
)
sideDistanceLabel
:
qsTr
(
"
Spacing
"
)
usingPreset
:
_usingPreset
cameraSpecifiedInPreset
:
missionItem
.
cameraInPreset
}
}
// Camera Column
Column
{
Column
Layout
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
_margin
visible
:
tabBar
.
currentIndex
==
2
QGCLabel
{
Layout.fillWidth
:
true
text
:
qsTr
(
"
Presets
"
)
wrapMode
:
Text
.
WordWrap
}
QGCComboBox
{
id
:
presetCombo
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
model
:
_presetList
property
var
_presetList
:
[]
readonly
property
int
_indexCustom
:
0
readonly
property
int
_indexCreate
:
1
readonly
property
int
_indexDelete
:
2
readonly
property
int
_indexLabel
:
3
readonly
property
int
_indexFirstPreset
:
4
Component.onCompleted
:
_updateList
()
onActivated
:
{
if
(
index
==
_indexCustom
)
{
missionItem
.
clearCurrentPreset
()
}
else
if
(
index
==
_indexCreate
)
{
mainWindow
.
showComponentDialog
(
savePresetDialog
,
qsTr
(
"
Save Preset
"
),
mainWindow
.
showDialogDefaultWidth
,
StandardButton
.
Save
|
StandardButton
.
Cancel
)
}
else
if
(
index
==
_indexDelete
)
{
if
(
missionItem
.
builtInPreset
)
{
mainWindow
.
showMessage
(
qsTr
(
"
Delete Preset
"
),
qsTr
(
"
This preset cannot be deleted.
"
))
}
else
{
missionItem
.
deleteCurrentPreset
()
}
}
else
if
(
index
>=
_indexFirstPreset
)
{
missionItem
.
loadPreset
(
textAt
(
index
))
}
else
{
_selectCurrentPreset
()
}
}
Connections
{
target
:
missionItem
onPresetNamesChanged
:
presetCombo
.
_updateList
()
onCurrentPresetChanged
:
presetCombo
.
_selectCurrentPreset
()
}
// There is some major strangeness going on with programatically changing the index of a combo box in this scenario.
// If you just set currentIndex directly it will just change back 1o -1 magically. Has something to do with resetting
// model on the fly I think. But not sure. To work around I delay the currentIndex changes to let things unwind.
Timer
{
id
:
delayedIndexChangeTimer
interval
:
10
property
int
newIndex
Layout.fillWidth
:
true
model
:
missionItem
.
presetNames
}
onTriggered
:
presetCombo
.
currentIndex
=
newIndex
RowLayout
{
Layout.fillWidth
:
true
QGCButton
{
Layout.fillWidth
:
true
text
:
qsTr
(
"
Apply Preset
"
)
enabled
:
missionItem
.
presetNames
.
length
!=
0
onClicked
:
missionItem
.
loadPreset
(
presetCombo
.
textAt
(
presetCombo
.
currentIndex
))
}
function
delayedIndexChange
(
index
)
{
delayedIndexChangeTimer
.
newIndex
=
index
delayedIndexChangeTimer
.
start
()
QGCButton
{
Layout.fillWidth
:
true
text
:
qsTr
(
"
Delete Preset
"
)
enabled
:
missionItem
.
presetNames
.
length
!=
0
onClicked
:
missionItem
.
deletePreset
(
presetCombo
.
textAt
(
presetCombo
.
currentIndex
))
}
function
_updateList
()
{
_presetList
=
[]
_presetList
.
push
(
qsTr
(
"
Custom (specify all settings)
"
))
_presetList
.
push
(
qsTr
(
"
Save Settings As Preset
"
))
_presetList
.
push
(
qsTr
(
"
Delete Current Preset
"
))
if
(
missionItem
.
presetNames
.
length
!==
0
)
{
_presetList
.
push
(
qsTr
(
"
Presets:
"
))
}
}
for
(
var
i
=
0
;
i
<
missionItem
.
presetNames
.
length
;
i
++
)
{
_presetList
.
push
(
missionItem
.
presetNames
[
i
])
}
model
=
_presetList
_selectCurrentPreset
()
}
Item
{
height
:
ScreenTools
.
defaultFontPixelHeight
;
width
:
1
}
function
_selectCurrentPreset
()
{
if
(
_usingPreset
)
{
var
newIndex
=
find
(
_currentPreset
)
if
(
newIndex
!==
-
1
)
{
delayedIndexChange
(
newIndex
)
return
}
}
delayedIndexChange
(
presetCombo
.
_indexCustom
)
}
QGCButton
{
Layout.alignment
:
Qt
.
AlignCenter
Layout.fillWidth
:
true
text
:
qsTr
(
"
Save Settings As New Preset
"
)
onClicked
:
mainWindow
.
showComponentDialog
(
savePresetDialog
,
qsTr
(
"
Save Preset
"
),
mainWindow
.
showDialogDefaultWidth
,
StandardButton
.
Save
|
StandardButton
.
Cancel
)
}
}
// Camera Column
...
...
@@ -408,13 +352,6 @@ Rectangle {
QGCTextField
{
id
:
presetNameField
Layout.fillWidth
:
true
text
:
_currentPreset
}
QGCCheckBox
{
text
:
qsTr
(
"
Save Camera In Preset
"
)
checked
:
missionItem
.
cameraInPreset
onClicked
:
missionItem
.
cameraInPreset
=
checked
}
}
}
...
...
src/QmlControls/QGroundControl/Controls/qmldir
View file @
24d9dc9b
...
...
@@ -3,7 +3,6 @@ Module QGroundControl.Controls
AnalyzePage 1.0 AnalyzePage.qml
AppMessages 1.0 AppMessages.qml
AxisMonitor 1.0 AxisMonitor.qml
CameraCalc 1.0 CameraCalc.qml
CameraCalcCamera 1.0 CameraCalcCamera.qml
CameraCalcGrid 1.0 CameraCalcGrid.qml
APMSubMotorDisplay 1.0 APMSubMotorDisplay.qml
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment