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