GuidedActionsController.qml 21.3 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

import QtQuick                  2.3
import QtQuick.Controls         1.2
import QtQuick.Controls.Styles  1.4
import QtQuick.Dialogs          1.2
import QtLocation               5.3
import QtPositioning            5.3
import QtQuick.Layouts          1.2

import QGroundControl                           1.0
import QGroundControl.ScreenTools               1.0
import QGroundControl.Controls                  1.0
import QGroundControl.Palette                   1.0
import QGroundControl.Vehicle                   1.0
import QGroundControl.FlightMap                 1.0

/// This provides the smarts behind the guided mode commands, minus the user interface. This way you can change UI
/// without affecting the underlying functionality.
Item {
    id: _root

    property var missionController
31
    property var confirmDialog
DonLakeFlyer's avatar
DonLakeFlyer committed
32
    property var actionList
Don Gagne's avatar
Don Gagne committed
33
    property var altitudeSlider
34

35
    readonly property string emergencyStopTitle:            qsTr("EMERGENCY STOP")
36 37 38 39 40 41 42 43 44 45 46 47 48 49 50
    readonly property string armTitle:                      qsTr("Arm")
    readonly property string disarmTitle:                   qsTr("Disarm")
    readonly property string rtlTitle:                      qsTr("RTL")
    readonly property string takeoffTitle:                  qsTr("Takeoff")
    readonly property string landTitle:                     qsTr("Land")
    readonly property string startMissionTitle:             qsTr("Start Mission")
    readonly property string continueMissionTitle:          qsTr("Continue Mission")
    readonly property string resumeMissionTitle:            qsTr("Resume Mission")
    readonly property string resumeMissionUploadFailTitle:  qsTr("Resume FAILED")
    readonly property string pauseTitle:                    qsTr("Pause")
    readonly property string changeAltTitle:                qsTr("Change Altitude")
    readonly property string orbitTitle:                    qsTr("Orbit")
    readonly property string landAbortTitle:                qsTr("Land Abort")
    readonly property string setWaypointTitle:              qsTr("Set Waypoint")
    readonly property string gotoTitle:                     qsTr("Goto Location")
51
    readonly property string vtolTransitionTitle:           qsTr("VTOL Transition")
52

53 54
    readonly property string armMessage:                        qsTr("Arm the vehicle.")
    readonly property string disarmMessage:                     qsTr("Disarm the vehicle")
55
    readonly property string emergencyStopMessage:              qsTr("WARNING: THIS WILL STOP ALL MOTORS. IF VEHICLE IS CURRENTLY IN THE AIR IT WILL CRASH.")
56 57 58 59 60 61 62 63 64 65 66 67 68
    readonly property string takeoffMessage:                    qsTr("Takeoff from ground and hold position.")
    readonly property string startMissionMessage:               qsTr("Takeoff from ground and start the current mission.")
    readonly property string continueMissionMessage:            qsTr("Continue the mission from the current waypoint.")
             property string resumeMissionMessage:              qsTr("Resume the current mission. This will re-generate the mission from waypoint %1, takeoff and continue the mission.").arg(_resumeMissionIndex)
             property string resumeMissionUploadFailMessage:    qsTr("Upload of resume mission failed. Confirm to retry upload")
    readonly property string resumeMissionReadyMessage:         qsTr("Review the modified mission. Confirm if you want to takeoff and begin mission.")
    readonly property string landMessage:                       qsTr("Land the vehicle at the current position.")
    readonly property string rtlMessage:                        qsTr("Return to the home position of the vehicle.")
    readonly property string changeAltMessage:                  qsTr("Change the altitude of the vehicle up or down.")
    readonly property string gotoMessage:                       qsTr("Move the vehicle to the location clicked on the map.")
             property string setWaypointMessage:                qsTr("Adjust current waypoint to %1.").arg(_actionData)
    readonly property string orbitMessage:                      qsTr("Orbit the vehicle around the current location.")
    readonly property string landAbortMessage:                  qsTr("Abort the landing sequence.")
69
    readonly property string pauseMessage:                      qsTr("Pause the vehicle at it's current position, adjusting altitude up or down as needed.")
70
    readonly property string mvPauseMessage:                    qsTr("Pause all vehicles at their current position.")
71 72
    readonly property string vtolTransitionFwdMessage:          qsTr("Transition VTOL to fixed wing flight.")
    readonly property string vtolTransitionMRMessage:           qsTr("Transition VTOL to multi-rotor flight.")
73

74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90
    readonly property int actionRTL:                        1
    readonly property int actionLand:                       2
    readonly property int actionTakeoff:                    3
    readonly property int actionArm:                        4
    readonly property int actionDisarm:                     5
    readonly property int actionEmergencyStop:              6
    readonly property int actionChangeAlt:                  7
    readonly property int actionGoto:                       8
    readonly property int actionSetWaypoint:                9
    readonly property int actionOrbit:                      10
    readonly property int actionLandAbort:                  11
    readonly property int actionStartMission:               12
    readonly property int actionContinueMission:            13
    readonly property int actionResumeMission:              14
    readonly property int actionResumeMissionReady:         15
    readonly property int actionResumeMissionUploadFail:    16
    readonly property int actionPause:                      17
91 92
    readonly property int actionMVPause:                    18
    readonly property int actionMVStartMission:             19
93 94
    readonly property int actionVtolTransitionToFwdFlight:  20
    readonly property int actionVtolTransitionToMRFlight:   21
95

96 97 98 99 100 101 102 103 104 105 106 107 108
    property bool showEmergenyStop:     _guidedActionsEnabled && !_hideEmergenyStop && _vehicleArmed && _vehicleFlying
    property bool showArm:              _guidedActionsEnabled && !_vehicleArmed
    property bool showDisarm:           _guidedActionsEnabled && _vehicleArmed && !_vehicleFlying
    property bool showRTL:              _guidedActionsEnabled && _vehicleArmed && _activeVehicle.guidedModeSupported && _vehicleFlying && !_vehicleInRTLMode
    property bool showTakeoff:          _guidedActionsEnabled && _activeVehicle.takeoffVehicleSupported && !_vehicleFlying
    property bool showLand:             _guidedActionsEnabled && _activeVehicle.guidedModeSupported && _vehicleArmed && !_activeVehicle.fixedWing && !_vehicleInLandMode
    property bool showStartMission:     _guidedActionsEnabled && _missionAvailable && !_missionActive && !_vehicleFlying
    property bool showContinueMission:  _guidedActionsEnabled && _missionAvailable && !_missionActive && _vehicleFlying && (_currentMissionIndex < missionController.visualItems.count - 1)
    property bool showPause:            _guidedActionsEnabled && _vehicleArmed && _activeVehicle.pauseVehicleSupported && _vehicleFlying && !_vehiclePaused
    property bool showChangeAlt:        _guidedActionsEnabled && _vehicleFlying && _activeVehicle.guidedModeSupported && _vehicleArmed && !_missionActive
    property bool showOrbit:            _guidedActionsEnabled && !_hideOrbit && _vehicleFlying && _activeVehicle.orbitModeSupported && _vehicleArmed && !_missionActive
    property bool showLandAbort:        _guidedActionsEnabled && _vehicleFlying && _activeVehicle.fixedWing && _vehicleLanding
    property bool showGotoLocation:     _guidedActionsEnabled && _vehicleFlying
109

110 111 112
    // Note: The 'missionController.visualItems.count - 3' is a hack to not trigger resume mission when a mission ends with an RTL item
    property bool showResumeMission:    _activeVehicle && !_vehicleArmed && _vehicleWasFlying && _missionAvailable && _resumeMissionIndex > 0 && (_resumeMissionIndex < missionController.visualItems.count - 3)

DonLakeFlyer's avatar
DonLakeFlyer committed
113 114
    property bool guidedUIVisible:      guidedActionConfirm.visible || guidedActionList.visible

115
    property bool   _guidedActionsEnabled:  (!ScreenTools.isDebug && QGroundControl.corePlugin.options.guidedActionsRequireRCRSSI && _activeVehicle) ? _rcRSSIAvailable : _activeVehicle
116 117 118 119 120
    property var    _activeVehicle:         QGroundControl.multiVehicleManager.activeVehicle
    property string _flightMode:            _activeVehicle ? _activeVehicle.flightMode : ""
    property bool   _missionAvailable:      missionController.containsItems
    property bool   _missionActive:         _activeVehicle ? _vehicleArmed && (_vehicleInLandMode || _vehicleInRTLMode || _vehicleInMissionMode) : false
    property bool   _vehicleArmed:          _activeVehicle ? _activeVehicle.armed  : false
121
    property bool   _vehicleFlying:         _activeVehicle ? _activeVehicle.flying  : false
122
    property bool   _vehicleLanding:        _activeVehicle ? _activeVehicle.landing  : false
123 124 125 126
    property bool   _vehiclePaused:         false
    property bool   _vehicleInMissionMode:  false
    property bool   _vehicleInRTLMode:      false
    property bool   _vehicleInLandMode:     false
127
    property int    _currentMissionIndex:   missionController.currentMissionIndex
128 129 130
    property int    _resumeMissionIndex:    missionController.resumeMissionIndex
    property bool   _hideEmergenyStop:      !QGroundControl.corePlugin.options.guidedBarShowEmergencyStop
    property bool   _hideOrbit:             !QGroundControl.corePlugin.options.guidedBarShowOrbit
131
    property bool   _vehicleWasFlying:      false
132
    property bool   _rcRSSIAvailable:       _activeVehicle ? _activeVehicle.rcRSSI > 0 && _activeVehicle.rcRSSI < 255 : false
133

134
    //Handy code for debugging state problems
135 136
    property bool __debugGuidedStates:      false
    property bool __guidedModeSupported:    _activeVehicle ? _activeVehicle.guidedModeSupported : false
137
    property bool __pauseVehicleSupported: _activeVehicle ? _activeVehicle.pauseVehicleSupported : false
138
    property bool __flightMode:             _flightMode
139 140

    function _outputState() {
141 142 143
        if (__debugGuidedStates) {
            console.log(qsTr("_activeVehicle(%1) _vehicleArmed(%2) guidedModeSupported(%3) _vehicleFlying(%4) _vehicleInRTLMode(%5) pauseVehicleSupported(%6) _vehiclePaused(%7) _flightMode(%8)").arg(_activeVehicle ? 1 : 0).arg(_vehicleArmed ? 1 : 0).arg(__guidedModeSupported ? 1 : 0).arg(_vehicleFlying ? 1 : 0).arg(_vehicleInRTLMode ? 1 : 0).arg(__pauseVehicleSupported ? 1 : 0).arg(_vehiclePaused ? 1 : 0).arg(_flightMode))
        }
144 145
    }

146 147 148 149 150 151 152 153 154
    Component.onCompleted:              _outputState()
    on_ActiveVehicleChanged:            _outputState()
    on_VehicleArmedChanged:             _outputState()
    on_VehicleInRTLModeChanged:         _outputState()
    on_VehiclePausedChanged:            _outputState()
    on__FlightModeChanged:              _outputState()
    on__GuidedModeSupportedChanged:     _outputState()
    on__PauseVehicleSupportedChanged:   _outputState()

DonLakeFlyer's avatar
DonLakeFlyer committed
155 156 157 158 159 160 161 162 163 164
    on_CurrentMissionIndexChanged: {
        if (__debugGuidedStates) {
            console.log("_currentMissionIndex", _currentMissionIndex)
        }
    }
    on_ResumeMissionIndexChanged: {
        if (__debugGuidedStates) {
            console.log("_resumeMissionIndex", _resumeMissionIndex)
        }
    }
165
    onShowResumeMissionChanged: {
166 167 168
        if (__debugGuidedStates) {
            console.log("showResumeMission", showResumeMission)
        }
169 170 171
        _outputState()
    }
    onShowStartMissionChanged: {
172 173 174
        if (__debugGuidedStates) {
            console.log("showStartMission", showStartMission)
        }
175 176 177
        _outputState()
    }
    onShowContinueMissionChanged: {
178 179 180
        if (__debugGuidedStates) {
            console.log("showContinueMission", showContinueMission)
        }
181 182
        _outputState()
    }
183 184
    // End of hack

185
    on_VehicleFlyingChanged: {
186
        _outputState()
187 188 189 190 191 192
        if (!_vehicleFlying) {
            // We use _vehicleWasFLying to help trigger Resume Mission only if the vehicle actually flew and came back down.
            // Otherwise it may trigger during the Start Mission sequence due to signal ordering or armed and resume mission index.
            _vehicleWasFlying = true
        }
    }
193 194 195
    property var    _actionData

    on_FlightModeChanged: {
196 197 198 199
        _vehiclePaused =        _activeVehicle ? _flightMode === _activeVehicle.pauseFlightMode : false
        _vehicleInRTLMode =     _activeVehicle ? _flightMode === _activeVehicle.rtlFlightMode : false
        _vehicleInLandMode =    _activeVehicle ? _flightMode === _activeVehicle.landFlightMode : false
        _vehicleInMissionMode = _activeVehicle ? _flightMode === _activeVehicle.missionFlightMode : false // Must be last to get correct signalling for showStartMission popups
200
    }
201 202 203

    // Called when an action is about to be executed in order to confirm
    function confirmAction(actionCode, actionData) {
204
        var showImmediate = true
205
        closeAll()
206 207
        confirmDialog.action = actionCode
        confirmDialog.actionData = actionData
208
        confirmDialog.hideTrigger = true
209 210 211
        _actionData = actionData
        switch (actionCode) {
        case actionArm:
212
            if (_vehicleFlying || !_guidedActionsEnabled) {
213 214
                return
            }
215 216 217
            confirmDialog.title = armTitle
            confirmDialog.message = armMessage
            confirmDialog.hideTrigger = Qt.binding(function() { return !showArm })
218 219
            break;
        case actionDisarm:
220
            if (_vehicleFlying) {
221 222
                return
            }
223 224 225
            confirmDialog.title = disarmTitle
            confirmDialog.message = disarmMessage
            confirmDialog.hideTrigger = Qt.binding(function() { return !showDisarm })
226 227
            break;
        case actionEmergencyStop:
228 229 230
            confirmDialog.title = emergencyStopTitle
            confirmDialog.message = emergencyStopMessage
            confirmDialog.hideTrigger = Qt.binding(function() { return !showEmergenyStop })
231 232
            break;
        case actionTakeoff:
233 234 235
            confirmDialog.title = takeoffTitle
            confirmDialog.message = takeoffMessage
            confirmDialog.hideTrigger = Qt.binding(function() { return !showTakeoff })
236
            altitudeSlider.setToMinimumTakeoff()
237
            altitudeSlider.visible = true
238 239
            break;
        case actionStartMission:
240
            showImmediate = false
241 242 243
            confirmDialog.title = startMissionTitle
            confirmDialog.message = startMissionMessage
            confirmDialog.hideTrigger = Qt.binding(function() { return !showStartMission })
244
            break;
245 246 247 248 249
        case actionMVStartMission:
            confirmDialog.title = startMissionTitle
            confirmDialog.message = startMissionMessage
            confirmDialog.hideTrigger = true
            break;
250
        case actionContinueMission:
251
            showImmediate = false
252 253 254 255
            confirmDialog.title = continueMissionTitle
            confirmDialog.message = continueMissionMessage
            confirmDialog.hideTrigger = Qt.binding(function() { return !showContinueMission })
            break;
256
        case actionResumeMission:
257
            showImmediate = false
258 259 260
            confirmDialog.title = resumeMissionTitle
            confirmDialog.message = resumeMissionMessage
            confirmDialog.hideTrigger = Qt.binding(function() { return !showResumeMission })
261
            break;
262 263 264 265 266
        case actionResumeMissionUploadFail:
            confirmDialog.title = resumeMissionUploadFailTitle
            confirmDialog.message = resumeMissionUploadFailMessage
            confirmDialog.hideTrigger = Qt.binding(function() { return !showResumeMission })
            break;
267
        case actionResumeMissionReady:
268 269 270
            confirmDialog.title = resumeMissionTitle
            confirmDialog.message = resumeMissionReadyMessage
            confirmDialog.hideTrigger = false
271 272
            break;
        case actionLand:
273 274 275
            confirmDialog.title = landTitle
            confirmDialog.message = landMessage
            confirmDialog.hideTrigger = Qt.binding(function() { return !showLand })
276 277
            break;
        case actionRTL:
278 279 280
            confirmDialog.title = rtlTitle
            confirmDialog.message = rtlMessage
            confirmDialog.hideTrigger = Qt.binding(function() { return !showRTL })
281 282
            break;
        case actionChangeAlt:
283 284 285
            confirmDialog.title = changeAltTitle
            confirmDialog.message = changeAltMessage
            confirmDialog.hideTrigger = Qt.binding(function() { return !showChangeAlt })
Don Gagne's avatar
Don Gagne committed
286 287
            altitudeSlider.reset()
            altitudeSlider.visible = true
288 289
            break;
        case actionGoto:
290 291 292
            confirmDialog.title = gotoTitle
            confirmDialog.message = gotoMessage
            confirmDialog.hideTrigger = Qt.binding(function() { return !showGotoLocation })
293 294
            break;
        case actionSetWaypoint:
295 296
            confirmDialog.title = setWaypointTitle
            confirmDialog.message = setWaypointMessage
297 298
            break;
        case actionOrbit:
299 300 301
            confirmDialog.title = orbitTitle
            confirmDialog.message = orbitMessage
            confirmDialog.hideTrigger = Qt.binding(function() { return !showOrbit })
302 303
            break;
        case actionLandAbort:
304 305 306
            confirmDialog.title = landAbortTitle
            confirmDialog.message = landAbortMessage
            confirmDialog.hideTrigger = Qt.binding(function() { return !showLandAbort })
307 308
            break;
        case actionPause:
309 310 311
            confirmDialog.title = pauseTitle
            confirmDialog.message = pauseMessage
            confirmDialog.hideTrigger = Qt.binding(function() { return !showPause })
312 313
            altitudeSlider.reset()
            altitudeSlider.visible = true
314
            break;
315 316 317 318 319
        case actionMVPause:
            confirmDialog.title = pauseTitle
            confirmDialog.message = mvPauseMessage
            confirmDialog.hideTrigger = true
            break;
320 321 322 323 324 325 326 327 328 329
        case actionVtolTransitionToFwdFlight:
            confirmDialog.title = vtolTransitionTitle
            confirmDialog.message = vtolTransitionFwdMessage
            confirmDialog.hideTrigger = true
            break
        case actionVtolTransitionToMRFlight:
            confirmDialog.title = vtolTransitionTitle
            confirmDialog.message = vtolTransitionMRMessage
            confirmDialog.hideTrigger = true
            break
330 331 332
        default:
            console.warn("Unknown actionCode", actionCode)
            return
333
        }
334
        confirmDialog.show(showImmediate)
335 336 337 338
    }

    // Executes the specified action
    function executeAction(actionCode, actionData) {
339 340
        var i;
        var rgVehicle;
341 342 343 344 345 346 347 348
        switch (actionCode) {
        case actionRTL:
            _activeVehicle.guidedModeRTL()
            break
        case actionLand:
            _activeVehicle.guidedModeLand()
            break
        case actionTakeoff:
349
            _activeVehicle.guidedModeTakeoff(actionData)
350 351
            break
        case actionResumeMission:
352
        case actionResumeMissionUploadFail:
353
            missionController.resumeMission(missionController.resumeMissionIndex)
354 355
            break
        case actionResumeMissionReady:
356
            _vehicleWasFlying = false
357 358 359
            _activeVehicle.startMission()
            break
        case actionStartMission:
360
        case actionContinueMission:
361 362
            _activeVehicle.startMission()
            break
363
        case actionMVStartMission:
364 365 366
            rgVehicle = QGroundControl.multiVehicleManager.vehicles
            for (i = 0; i < rgVehicle.count; i++) {
                rgVehicle.get(i).startMission()
367 368
            }
            break
369
        case actionArm:
DonLakeFlyer's avatar
DonLakeFlyer committed
370
            _activeVehicle.armed = true
371 372
            break
        case actionDisarm:
DonLakeFlyer's avatar
DonLakeFlyer committed
373
            _activeVehicle.armed = false
374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394
            break
        case actionEmergencyStop:
            _activeVehicle.emergencyStop()
            break
        case actionChangeAlt:
            _activeVehicle.guidedModeChangeAltitude(actionData)
            break
        case actionGoto:
            _activeVehicle.guidedModeGotoLocation(actionData)
            break
        case actionSetWaypoint:
            _activeVehicle.setCurrentMissionSequence(actionData)
            break
        case actionOrbit:
            _activeVehicle.guidedModeOrbit()
            break
        case actionLandAbort:
            _activeVehicle.abortLanding(50)     // hardcoded value for climbOutAltitude that is currently ignored
            break
        case actionPause:
            _activeVehicle.pauseVehicle()
395
            _activeVehicle.guidedModeChangeAltitude(actionData)
396
            break
397
        case actionMVPause:
398 399 400
            rgVehicle = QGroundControl.multiVehicleManager.vehicles
            for (i = 0; i < rgVehicle.count; i++) {
                rgVehicle.get(i).pauseVehicle()
401 402
            }
            break
403 404 405 406 407 408
        case actionVtolTransitionToFwdFlight:
            _activeVehicle.vtolInFwdFlight = true
            break
        case actionVtolTransitionToMRFlight:
            _activeVehicle.vtolInFwdFlight = false
            break
409 410 411 412 413 414
        default:
            console.warn(qsTr("Internal error: unknown actionCode"), actionCode)
            break
        }
    }
}