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
99b6c1c1
Commit
99b6c1c1
authored
Apr 16, 2017
by
Don Gagne
Committed by
GitHub
Apr 16, 2017
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #4987 from DonLakeFlyer/Fixes
Fixes
parents
1b9e036e
c89cf0ba
Changes
9
Hide whitespace changes
Inline
Side-by-side
Showing
9 changed files
with
57 additions
and
115 deletions
+57
-115
FlightDisplayViewMap.qml
src/FlightDisplay/FlightDisplayViewMap.qml
+2
-0
GuidedActionConfirm.qml
src/FlightDisplay/GuidedActionConfirm.qml
+1
-0
FlightMap.qml
src/FlightMap/FlightMap.qml
+1
-0
MissionSettings.FactMetaData.json
src/MissionManager/MissionSettings.FactMetaData.json
+0
-8
MissionSettingsItem.cc
src/MissionManager/MissionSettingsItem.cc
+17
-76
MissionSettingsItem.h
src/MissionManager/MissionSettingsItem.h
+5
-13
MissionSettingsEditor.qml
src/PlanView/MissionSettingsEditor.qml
+4
-5
PlanView.qml
src/PlanView/PlanView.qml
+26
-12
SimpleItemMapVisual.qml
src/PlanView/SimpleItemMapVisual.qml
+1
-1
No files found.
src/FlightDisplay/FlightDisplayViewMap.qml
View file @
99b6c1c1
...
@@ -29,9 +29,11 @@ FlightMap {
...
@@ -29,9 +29,11 @@ FlightMap {
mapName
:
_mapName
mapName
:
_mapName
allowGCSLocationCenter
:
!
userPanned
allowGCSLocationCenter
:
!
userPanned
allowVehicleLocationCenter
:
!
_keepVehicleCentered
allowVehicleLocationCenter
:
!
_keepVehicleCentered
planView
:
false
property
alias
scaleState
:
mapScale
.
state
property
alias
scaleState
:
mapScale
.
state
// The following properties must be set by the consumer
property
var
missionController
property
var
missionController
property
var
geoFenceController
property
var
geoFenceController
property
var
rallyPointController
property
var
rallyPointController
...
...
src/FlightDisplay/GuidedActionConfirm.qml
View file @
99b6c1c1
...
@@ -51,6 +51,7 @@ Rectangle {
...
@@ -51,6 +51,7 @@ Rectangle {
anchors.left
:
slider
.
left
anchors.left
:
slider
.
left
anchors.right
:
slider
.
right
anchors.right
:
slider
.
right
horizontalAlignment
:
Text
.
AlignHCenter
horizontalAlignment
:
Text
.
AlignHCenter
font.pointSize
:
ScreenTools
.
largeFontPointSize
}
}
QGCLabel
{
QGCLabel
{
...
...
src/FlightMap/FlightMap.qml
View file @
99b6c1c1
...
@@ -38,6 +38,7 @@ Map {
...
@@ -38,6 +38,7 @@ Map {
property
bool
allowVehicleLocationCenter
:
false
///< true: map will center/zoom to vehicle location one time
property
bool
allowVehicleLocationCenter
:
false
///< true: map will center/zoom to vehicle location one time
property
bool
firstGCSPositionReceived
:
false
///< true: first gcs position update was responded to
property
bool
firstGCSPositionReceived
:
false
///< true: first gcs position update was responded to
property
bool
firstVehiclePositionReceived
:
false
///< true: first vehicle position update was responded to
property
bool
firstVehiclePositionReceived
:
false
///< true: first vehicle position update was responded to
property
bool
planView
:
false
///< true: map being using for Plan view, items should be draggable
readonly
property
real
maxZoomLevel
:
20
readonly
property
real
maxZoomLevel
:
20
...
...
src/MissionManager/MissionSettings.FactMetaData.json
View file @
99b6c1c1
...
@@ -6,13 +6,5 @@
...
@@ -6,13 +6,5 @@
"units"
:
"m"
,
"units"
:
"m"
,
"decimalPlaces"
:
1
,
"decimalPlaces"
:
1
,
"defaultValue"
:
0
"defaultValue"
:
0
},
{
"name"
:
"MissionEndAction"
,
"shortDescription"
:
"The action to take when the mission completed."
,
"type"
:
"uint32"
,
"enumStrings"
:
"No action on mission end,Loiter after mission end,RTL after mission end"
,
"enumValues"
:
"0,1,2"
,
"defaultValue"
:
0
}
}
]
]
src/MissionManager/MissionSettingsItem.cc
View file @
99b6c1c1
...
@@ -24,18 +24,17 @@ QGC_LOGGING_CATEGORY(MissionSettingsComplexItemLog, "MissionSettingsComplexItemL
...
@@ -24,18 +24,17 @@ QGC_LOGGING_CATEGORY(MissionSettingsComplexItemLog, "MissionSettingsComplexItemL
const
char
*
MissionSettingsItem
::
jsonComplexItemTypeValue
=
"MissionSettings"
;
const
char
*
MissionSettingsItem
::
jsonComplexItemTypeValue
=
"MissionSettings"
;
const
char
*
MissionSettingsItem
::
_plannedHomePositionAltitudeName
=
"PlannedHomePositionAltitude"
;
const
char
*
MissionSettingsItem
::
_plannedHomePositionAltitudeName
=
"PlannedHomePositionAltitude"
;
const
char
*
MissionSettingsItem
::
_missionEndActionName
=
"MissionEndAction"
;
QMap
<
QString
,
FactMetaData
*>
MissionSettingsItem
::
_metaDataMap
;
QMap
<
QString
,
FactMetaData
*>
MissionSettingsItem
::
_metaDataMap
;
MissionSettingsItem
::
MissionSettingsItem
(
Vehicle
*
vehicle
,
QObject
*
parent
)
MissionSettingsItem
::
MissionSettingsItem
(
Vehicle
*
vehicle
,
QObject
*
parent
)
:
ComplexMissionItem
(
vehicle
,
parent
)
:
ComplexMissionItem
(
vehicle
,
parent
)
,
_plannedHomePositionAltitudeFact
(
0
,
_plannedHomePositionAltitudeName
,
FactMetaData
::
valueTypeDouble
)
,
_plannedHomePositionAltitudeFact
(
0
,
_plannedHomePositionAltitudeName
,
FactMetaData
::
valueTypeDouble
)
,
_missionEnd
ActionFact
(
0
,
_missionEndActionName
,
FactMetaData
::
valueTypeUint32
)
,
_missionEnd
RTL
(
false
)
,
_cameraSection
(
vehicle
)
,
_cameraSection
(
vehicle
)
,
_speedSection
(
vehicle
)
,
_speedSection
(
vehicle
)
,
_sequenceNumber
(
0
)
,
_sequenceNumber
(
0
)
,
_dirty
(
false
)
,
_dirty
(
false
)
{
{
_editorQml
=
"qrc:/qml/MissionSettingsEditor.qml"
;
_editorQml
=
"qrc:/qml/MissionSettingsEditor.qml"
;
...
@@ -44,27 +43,25 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent)
...
@@ -44,27 +43,25 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent)
}
}
_plannedHomePositionAltitudeFact
.
setMetaData
(
_metaDataMap
[
_plannedHomePositionAltitudeName
]);
_plannedHomePositionAltitudeFact
.
setMetaData
(
_metaDataMap
[
_plannedHomePositionAltitudeName
]);
_missionEndActionFact
.
setMetaData
(
_metaDataMap
[
_missionEndActionName
]);
_plannedHomePositionAltitudeFact
.
setRawValue
(
_plannedHomePositionAltitudeFact
.
rawDefaultValue
());
_plannedHomePositionAltitudeFact
.
setRawValue
(
_plannedHomePositionAltitudeFact
.
rawDefaultValue
());
_missionEndActionFact
.
setRawValue
(
_missionEndActionFact
.
rawDefaultValue
());
setHomePositionSpecialCase
(
true
);
setHomePositionSpecialCase
(
true
);
connect
(
this
,
&
MissionSettingsItem
::
specifyMissionFlightSpeedChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
connect
(
this
,
&
MissionSettingsItem
::
specifyMissionFlightSpeedChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
connect
(
this
,
&
MissionSettingsItem
::
missionEndRTLChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
connect
(
&
_cameraSection
,
&
CameraSection
::
itemCountChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
connect
(
&
_cameraSection
,
&
CameraSection
::
itemCountChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
connect
(
&
_speedSection
,
&
CameraSection
::
itemCountChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
connect
(
&
_speedSection
,
&
CameraSection
::
itemCountChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
connect
(
&
_plannedHomePositionAltitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
MissionSettingsItem
::
_setDirty
);
connect
(
&
_plannedHomePositionAltitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
MissionSettingsItem
::
_setDirty
);
connect
(
&
_plannedHomePositionAltitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
MissionSettingsItem
::
_updateAltitudeInCoordinate
);
connect
(
&
_
missionEndActionFact
,
&
Fact
::
valueChanged
,
this
,
&
MissionSettingsItem
::
_setDirty
);
connect
(
&
_
plannedHomePositionAltitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
MissionSettingsItem
::
_updateAltitudeInCoordinate
);
connect
(
&
_cameraSection
,
&
CameraSection
::
dirtyChanged
,
this
,
&
MissionSettingsItem
::
_sectionDirtyChanged
);
connect
(
&
_cameraSection
,
&
CameraSection
::
dirtyChanged
,
this
,
&
MissionSettingsItem
::
_sectionDirtyChanged
);
connect
(
&
_speedSection
,
&
SpeedSection
::
dirtyChanged
,
this
,
&
MissionSettingsItem
::
_sectionDirtyChanged
);
connect
(
&
_speedSection
,
&
SpeedSection
::
dirtyChanged
,
this
,
&
MissionSettingsItem
::
_sectionDirtyChanged
);
connect
(
&
_cameraSection
,
&
CameraSection
::
specifyGimbalChanged
,
this
,
&
MissionSettingsItem
::
specifiedGimbalYawChanged
);
connect
(
&
_cameraSection
,
&
CameraSection
::
specifyGimbalChanged
,
this
,
&
MissionSettingsItem
::
specifiedGimbalYawChanged
);
connect
(
&
_cameraSection
,
&
CameraSection
::
specifiedGimbalYawChanged
,
this
,
&
MissionSettingsItem
::
specifiedGimbalYawChanged
);
connect
(
&
_cameraSection
,
&
CameraSection
::
specifiedGimbalYawChanged
,
this
,
&
MissionSettingsItem
::
specifiedGimbalYawChanged
);
}
}
...
@@ -164,43 +161,7 @@ bool MissionSettingsItem::addMissionEndAction(QList<MissionItem*>& items, int se
...
@@ -164,43 +161,7 @@ bool MissionSettingsItem::addMissionEndAction(QList<MissionItem*>& items, int se
// IMPORTANT NOTE: If anything changes here you must also change MissionSettingsItem::scanForMissionSettings
// IMPORTANT NOTE: If anything changes here you must also change MissionSettingsItem::scanForMissionSettings
// Find last waypoint coordinate information so we have a lat/lon/alt to use
if
(
_missionEndRTL
)
{
QGeoCoordinate
lastWaypointCoord
;
MAV_FRAME
lastWaypointFrame
;
bool
found
=
false
;
for
(
int
i
=
items
.
count
()
-
1
;
i
>
0
;
i
--
)
{
MissionItem
*
missionItem
=
items
[
i
];
const
MissionCommandUIInfo
*
uiInfo
=
qgcApp
()
->
toolbox
()
->
missionCommandTree
()
->
getUIInfo
(
_vehicle
,
(
MAV_CMD
)
missionItem
->
command
());
if
(
uiInfo
->
specifiesCoordinate
()
&&
!
uiInfo
->
isStandaloneCoordinate
())
{
lastWaypointCoord
=
missionItem
->
coordinate
();
lastWaypointFrame
=
missionItem
->
frame
();
found
=
true
;
break
;
}
}
if
(
!
found
)
{
return
false
;
}
switch
(
_missionEndActionFact
.
rawValue
().
toInt
())
{
case
MissionEndLoiter
:
qCDebug
(
MissionSettingsComplexItemLog
)
<<
"Appending end action Loiter seqNum"
<<
seqNum
;
item
=
new
MissionItem
(
seqNum
,
MAV_CMD_NAV_LOITER_UNLIM
,
lastWaypointFrame
,
0
,
0
,
// param 1-2 unused
0
,
// use default loiter radius
0
,
// param 4 not used
lastWaypointCoord
.
latitude
(),
lastWaypointCoord
.
longitude
(),
lastWaypointCoord
.
altitude
(),
true
,
// autoContinue
false
,
// isCurrentItem
missionItemParent
);
break
;
case
MissionEndRTL
:
qCDebug
(
MissionSettingsComplexItemLog
)
<<
"Appending end action RTL seqNum"
<<
seqNum
;
qCDebug
(
MissionSettingsComplexItemLog
)
<<
"Appending end action RTL seqNum"
<<
seqNum
;
item
=
new
MissionItem
(
seqNum
,
item
=
new
MissionItem
(
seqNum
,
MAV_CMD_NAV_RETURN_TO_LAUNCH
,
MAV_CMD_NAV_RETURN_TO_LAUNCH
,
...
@@ -209,12 +170,6 @@ bool MissionSettingsItem::addMissionEndAction(QList<MissionItem*>& items, int se
...
@@ -209,12 +170,6 @@ bool MissionSettingsItem::addMissionEndAction(QList<MissionItem*>& items, int se
true
,
// autoContinue
true
,
// autoContinue
false
,
// isCurrentItem
false
,
// isCurrentItem
missionItemParent
);
missionItemParent
);
break
;
default:
break
;
}
if
(
item
)
{
items
.
append
(
item
);
items
.
append
(
item
);
return
true
;
return
true
;
}
else
{
}
else
{
...
@@ -248,25 +203,11 @@ bool MissionSettingsItem::scanForMissionSettings(QmlObjectListModel* visualItems
...
@@ -248,25 +203,11 @@ bool MissionSettingsItem::scanForMissionSettings(QmlObjectListModel* visualItems
if
(
item
)
{
if
(
item
)
{
MissionItem
&
missionItem
=
item
->
missionItem
();
MissionItem
&
missionItem
=
item
->
missionItem
();
switch
((
MAV_CMD
)
item
->
command
())
{
if
(
missionItem
.
command
()
==
MAV_CMD_NAV_RETURN_TO_LAUNCH
&&
case
MAV_CMD_NAV_LOITER_UNLIM
:
missionItem
.
param1
()
==
0
&&
missionItem
.
param2
()
==
0
&&
missionItem
.
param3
()
==
0
&&
missionItem
.
param4
()
==
0
&&
missionItem
.
param5
()
==
0
&&
missionItem
.
param6
()
==
0
&&
missionItem
.
param7
()
==
0
)
{
if
(
missionItem
.
param1
()
==
0
&&
missionItem
.
param2
()
==
0
&&
missionItem
.
param3
()
==
0
&&
missionItem
.
param4
()
==
0
)
{
qCDebug
(
MissionSettingsComplexItemLog
)
<<
"Scan: Found end action RTL"
;
qCDebug
(
MissionSettingsComplexItemLog
)
<<
"Scan: Found end action Loiter"
;
settingsItem
->
_missionEndRTL
=
true
;
settingsItem
->
missionEndAction
()
->
setRawValue
(
MissionEndLoiter
);
visualItems
->
removeAt
(
lastIndex
)
->
deleteLater
();
visualItems
->
removeAt
(
lastIndex
)
->
deleteLater
();
}
break
;
case
MAV_CMD_NAV_RETURN_TO_LAUNCH
:
if
(
missionItem
.
param1
()
==
0
&&
missionItem
.
param2
()
==
0
&&
missionItem
.
param3
()
==
0
&&
missionItem
.
param4
()
==
0
&&
missionItem
.
param5
()
==
0
&&
missionItem
.
param6
()
==
0
&&
missionItem
.
param7
()
==
0
)
{
qCDebug
(
MissionSettingsComplexItemLog
)
<<
"Scan: Found end action RTL"
;
settingsItem
->
missionEndAction
()
->
setRawValue
(
MissionEndRTL
);
visualItems
->
removeAt
(
lastIndex
)
->
deleteLater
();
}
break
;
default:
break
;
}
}
}
}
...
...
src/MissionManager/MissionSettingsItem.h
View file @
99b6c1c1
...
@@ -26,20 +26,12 @@ class MissionSettingsItem : public ComplexMissionItem
...
@@ -26,20 +26,12 @@ class MissionSettingsItem : public ComplexMissionItem
public:
public:
MissionSettingsItem
(
Vehicle
*
vehicle
,
QObject
*
parent
=
NULL
);
MissionSettingsItem
(
Vehicle
*
vehicle
,
QObject
*
parent
=
NULL
);
enum
MissionEndAction
{
MissionEndNoAction
,
MissionEndLoiter
,
MissionEndRTL
};
Q_ENUMS
(
MissionEndAction
)
Q_PROPERTY
(
Fact
*
missionEndAction
READ
missionEndAction
CONSTANT
)
Q_PROPERTY
(
Fact
*
plannedHomePositionAltitude
READ
plannedHomePositionAltitude
CONSTANT
)
Q_PROPERTY
(
Fact
*
plannedHomePositionAltitude
READ
plannedHomePositionAltitude
CONSTANT
)
Q_PROPERTY
(
bool
missionEndRTL
MEMBER
_missionEndRTL
NOTIFY
missionEndRTLChanged
)
Q_PROPERTY
(
QObject
*
cameraSection
READ
cameraSection
CONSTANT
)
Q_PROPERTY
(
QObject
*
cameraSection
READ
cameraSection
CONSTANT
)
Q_PROPERTY
(
QObject
*
speedSection
READ
speedSection
CONSTANT
)
Q_PROPERTY
(
QObject
*
speedSection
READ
speedSection
CONSTANT
)
Fact
*
plannedHomePositionAltitude
(
void
)
{
return
&
_plannedHomePositionAltitudeFact
;
}
Fact
*
plannedHomePositionAltitude
(
void
)
{
return
&
_plannedHomePositionAltitudeFact
;
}
Fact
*
missionEndAction
(
void
)
{
return
&
_missionEndActionFact
;
}
QObject
*
cameraSection
(
void
)
{
return
&
_cameraSection
;
}
QObject
*
cameraSection
(
void
)
{
return
&
_cameraSection
;
}
QObject
*
speedSection
(
void
)
{
return
&
_speedSection
;
}
QObject
*
speedSection
(
void
)
{
return
&
_speedSection
;
}
...
@@ -92,7 +84,8 @@ public:
...
@@ -92,7 +84,8 @@ public:
static
const
char
*
jsonComplexItemTypeValue
;
static
const
char
*
jsonComplexItemTypeValue
;
signals:
signals:
void
specifyMissionFlightSpeedChanged
(
bool
specifyMissionFlightSpeed
);
void
specifyMissionFlightSpeedChanged
(
bool
specifyMissionFlightSpeed
);
void
missionEndRTLChanged
(
bool
missionEndRTL
);
private
slots
:
private
slots
:
void
_setDirtyAndUpdateLastSequenceNumber
(
void
);
void
_setDirtyAndUpdateLastSequenceNumber
(
void
);
...
@@ -101,9 +94,9 @@ private slots:
...
@@ -101,9 +94,9 @@ private slots:
void
_updateAltitudeInCoordinate
(
QVariant
value
);
void
_updateAltitudeInCoordinate
(
QVariant
value
);
private:
private:
QGeoCoordinate
_plannedHomePositionCoordinate
;
// Does not include altitde
QGeoCoordinate
_plannedHomePositionCoordinate
;
// Does not include altit
u
de
Fact
_plannedHomePositionAltitudeFact
;
Fact
_plannedHomePositionAltitudeFact
;
Fact
_missionEndActionFact
;
bool
_missionEndRTL
;
CameraSection
_cameraSection
;
CameraSection
_cameraSection
;
SpeedSection
_speedSection
;
SpeedSection
_speedSection
;
...
@@ -113,7 +106,6 @@ private:
...
@@ -113,7 +106,6 @@ private:
static
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
static
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
static
const
char
*
_plannedHomePositionAltitudeName
;
static
const
char
*
_plannedHomePositionAltitudeName
;
static
const
char
*
_missionEndActionName
;
};
};
#endif
#endif
src/PlanView/MissionSettingsEditor.qml
View file @
99b6c1c1
...
@@ -124,11 +124,10 @@ Rectangle {
...
@@ -124,11 +124,10 @@ Rectangle {
}
}
}
// GridLayout
}
// GridLayout
FactComboBox
{
QGCCheckBox
{
anchors.left
:
parent
.
left
text
:
qsTr
(
"
RTL after mission end
"
)
anchors.right
:
parent
.
right
checked
:
missionItem
.
missionEndRTL
fact
:
missionItem
.
missionEndAction
onClicked
:
missionItem
.
missionEndRTL
=
checked
indexModel
:
false
}
}
}
}
...
...
src/PlanView/PlanView.qml
View file @
99b6c1c1
...
@@ -42,15 +42,16 @@ QGCView {
...
@@ -42,15 +42,16 @@ QGCView {
readonly
property
real
_toolButtonTopMargin
:
parent
.
height
-
ScreenTools
.
availableHeight
+
(
ScreenTools
.
defaultFontPixelHeight
/
2
)
readonly
property
real
_toolButtonTopMargin
:
parent
.
height
-
ScreenTools
.
availableHeight
+
(
ScreenTools
.
defaultFontPixelHeight
/
2
)
readonly
property
var
_defaultVehicleCoordinate
:
QtPositioning
.
coordinate
(
37.803784
,
-
122.462276
)
readonly
property
var
_defaultVehicleCoordinate
:
QtPositioning
.
coordinate
(
37.803784
,
-
122.462276
)
property
var
_visualItems
:
missionController
.
visualItems
property
var
_visualItems
:
missionController
.
visualItems
property
var
_currentMissionItem
property
var
_currentMissionItem
property
int
_currentMissionIndex
:
0
property
int
_currentMissionIndex
:
0
property
bool
_lightWidgetBorders
:
editorMap
.
isSatelliteMap
property
bool
_lightWidgetBorders
:
editorMap
.
isSatelliteMap
property
bool
_addWaypointOnClick
:
false
property
bool
_addWaypointOnClick
:
false
property
bool
_singleComplexItem
:
missionController
.
complexMissionItemNames
.
length
===
1
property
bool
_singleComplexItem
:
missionController
.
complexMissionItemNames
.
length
===
1
property
real
_toolbarHeight
:
_qgcView
.
height
-
ScreenTools
.
availableHeight
property
real
_toolbarHeight
:
_qgcView
.
height
-
ScreenTools
.
availableHeight
property
int
_editingLayer
:
_layerMission
property
int
_editingLayer
:
_layerMission
property
bool
_autoSync
:
QGroundControl
.
settingsManager
.
appSettings
.
automaticMissionUpload
.
rawValue
!=
0
property
bool
_autoSync
:
QGroundControl
.
settingsManager
.
appSettings
.
automaticMissionUpload
.
rawValue
!=
0
property
bool
_switchToFlyAfterUpload
:
false
/// The controller which should be called for load/save, send to/from vehicle calls
/// The controller which should be called for load/save, send to/from vehicle calls
property
var
_syncDropDownController
:
missionController
property
var
_syncDropDownController
:
missionController
...
@@ -141,8 +142,19 @@ QGCView {
...
@@ -141,8 +142,19 @@ QGCView {
onClicked
:
{
onClicked
:
{
_activeVehicle
.
flightMode
=
_activeVehicle
.
pauseFlightMode
_activeVehicle
.
flightMode
=
_activeVehicle
.
pauseFlightMode
missionController
.
sendToVehicle
()
missionController
.
sendToVehicle
()
toolbar
.
showFlyView
()
hideDialog
()
hideDialog
()
if
(
_switchToFlyAfterUpload
)
{
toolbar
.
showFlyView
()
}
}
}
QGCButton
{
text
:
qsTr
(
"
Exit planning (no upload)
"
)
visible
:
_switchToFlyAfterUpload
onClicked
:
{
hideDialog
()
toolbar
.
showFlyView
()
}
}
}
}
}
}
...
@@ -159,8 +171,9 @@ QGCView {
...
@@ -159,8 +171,9 @@ QGCView {
setCurrentItem
(
0
)
setCurrentItem
(
0
)
}
}
function
_denyUpload
()
{
function
_denyUpload
(
switchToFly
)
{
if
(
_activeVehicle
&&
_activeVehicle
.
armed
&&
_activeVehicle
.
flightMode
===
_activeVehicle
.
missionFlightMode
)
{
if
(
_activeVehicle
&&
_activeVehicle
.
armed
&&
_activeVehicle
.
flightMode
===
_activeVehicle
.
missionFlightMode
)
{
_switchToFlyAfterUpload
=
switchToFly
_qgcView
.
showDialog
(
activeMissionUploadDialogComponent
,
qsTr
(
"
Mission Upload
"
),
_qgcView
.
showDialogDefaultWidth
,
StandardButton
.
Cancel
)
_qgcView
.
showDialog
(
activeMissionUploadDialogComponent
,
qsTr
(
"
Mission Upload
"
),
_qgcView
.
showDialogDefaultWidth
,
StandardButton
.
Cancel
)
return
true
return
true
}
else
{
}
else
{
...
@@ -171,7 +184,7 @@ QGCView {
...
@@ -171,7 +184,7 @@ QGCView {
// Users is switching away from Plan View
// Users is switching away from Plan View
function
uploadOnSwitch
()
{
function
uploadOnSwitch
()
{
if
(
missionController
.
dirty
&&
_autoSync
)
{
if
(
missionController
.
dirty
&&
_autoSync
)
{
if
(
_denyUpload
())
{
if
(
_denyUpload
(
true
/* switchToFly */
))
{
return
false
return
false
}
else
{
}
else
{
sendToVehicle
()
sendToVehicle
()
...
@@ -181,7 +194,7 @@ QGCView {
...
@@ -181,7 +194,7 @@ QGCView {
}
}
function
upload
()
{
function
upload
()
{
if
(
!
_denyUpload
())
{
if
(
!
_denyUpload
(
false
/* switchToFly */
))
{
sendToVehicle
()
sendToVehicle
()
}
}
}
}
...
@@ -384,6 +397,7 @@ QGCView {
...
@@ -384,6 +397,7 @@ QGCView {
mapName
:
"
MissionEditor
"
mapName
:
"
MissionEditor
"
allowGCSLocationCenter
:
true
allowGCSLocationCenter
:
true
allowVehicleLocationCenter
:
true
allowVehicleLocationCenter
:
true
planView
:
true
// This is the center rectangle of the map which is not obscured by tools
// This is the center rectangle of the map which is not obscured by tools
property
rect
centerViewport
:
Qt
.
rect
(
_leftToolWidth
,
_toolbarHeight
,
editorMap
.
width
-
_leftToolWidth
-
_rightPanelWidth
,
editorMap
.
height
-
_statusHeight
-
_toolbarHeight
)
property
rect
centerViewport
:
Qt
.
rect
(
_leftToolWidth
,
_toolbarHeight
,
editorMap
.
width
-
_leftToolWidth
-
_rightPanelWidth
,
editorMap
.
height
-
_statusHeight
-
_toolbarHeight
)
...
...
src/PlanView/SimpleItemMapVisual.qml
View file @
99b6c1c1
...
@@ -62,7 +62,7 @@ Item {
...
@@ -62,7 +62,7 @@ Item {
Component.onCompleted
:
{
Component.onCompleted
:
{
showItemVisuals
()
showItemVisuals
()
if
(
_missionItem
.
isCurrentItem
)
{
if
(
_missionItem
.
isCurrentItem
&&
map
.
planView
)
{
showDragArea
()
showDragArea
()
}
}
}
}
...
...
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