QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
GuidedActionsController.qml
Go to the documentation of this file.
1import QtQuick
2import QtQuick.Controls
3import QtQuick.Dialogs
4import QtLocation
5import QtPositioning
6import QtQuick.Layouts
7
8import QGroundControl
9import QGroundControl.Controls
10import QGroundControl.FlightMap
11
12/// This provides the smarts behind the guided mode commands, minus the user interface. This way you can change UI
13/// without affecting the underlying functionality.
14Item {
15 id: _root
16
17 property var missionController
18 property var confirmDialog
19 property var guidedValueSlider
20 property var fwdFlightGotoMapCircle
21 property var orbitMapCircle
22
23 readonly property string emergencyStopTitle: qsTr("EMERGENCY STOP")
24 readonly property string armTitle: qsTr("Arm")
25 readonly property string mvArmTitle: qsTr("Arm (MV)")
26 readonly property string forceArmTitle: qsTr("Force Arm")
27 readonly property string disarmTitle: qsTr("Disarm")
28 readonly property string mvDisarmTitle: qsTr("Disarm (MV)")
29 readonly property string rtlTitle: qsTr("Return")
30 readonly property string takeoffTitle: qsTr("Takeoff")
31 readonly property string landTitle: qsTr("Land")
32 readonly property string startMissionTitle: qsTr("Start Mission")
33 readonly property string mvStartMissionTitle: qsTr("Start Mission (MV)")
34 readonly property string continueMissionTitle: qsTr("Continue Mission")
35 readonly property string resumeMissionUploadFailTitle: qsTr("Resume FAILED")
36 readonly property string pauseTitle: qsTr("Pause")
37 readonly property string mvPauseTitle: qsTr("Pause (MV)")
38 readonly property string changeAltTitle: qsTr("Change Altitude")
39 readonly property string changeLoiterRadiusTitle: qsTr("Change Loiter Radius")
40 readonly property string changeCruiseSpeedTitle: qsTr("Change Max Ground Speed")
41 readonly property string changeAirspeedTitle: qsTr("Change Airspeed")
42 readonly property string orbitTitle: qsTr("Orbit")
43 readonly property string landAbortTitle: qsTr("Land Abort")
44 readonly property string setWaypointTitle: qsTr("Set Waypoint")
45 readonly property string gotoTitle: qsTr("Go To Location")
46 readonly property string roiTitle: qsTr("ROI")
47 readonly property string setHomeTitle: qsTr("Set Home")
48 readonly property string setEstimatorOriginTitle: qsTr("Set Estimator Origin")
49 readonly property string setFlightMode: qsTr("Set Flight Mode")
50 readonly property string changeHeadingTitle: qsTr("Change Heading")
51
52 readonly property string armMessage: qsTr("Arm the vehicle.")
53 readonly property string mvArmMessage: qsTr("Arm selected vehicles.")
54 readonly property string forceArmMessage: qsTr("WARNING: This will force arming of the vehicle bypassing any safety checks.")
55 readonly property string disarmMessage: qsTr("Disarm the vehicle")
56 readonly property string mvDisarmMessage: qsTr("Disarm selected vehicles.")
57 readonly property string emergencyStopMessage: qsTr("WARNING: THIS WILL STOP ALL MOTORS. IF VEHICLE IS CURRENTLY IN THE AIR IT WILL CRASH.")
58 readonly property string takeoffMessage: qsTr("Takeoff and hold position")
59 readonly property string startMissionMessage: qsTr("Takeoff and start the current mission")
60 readonly property string mvStartMissionMessage: qsTr("Takeoff and start the current mission for selected vehicles")
61 readonly property string continueMissionMessage: qsTr("Continue the mission from the current waypoint")
62 readonly property string resumeMissionUploadFailMessage: qsTr("Upload of resume mission failed. Confirm to retry upload")
63 readonly property string landMessage: qsTr("Land the vehicle at the current position")
64 readonly property string rtlMessage: qsTr("Return to the launch position of the vehicle")
65 readonly property string changeAltMessage: qsTr("Change the altitude of the vehicle up or down")
66 readonly property string changeLoiterRadiusMessage: qsTr("Change the forward flight loiter radius")
67 readonly property string changeCruiseSpeedMessage: qsTr("Change the maximum horizontal cruise speed")
68 readonly property string changeAirspeedMessage: qsTr("Change the equivalent airspeed setpoint")
69 readonly property string gotoMessage: qsTr("Move the vehicle to the specified location")
70 property string setWaypointMessage: qsTr("Adjust current waypoint to %1").arg(_actionData)
71 readonly property string orbitMessage: qsTr("Orbit the vehicle around the specified location")
72 readonly property string landAbortMessage: qsTr("Abort the landing sequence")
73 readonly property string pauseMessage: qsTr("Pause at current position")
74 readonly property string mvPauseMessage: qsTr("Pause selected vehicles at their current position")
75 readonly property string roiMessage: qsTr("Make the specified location a Region Of Interest")
76 readonly property string setHomeMessage: qsTr("Set vehicle home as the specified location. This will affect Return to Home position")
77 readonly property string setEstimatorOriginMessage: qsTr("Make the specified location the estimator origin")
78 readonly property string setFlightModeMessage: qsTr("Set the vehicle flight mode to %1").arg(_actionData)
79 readonly property string changeHeadingMessage: qsTr("Set the vehicle heading towards the specified location")
80
81 readonly property int actionRTL: 1
82 readonly property int actionLand: 2
83 readonly property int actionTakeoff: 3
84 readonly property int actionArm: 4
85 readonly property int actionDisarm: 5
86 readonly property int actionEmergencyStop: 6
87 readonly property int actionChangeAlt: 7
88 readonly property int actionGoto: 8
89 readonly property int actionSetWaypoint: 9
90 readonly property int actionOrbit: 10
91 readonly property int actionLandAbort: 11
92 readonly property int actionStartMission: 12
93 readonly property int actionContinueMission: 13
94 readonly property int actionResumeMission: 14
95 readonly property int _actionUnused: 15
96 readonly property int actionResumeMissionUploadFail: 16
97 readonly property int actionPause: 17
98 readonly property int actionMVPause: 18
99 readonly property int actionMVStartMission: 19
100 readonly property int actionROI: 20
101 readonly property int actionForceArm: 21
102 readonly property int actionChangeSpeed: 22
103 readonly property int actionSetHome: 24
104 readonly property int actionSetEstimatorOrigin: 25
105 readonly property int actionSetFlightMode: 26
106 readonly property int actionChangeHeading: 27
107 readonly property int actionMVArm: 28
108 readonly property int actionMVDisarm: 29
109 readonly property int actionChangeLoiterRadius: 30
110
111 readonly property int customActionStart: 10000 // Custom actions ids should start here so that they don't collide with the built in actions
112
113 property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
114 property var _flyViewSettings: QGroundControl.settingsManager.flyViewSettings
115 property var _unitsConversion: QGroundControl.unitsConversion
116 property bool _useChecklist: QGroundControl.settingsManager.appSettings.useChecklist.rawValue && QGroundControl.corePlugin.options.preFlightChecklistUrl.toString().length
117 property bool _enforceChecklist: _useChecklist && QGroundControl.settingsManager.appSettings.enforceChecklist.rawValue
118 property bool _checklistPassed: _activeVehicle ? (_useChecklist ? (_enforceChecklist ? _activeVehicle.checkListState === Vehicle.CheckListPassed : true) : true) : true
119 property bool _canArm: _activeVehicle ? (_checklistPassed && (!_activeVehicle.healthAndArmingCheckReport.supported || _activeVehicle.healthAndArmingCheckReport.canArm)) : false
120 property bool _canTakeoff: _activeVehicle ? (_checklistPassed && (!_activeVehicle.healthAndArmingCheckReport.supported || _activeVehicle.healthAndArmingCheckReport.canTakeoff)) : false
121 property bool _canStartMission: _activeVehicle ? (_checklistPassed && (!_activeVehicle.healthAndArmingCheckReport.supported || _activeVehicle.healthAndArmingCheckReport.canStartMission)) : false
122 property bool _initialConnectComplete: _activeVehicle ? _activeVehicle.initialConnectComplete : false
123
124 property bool showEmergenyStop: _guidedActionsEnabled && !_hideEmergenyStop && _vehicleArmed && _vehicleFlying
125 property bool showArm: _guidedActionsEnabled && !_vehicleArmed && _canArm
126 property bool showForceArm: _guidedActionsEnabled && !_vehicleArmed
127 property bool showDisarm: _guidedActionsEnabled && _vehicleArmed && !_vehicleFlying
128 property bool showRTL: _guidedActionsEnabled && _vehicleArmed && _activeVehicle.supports.guidedMode && _vehicleFlying && !_vehicleInRTLMode
129 property bool showTakeoff: _guidedActionsEnabled && (_activeVehicle.supports.guidedTakeoffWithAltitude || _activeVehicle.supports.guidedTakeoffWithoutAltitude) && !_vehicleFlying && _canTakeoff
130 property bool showLand: _guidedActionsEnabled && _activeVehicle.supports.guidedMode && _vehicleArmed && !_activeVehicle.fixedWing && !_vehicleInLandMode
131 property bool showStartMission: _guidedActionsEnabled && _missionAvailable && !_missionActive && !_vehicleFlying && _canStartMission
132 property bool showContinueMission: _guidedActionsEnabled && _missionAvailable && !_missionActive && _vehicleArmed && _vehicleFlying && (_currentMissionIndex < _missionItemCount - 1)
133 property bool showPause: _guidedActionsEnabled && _vehicleArmed && _activeVehicle.supports.pauseVehicle && _vehicleFlying && !_vehiclePaused && !_fixedWingOnApproach
134 property bool showChangeAlt: _guidedActionsEnabled && _vehicleFlying && _activeVehicle.supports.guidedMode && _vehicleArmed && !_missionActive
135 property bool showChangeLoiterRadius: _guidedActionsEnabled && _vehicleFlying && _activeVehicle.supports.guidedMode && _vehicleArmed && !_missionActive && _vehicleInFwdFlight && fwdFlightGotoMapCircle.visible
136 property bool showChangeSpeed: _guidedActionsEnabled && _vehicleFlying && _activeVehicle.supports.guidedMode && _vehicleArmed && !_missionActive && _speedLimitsAvailable
137 property bool showOrbit: _guidedActionsEnabled && _vehicleFlying && __orbitSupported && !_missionActive && _activeVehicle.homePosition.isValid && !isNaN(_activeVehicle.homePosition.altitude)
138 property bool showROI: _guidedActionsEnabled && _vehicleFlying && __roiSupported
139 property bool showLandAbort: _guidedActionsEnabled && _vehicleFlying && _fixedWingOnApproach
140 property bool showGotoLocation: _guidedActionsEnabled && _vehicleFlying
141 property bool showSetHome: _guidedActionsEnabled
142 property bool showSetEstimatorOrigin: _activeVehicle && !(_activeVehicle.sensorsPresentBits & Vehicle.SysStatusSensorGPS)
143 property bool showChangeHeading: _guidedActionsEnabled && _vehicleFlying
144
145 property string changeSpeedTitle: _vehicleInFwdFlight ? changeAirspeedTitle : changeCruiseSpeedTitle
146 property string changeSpeedMessage: _vehicleInFwdFlight ? changeAirspeedMessage : changeCruiseSpeedMessage
147
148 // Note: The '_missionItemCount - 2' is a hack to not trigger resume mission when a mission ends with an RTL item
149 property bool showResumeMission: _activeVehicle && !_vehicleArmed && _vehicleWasFlying && _missionAvailable && _resumeMissionIndex > 0 && (_resumeMissionIndex < _missionItemCount - 2)
150
151 property bool guidedUIVisible: confirmDialog.visible
152
153 property var _corePlugin: QGroundControl.corePlugin
154 property var _corePluginOptions: QGroundControl.corePlugin.options
155 property bool _guidedActionsEnabled: (!ScreenTools.isDebug && _corePluginOptions.guidedActionsRequireRCRSSI && _activeVehicle) ? _rcRSSIAvailable : _activeVehicle
156 property string _flightMode: _activeVehicle ? _activeVehicle.flightMode : ""
157 property bool _missionAvailable: missionController.containsItems
158 property bool _missionActive: _activeVehicle ? _vehicleArmed && (_vehicleInLandMode || _vehicleInRTLMode || _vehicleInMissionMode) : false
159 property bool _vehicleArmed: _activeVehicle ? _activeVehicle.armed : false
160 property bool _vehicleFlying: _activeVehicle ? _activeVehicle.flying : false
161 property bool _vehicleLanding: _activeVehicle ? _activeVehicle.landing : false
162 property bool _vehiclePaused: false
163 property bool _vehicleInMissionMode: false
164 property bool _vehicleInRTLMode: false
165 property bool _vehicleInLandMode: false
166 property int _missionItemCount: missionController.missionItemCount
167 property int _currentMissionIndex: missionController.currentMissionIndex
168 property int _resumeMissionIndex: missionController.resumeMissionIndex
169 property bool _hideEmergenyStop: !_corePluginOptions.flyView.guidedBarShowEmergencyStop
170 property bool _hideOrbit: !_corePluginOptions.flyView.guidedBarShowOrbit
171 property bool _hideROI: !_corePluginOptions.flyView.guidedBarShowROI
172 property bool _vehicleWasFlying: false
173 property bool _rcRSSIAvailable: _activeVehicle ? _activeVehicle.rcRSSI > 0 && _activeVehicle.rcRSSI <= 100 : false
174 property bool _fixedWingOnApproach: _activeVehicle ? _activeVehicle.fixedWing && _vehicleLanding : false
175 property bool _vehicleInFwdFlight: _activeVehicle ? _activeVehicle.inFwdFlight : false
176 property bool _speedLimitsAvailable: _activeVehicle && ((_vehicleInFwdFlight && _activeVehicle.haveFWSpeedLimits) || (!_vehicleInFwdFlight && _activeVehicle.haveMRSpeedLimits))
177
178 // You can turn on log output for GuidedActionsController by turning on GuidedActionsControllerLog category
179 property bool __guidedModeSupported: _activeVehicle ? _activeVehicle.supports.guidedMode : false
180 property bool __pauseVehicleSupported: _activeVehicle ? _activeVehicle.supports.pauseVehicle : false
181 property bool __roiSupported: _activeVehicle ? !_hideROI && _activeVehicle.supports.roiMode : false
182 property bool __orbitSupported: _activeVehicle ? !_hideOrbit && _activeVehicle.supports.orbitMode : false
183 property bool __flightMode: _flightMode
184
185 // Allow custom builds to add custom actions by overriding CustomGuidedActionsController.qml
186 CustomGuidedActionsController {
187 id: customController
188 }
189 property var _customController: customController
190
191 function _isGuidedActionsControllerLogEnabled() {
192 return QGroundControl.categoryLoggingOn("GuidedActionsControllerLog")
193 }
194
195 function _outputState() {
196 if (_isGuidedActionsControllerLogEnabled()) {
197 console.log(qsTr("_activeVehicle(%1) _vehicleArmed(%2) guidedModeSupported(%3) _vehicleFlying(%4) _vehicleWasFlying(%5) _vehicleInRTLMode(%6) pauseVehicleSupported(%7) _vehiclePaused(%8) _flightMode(%9) _missionItemCount(%10) roiSupported(%11) orbitSupported(%12) _missionActive(%13) _hideROI(%14) _hideOrbit(%15)").arg(_activeVehicle ? 1 : 0).arg(_vehicleArmed ? 1 : 0).arg(__guidedModeSupported ? 1 : 0).arg(_vehicleFlying ? 1 : 0).arg(_vehicleWasFlying ? 1 : 0).arg(_vehicleInRTLMode ? 1 : 0).arg(__pauseVehicleSupported ? 1 : 0).arg(_vehiclePaused ? 1 : 0).arg(_flightMode).arg(_missionItemCount).arg(__roiSupported).arg(__orbitSupported).arg(_missionActive).arg(_hideROI).arg(_hideOrbit))
198 }
199 }
200
201 function setupSlider(actionCode) {
202 if (actionCode === actionTakeoff) {
203 guidedValueSlider.setupSlider(
204 GuidedValueSlider.SliderType.Takeoff,
205 _unitsConversion.metersToAppSettingsVerticalDistanceUnits(_activeVehicle.minimumTakeoffAltitudeMeters()),
206 _flyViewSettings.guidedMaximumAltitude.value,
207 _unitsConversion.metersToAppSettingsVerticalDistanceUnits(_activeVehicle.minimumTakeoffAltitudeMeters()),
208 qsTr("Height (rel)"))
209 } else if (actionCode === actionChangeSpeed) {
210 if (_vehicleInFwdFlight) {
211 guidedValueSlider.setupSlider(
212 GuidedValueSlider.SliderType.Speed,
213 _unitsConversion.metersSecondToAppSettingsSpeedUnits(_activeVehicle.minimumEquivalentAirspeed()).toFixed(1),
214 _unitsConversion.metersSecondToAppSettingsSpeedUnits(_activeVehicle.maximumEquivalentAirspeed()).toFixed(1),
215 _unitsConversion.metersSecondToAppSettingsSpeedUnits(_activeVehicle.airSpeed.rawValue),
216 qsTr("Airspeed"))
217 } else if (!_vehicleInFwdFlight && _activeVehicle.haveMRSpeedLimits) {
218 guidedValueSlider.setupSlider(
219 GuidedValueSlider.SliderType.Speed,
220 _unitsConversion.metersSecondToAppSettingsSpeedUnits(0.1).toFixed(1),
221 _unitsConversion.metersSecondToAppSettingsSpeedUnits(_activeVehicle.maximumHorizontalSpeedMultirotor()).toFixed(1),
222 _unitsConversion.metersSecondToAppSettingsSpeedUnits(_activeVehicle.maximumHorizontalSpeedMultirotor()/2).toFixed(1),
223 qsTr("Speed"))
224 } else {
225 console.error("setupSlider called for inapproproate change speed action", _vehicleInFwdFlight, _activeVehicle.haveMRSpeedLimits)
226 }
227 } else if (actionCode === actionChangeAlt || actionCode === actionOrbit || actionCode === actionGoto || actionCode === actionPause) {
228 guidedValueSlider.setupSlider(
229 GuidedValueSlider.SliderType.Altitude,
230 _flyViewSettings.guidedMinimumAltitude.value,
231 _flyViewSettings.guidedMaximumAltitude.value,
232 _activeVehicle.altitudeRelative.value,
233 qsTr("Alt (rel)"))
234 }
235 }
236
237 on_ActiveVehicleChanged: _outputState()
238
239 Component.onCompleted: _outputState()
240 on_VehicleArmedChanged: _outputState()
241 on_VehicleInRTLModeChanged: _outputState()
242 on_VehiclePausedChanged: _outputState()
243 on__FlightModeChanged: _outputState()
244 on__GuidedModeSupportedChanged: _outputState()
245 on__PauseVehicleSupportedChanged: _outputState()
246 on__RoiSupportedChanged: _outputState()
247 on__OrbitSupportedChanged: _outputState()
248 on_MissionItemCountChanged: _outputState()
249 on_MissionActiveChanged: _outputState()
250
251 on_CurrentMissionIndexChanged: {
252 if (_isGuidedActionsControllerLogEnabled()) {
253 console.log("_currentMissionIndex", _currentMissionIndex)
254 }
255 }
256 on_ResumeMissionIndexChanged: {
257 if (_isGuidedActionsControllerLogEnabled()) {
258 console.log("_resumeMissionIndex", _resumeMissionIndex)
259 }
260 }
261 onShowResumeMissionChanged: {
262 if (_isGuidedActionsControllerLogEnabled()) {
263 console.log("showResumeMission", showResumeMission)
264 }
265 _outputState()
266 }
267 onShowStartMissionChanged: {
268 if (_isGuidedActionsControllerLogEnabled()) {
269 console.log("showStartMission", showStartMission)
270 }
271 _outputState()
272 if (showStartMission &&
273 _flyViewSettings.enableAutomaticMissionPopups.rawValue) {
274 confirmAction(actionStartMission)
275 }
276 }
277 onShowContinueMissionChanged: {
278 if (_isGuidedActionsControllerLogEnabled()) {
279 console.log("showContinueMission", showContinueMission)
280 }
281 _outputState()
282 if (showContinueMission &&
283 _flyViewSettings.enableAutomaticMissionPopups.rawValue) {
284 confirmAction(actionContinueMission)
285 }
286 }
287 onShowRTLChanged: {
288 if (_isGuidedActionsControllerLogEnabled()) {
289 console.log("showRTL", showRTL)
290 }
291 _outputState()
292 }
293 onShowChangeAltChanged: {
294 if (_isGuidedActionsControllerLogEnabled()) {
295 console.log("showChangeAlt", showChangeAlt)
296 }
297 _outputState()
298 }
299 onShowROIChanged: {
300 if (_isGuidedActionsControllerLogEnabled()) {
301 console.log("showROI", showROI)
302 }
303 _outputState()
304 }
305 onShowOrbitChanged: {
306 if (_isGuidedActionsControllerLogEnabled()) {
307 console.log("showOrbit", showOrbit)
308 }
309 _outputState()
310 }
311 onShowGotoLocationChanged: {
312 if (_isGuidedActionsControllerLogEnabled()) {
313 console.log("showGotoLocation", showGotoLocation)
314 }
315 _outputState()
316 }
317 onShowLandAbortChanged: {
318 if (showLandAbort) {
319 confirmAction(actionLandAbort)
320 }
321 }
322
323 on_VehicleFlyingChanged: {
324 _outputState()
325 if (!_vehicleFlying) {
326 // We use _vehicleWasFLying to help trigger Resume Mission only if the vehicle actually flew and came back down.
327 // Otherwise it may trigger during the Start Mission sequence due to signal ordering or armed and resume mission index.
328 _vehicleWasFlying = true
329 }
330 }
331
332 property var _actionData
333
334 on_FlightModeChanged: {
335 _vehiclePaused = _activeVehicle ? _flightMode === _activeVehicle.pauseFlightMode : false
336 _vehicleInRTLMode = _activeVehicle ? _flightMode === _activeVehicle.rtlFlightMode || _flightMode === _activeVehicle.smartRTLFlightMode : false
337 _vehicleInLandMode = _activeVehicle ? _flightMode === _activeVehicle.landFlightMode : false
338 _vehicleInMissionMode = _activeVehicle ? _flightMode === _activeVehicle.missionFlightMode : false // Must be last to get correct signalling for showStartMission popups
339 }
340
341 Connections {
342 target: missionController
343 function onResumeMissionUploadFail() { confirmAction(actionResumeMissionUploadFail) }
344 }
345
346 Connections {
347 target: mainWindow
348 function onArmVehicleRequest() { armVehicleRequest() }
349 function onForceArmVehicleRequest() { forceArmVehicleRequest() }
350 function onDisarmVehicleRequest() { disarmVehicleRequest() }
351 }
352
353 function armVehicleRequest() {
354 confirmAction(actionArm)
355 }
356
357 function forceArmVehicleRequest() {
358 confirmAction(actionForceArm)
359 }
360
361 function disarmVehicleRequest() {
362 if (showEmergenyStop) {
363 confirmAction(actionEmergencyStop)
364 } else {
365 confirmAction(actionDisarm)
366 }
367
368 }
369
370 function closeAll() {
371 confirmDialog.visible = false
372 guidedValueSlider.visible = false
373 }
374
375 // Called when an action is about to be executed in order to confirm
376 function confirmAction(actionCode, actionData, mapIndicator) {
377 var showImmediate = true
378 closeAll()
379 confirmDialog.action = actionCode
380 confirmDialog.actionData = actionData
381 confirmDialog.hideTrigger = true
382 confirmDialog.mapIndicator = mapIndicator
383 confirmDialog.optionText = ""
384 _actionData = actionData
385
386 setupSlider(actionCode)
387
388 switch (actionCode) {
389 case actionArm:
390 if (_vehicleFlying || !_guidedActionsEnabled) {
391 return
392 }
393 confirmDialog.title = armTitle
394 confirmDialog.message = armMessage
395 confirmDialog.hideTrigger = Qt.binding(function() { return !showArm })
396 break;
397 case actionMVArm:
398 confirmDialog.title = mvArmTitle
399 confirmDialog.message = mvArmMessage
400 confirmDialog.hideTrigger = true
401 break;
402 case actionForceArm:
403 confirmDialog.title = forceArmTitle
404 confirmDialog.message = forceArmMessage
405 confirmDialog.hideTrigger = Qt.binding(function() { return !showForceArm })
406 break;
407 case actionDisarm:
408 if (_vehicleFlying) {
409 return
410 }
411 confirmDialog.title = disarmTitle
412 confirmDialog.message = disarmMessage
413 confirmDialog.hideTrigger = Qt.binding(function() { return !showDisarm })
414 break;
415 case actionMVDisarm:
416 confirmDialog.title = mvDisarmTitle
417 confirmDialog.message = mvDisarmMessage
418 confirmDialog.hideTrigger = true
419 break;
420 case actionEmergencyStop:
421 confirmDialog.title = emergencyStopTitle
422 confirmDialog.message = emergencyStopMessage
423 confirmDialog.hideTrigger = Qt.binding(function() { return !showEmergenyStop })
424 break;
425 case actionTakeoff:
426 confirmDialog.title = takeoffTitle
427 confirmDialog.message = takeoffMessage
428 confirmDialog.hideTrigger = Qt.binding(function() { return !showTakeoff })
429 guidedValueSlider.visible = _activeVehicle.supports.guidedTakeoffWithAltitude
430 break;
431 case actionStartMission:
432 showImmediate = false
433 confirmDialog.title = startMissionTitle
434 confirmDialog.message = startMissionMessage
435 confirmDialog.hideTrigger = Qt.binding(function() { return !showStartMission })
436 break;
437 case actionMVStartMission:
438 confirmDialog.title = mvStartMissionTitle
439 confirmDialog.message = mvStartMissionMessage
440 confirmDialog.hideTrigger = true
441 break;
442 case actionContinueMission:
443 showImmediate = false
444 confirmDialog.title = continueMissionTitle
445 confirmDialog.message = continueMissionMessage
446 confirmDialog.hideTrigger = Qt.binding(function() { return !showContinueMission })
447 break;
448 case actionResumeMission:
449 // Resume Mission is handled in mission end dialog
450 return
451 case actionResumeMissionUploadFail:
452 confirmDialog.title = resumeMissionUploadFailTitle
453 confirmDialog.message = resumeMissionUploadFailMessage
454 confirmDialog.hideTrigger = Qt.binding(function() { return !showResumeMission })
455 break;
456 case actionLand:
457 confirmDialog.title = landTitle
458 confirmDialog.message = landMessage
459 confirmDialog.hideTrigger = Qt.binding(function() { return !showLand })
460 break;
461 case actionRTL:
462 confirmDialog.title = rtlTitle
463 confirmDialog.message = rtlMessage
464 if (_activeVehicle.supports.smartRTL) {
465 confirmDialog.optionText = qsTr("Smart RTL")
466 confirmDialog.optionChecked = false
467 }
468 confirmDialog.hideTrigger = Qt.binding(function() { return !showRTL })
469 break;
470 case actionChangeAlt:
471 confirmDialog.title = changeAltTitle
472 confirmDialog.message = changeAltMessage
473 confirmDialog.hideTrigger = Qt.binding(function() { return !showChangeAlt })
474 guidedValueSlider.visible = true
475 break;
476 case actionChangeLoiterRadius:
477 confirmDialog.title = changeLoiterRadiusTitle
478 confirmDialog.message = changeLoiterRadiusMessage
479 confirmDialog.hideTrigger = Qt.binding(function() { return !showChangeLoiterRadius })
480 confirmDialog.mapIndicator = fwdFlightGotoMapCircle
481 fwdFlightGotoMapCircle.startLoiterRadiusEdit()
482 break
483 case actionGoto:
484 confirmDialog.title = gotoTitle
485 confirmDialog.message = gotoMessage
486 confirmDialog.hideTrigger = Qt.binding(function() { return !showGotoLocation })
487 break;
488 case actionSetWaypoint:
489 confirmDialog.title = setWaypointTitle
490 confirmDialog.message = setWaypointMessage
491 break;
492 case actionOrbit:
493 confirmDialog.title = orbitTitle
494 confirmDialog.message = orbitMessage
495 confirmDialog.hideTrigger = Qt.binding(function() { return !showOrbit })
496 guidedValueSlider.visible = true
497 break;
498 case actionLandAbort:
499 confirmDialog.title = landAbortTitle
500 confirmDialog.message = landAbortMessage
501 confirmDialog.hideTrigger = Qt.binding(function() { return !showLandAbort })
502 break;
503 case actionPause:
504 confirmDialog.title = pauseTitle
505 confirmDialog.message = pauseMessage
506 confirmDialog.hideTrigger = Qt.binding(function() { return !showPause })
507 guidedValueSlider.visible = true
508 break;
509 case actionMVPause:
510 confirmDialog.title = mvPauseTitle
511 confirmDialog.message = mvPauseMessage
512 confirmDialog.hideTrigger = true
513 break;
514 case actionROI:
515 confirmDialog.title = roiTitle
516 confirmDialog.message = roiMessage
517 confirmDialog.hideTrigger = Qt.binding(function() { return !showROI })
518 break;
519 case actionChangeSpeed:
520 confirmDialog.hideTrigger = true
521 confirmDialog.title = changeSpeedTitle
522 confirmDialog.message = changeSpeedMessage
523 guidedValueSlider.visible = true
524 break
525 case actionSetHome:
526 confirmDialog.title = setHomeTitle
527 confirmDialog.message = setHomeMessage
528 confirmDialog.hideTrigger = Qt.binding(function() { return !showSetHome })
529 break
530 case actionSetEstimatorOrigin:
531 confirmDialog.title = setEstimatorOriginTitle
532 confirmDialog.message = setEstimatorOriginMessage
533 break
534 case actionSetFlightMode:
535 confirmDialog.title = setFlightMode
536 confirmDialog.message = setFlightModeMessage
537 break
538 case actionChangeHeading:
539 confirmDialog.title = changeHeadingTitle
540 confirmDialog.message = changeHeadingMessage
541 break
542 default:
543 if (!customController.customConfirmAction(actionCode, actionData, mapIndicator, confirmDialog)) {
544 console.warn("Unknown actionCode", actionCode)
545 return
546 }
547 }
548 confirmDialog.show(showImmediate)
549 }
550
551 // Executes the specified action
552 function executeAction(actionCode, actionData, sliderOutputValue, optionChecked) {
553 var i;
554 var selectedVehicles;
555 switch (actionCode) {
556 case actionRTL:
557 _activeVehicle.guidedModeRTL(optionChecked)
558 break
559 case actionLand:
560 _activeVehicle.guidedModeLand()
561 break
562 case actionTakeoff:
563 if (_activeVehicle.supports.guidedTakeoffWithAltitude) {
564 var valueInMeters = _unitsConversion.appSettingsVerticalDistanceUnitsToMeters(sliderOutputValue)
565 _activeVehicle.guidedModeTakeoff(valueInMeters)
566 } else {
567 _activeVehicle.startTakeoff()
568 }
569 break
570 case actionResumeMission:
571 case actionResumeMissionUploadFail:
572 missionController.resumeMission(missionController.resumeMissionIndex)
573 break
574 case actionStartMission:
575 case actionContinueMission:
576 _activeVehicle.startMission()
577 break
578 case actionMVStartMission:
579 selectedVehicles = QGroundControl.multiVehicleManager.selectedVehicles
580 for (i = 0; i < selectedVehicles.count; i++) {
581 var vehicle = selectedVehicles.get(i)
582 if (vehicle.armed === true){
583 vehicle.startMission()
584 }
585 }
586 break
587 case actionArm:
588 _activeVehicle.armed = true
589 break
590 case actionMVArm:
591 selectedVehicles = QGroundControl.multiVehicleManager.selectedVehicles
592 for (i = 0; i < selectedVehicles.count; i++) {
593 selectedVehicles.get(i).armed = true
594 }
595 break
596 case actionForceArm:
597 _activeVehicle.forceArm()
598 break
599 case actionDisarm:
600 _activeVehicle.armed = false
601 break
602 case actionMVDisarm:
603 selectedVehicles = QGroundControl.multiVehicleManager.selectedVehicles
604 for (i = 0; i < selectedVehicles.count; i++) {
605 selectedVehicles.get(i).armed = false
606 }
607 break
608 case actionEmergencyStop:
609 _activeVehicle.emergencyStop()
610 break
611 case actionChangeAlt:
612 var valueInMeters = _unitsConversion.appSettingsVerticalDistanceUnitsToMeters(sliderOutputValue)
613 var altitudeChangeInMeters = valueInMeters - _activeVehicle.altitudeRelative.rawValue
614 _activeVehicle.guidedModeChangeAltitude(altitudeChangeInMeters, false /* pauseVehicle */)
615 break
616 case actionChangeLoiterRadius:
617 _activeVehicle.guidedModeGotoLocation(
618 fwdFlightGotoMapCircle.coordinate,
619 (fwdFlightGotoMapCircle.clockwiseRotation ? 1 : -1) *
620 Math.abs(fwdFlightGotoMapCircle.radius.rawValue)
621 )
622 break
623 case actionGoto:
624 _activeVehicle.guidedModeGotoLocation(
625 actionData,
626 _vehicleInFwdFlight /* forwardFlightLoiterRadius */
627 ? _flyViewSettings.forwardFlightGoToLocationLoiterRad.value
628 : 0
629 )
630 break
631 case actionSetWaypoint:
632 _activeVehicle.setCurrentMissionSequence(actionData)
633 break
634 case actionOrbit:
635 var valueInMeters = _unitsConversion.appSettingsVerticalDistanceUnitsToMeters(sliderOutputValue)
636 _activeVehicle.guidedModeOrbit(orbitMapCircle.center, orbitMapCircle.radius() * (orbitMapCircle.clockwiseRotation ? 1 : -1), _activeVehicle.homePosition.altitude + valueInMeters)
637 break
638 case actionLandAbort:
639 _activeVehicle.abortLanding(50) // hardcoded value for climbOutAltitude that is currently ignored
640 break
641 case actionPause:
642 var valueInMeters = _unitsConversion.appSettingsVerticalDistanceUnitsToMeters(sliderOutputValue)
643 var altitudeChangeInMeters = valueInMeters - _activeVehicle.altitudeRelative.rawValue
644 _activeVehicle.guidedModeChangeAltitude(altitudeChangeInMeters, true /* pauseVehicle */)
645 break
646 case actionMVPause:
647 selectedVehicles = QGroundControl.multiVehicleManager.selectedVehicles
648 for (i = 0; i < selectedVehicles.count; i++) {
649 selectedVehicles.get(i).pauseVehicle()
650 }
651 break
652 case actionROI:
653 _activeVehicle.guidedModeROI(actionData)
654 break
655 case actionChangeSpeed:
656 if (_activeVehicle) {
657 // We need to convert back to m/s as that is what mavlink standard uses for MAV_CMD_DO_CHANGE_SPEED
658 var metersSecondSpeed = _unitsConversion.appSettingsSpeedUnitsToMetersSecond(sliderOutputValue)
659 if (_vehicleInFwdFlight) {
660 _activeVehicle.guidedModeChangeEquivalentAirspeedMetersSecond(metersSecondSpeed)
661 } else {
662 _activeVehicle.guidedModeChangeGroundSpeedMetersSecond(metersSecondSpeed)
663 }
664 }
665 break
666 case actionSetHome:
667 _activeVehicle.doSetHome(actionData)
668 break
669 case actionSetEstimatorOrigin:
670 _activeVehicle.setEstimatorOrigin(actionData)
671 break
672 case actionSetFlightMode:
673 _activeVehicle.flightMode = actionData
674 break
675 case actionChangeHeading:
676 _activeVehicle.guidedModeChangeHeading(actionData)
677 break
678 default:
679 if (!customController.customExecuteAction(actionCode, actionData, sliderOutputValue, optionChecked)) {
680 console.warn(qsTr("Internal error: unknown actionCode"), actionCode)
681 return
682 }
683 break
684 }
685 }
686}