|
|
|
@ -144,33 +144,31 @@ Item {
@@ -144,33 +144,31 @@ Item {
|
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// The following code is used to track vehicle states such that we prompt to remove mission from vehicle when mission completes |
|
|
|
|
|
|
|
|
|
// The following code is used to track vehicle states for showing the mission complete dialog |
|
|
|
|
property bool vehicleArmed: activeVehicle ? activeVehicle.armed : true // true here prevents pop up from showing during shutdown |
|
|
|
|
property bool vehicleWasArmed: false |
|
|
|
|
property bool vehicleInMissionFlightMode: activeVehicle ? (activeVehicle.flightMode === activeVehicle.missionFlightMode) : false |
|
|
|
|
property bool promptForMissionRemove: false |
|
|
|
|
property bool vehicleWasInMissionFlightMode: false |
|
|
|
|
property bool showMissionCompleteDialog: vehicleWasArmed && vehicleWasInMissionFlightMode && |
|
|
|
|
(_missionController.containsItems || _geoFenceController.containsItems || _rallyPointController.containsItems || |
|
|
|
|
(activeVehicle ? activeVehicle.cameraTriggerPoints.count !== 0 : false)) |
|
|
|
|
|
|
|
|
|
onVehicleArmedChanged: { |
|
|
|
|
if (vehicleArmed) { |
|
|
|
|
if (!promptForMissionRemove) { |
|
|
|
|
promptForMissionRemove = vehicleInMissionFlightMode |
|
|
|
|
vehicleWasArmed = true |
|
|
|
|
} |
|
|
|
|
vehicleWasInMissionFlightMode = vehicleInMissionFlightMode |
|
|
|
|
} else { |
|
|
|
|
if (promptForMissionRemove && (_missionController.containsItems || _geoFenceController.containsItems || _rallyPointController.containsItems)) { |
|
|
|
|
// ArduPilot has a strange bug which prevents mission clear from working at certain times, so we can't show this dialog |
|
|
|
|
if (!activeVehicle.apmFirmware) { |
|
|
|
|
if (showMissionCompleteDialog) { |
|
|
|
|
mainWindow.showComponentDialog(missionCompleteDialogComponent, qsTr("Flight Plan complete"), mainWindow.showDialogDefaultWidth, StandardButton.Close) |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
promptForMissionRemove = false |
|
|
|
|
vehicleWasArmed = false |
|
|
|
|
vehicleWasInMissionFlightMode = false |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
onVehicleInMissionFlightModeChanged: { |
|
|
|
|
if (!promptForMissionRemove && vehicleArmed) { |
|
|
|
|
promptForMissionRemove = true |
|
|
|
|
if (vehicleInMissionFlightMode && vehicleArmed) { |
|
|
|
|
vehicleWasInMissionFlightMode = true |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -193,11 +191,7 @@ Item {
@@ -193,11 +191,7 @@ Item {
|
|
|
|
|
anchors.margins: _margins |
|
|
|
|
anchors.left: parent.left |
|
|
|
|
anchors.right: parent.right |
|
|
|
|
|
|
|
|
|
ColumnLayout { |
|
|
|
|
Layout.fillWidth: true |
|
|
|
|
spacing: ScreenTools.defaultFontPixelHeight |
|
|
|
|
visible: !activeVehicle.connectionLost || !_guidedController.showResumeMission |
|
|
|
|
|
|
|
|
|
QGCLabel { |
|
|
|
|
Layout.fillWidth: true |
|
|
|
@ -209,6 +203,7 @@ Item {
@@ -209,6 +203,7 @@ Item {
|
|
|
|
|
QGCButton { |
|
|
|
|
Layout.fillWidth: true |
|
|
|
|
text: qsTr("Remove plan from vehicle") |
|
|
|
|
visible: !activeVehicle.connectionLost// && !activeVehicle.apmFirmware // ArduPilot has a bug somewhere with mission clear |
|
|
|
|
onClicked: { |
|
|
|
|
_planController.removeAllFromVehicle() |
|
|
|
|
hideDialog() |
|
|
|
@ -228,11 +223,15 @@ Item {
@@ -228,11 +223,15 @@ Item {
|
|
|
|
|
height: 1 |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
ColumnLayout { |
|
|
|
|
Layout.fillWidth: true |
|
|
|
|
spacing: ScreenTools.defaultFontPixelHeight |
|
|
|
|
visible: !activeVehicle.connectionLost && _guidedController.showResumeMission |
|
|
|
|
|
|
|
|
|
QGCButton { |
|
|
|
|
Layout.fillWidth: true |
|
|
|
|
Layout.alignment: Qt.AlignHCenter |
|
|
|
|
text: qsTr("Resume Mission From Waypoint %1").arg(_guidedController._resumeMissionIndex) |
|
|
|
|
visible: _guidedController.showResumeMission |
|
|
|
|
|
|
|
|
|
onClicked: { |
|
|
|
|
guidedController.executeAction(_guidedController.actionResumeMission, null, null) |
|
|
|
@ -244,29 +243,15 @@ Item {
@@ -244,29 +243,15 @@ Item {
|
|
|
|
|
Layout.fillWidth: true |
|
|
|
|
wrapMode: Text.WordWrap |
|
|
|
|
text: qsTr("Resume Mission will rebuild the current mission from the last flown waypoint and upload it to the vehicle for the next flight.") |
|
|
|
|
visible: _guidedController.showResumeMission |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
QGCLabel { |
|
|
|
|
Layout.fillWidth: true |
|
|
|
|
wrapMode: Text.WordWrap |
|
|
|
|
color: qgcPal.warningText |
|
|
|
|
text: qsTr("If you are changing batteries for Resume Mission do not disconnect from the vehicle when communication is lost.") |
|
|
|
|
visible: _guidedController.showResumeMission |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
ColumnLayout { |
|
|
|
|
Layout.fillWidth: true |
|
|
|
|
spacing: ScreenTools.defaultFontPixelHeight |
|
|
|
|
visible: activeVehicle.connectionLost && _guidedController.showResumeMission |
|
|
|
|
|
|
|
|
|
QGCLabel { |
|
|
|
|
Layout.fillWidth: true |
|
|
|
|
wrapMode: Text.WordWrap |
|
|
|
|
color: qgcPal.warningText |
|
|
|
|
text: qsTr("If you are changing batteries for Resume Mission do not disconnect from the vehicle.") |
|
|
|
|
} |
|
|
|
|
visible: _guidedController.showResumeMission |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|