Commit eaaeab0c authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #4907 from DonLakeFlyer/GuidedBarRewrite

Yet another guided bar rewrite
parents 4333b50b cc51c1d3
......@@ -126,6 +126,7 @@
<file alias="QGroundControl/FlightDisplay/FlightDisplayViewMap.qml">src/FlightDisplay/FlightDisplayViewMap.qml</file>
<file alias="QGroundControl/FlightDisplay/FlightDisplayViewVideo.qml">src/FlightDisplay/FlightDisplayViewVideo.qml</file>
<file alias="QGroundControl/FlightDisplay/FlightDisplayViewWidgets.qml">src/FlightDisplay/FlightDisplayViewWidgets.qml</file>
<file alias="QGroundControl/FlightDisplay/GuidedActionsController.qml">src/FlightDisplay/GuidedActionsController.qml</file>
<file alias="QGroundControl/FlightDisplay/MultiVehicleList.qml">src/FlightDisplay/MultiVehicleList.qml</file>
<file alias="QGroundControl/FlightDisplay/qmldir">src/FlightDisplay/qmldir</file>
<file alias="QGroundControl/FlightMap/CenterMapDropButton.qml">src/FlightMap/Widgets/CenterMapDropButton.qml</file>
......
......@@ -220,7 +220,7 @@ bool PX4FirmwarePlugin::supportsManualControl(void)
bool PX4FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities)
{
if (vehicle->multiRotor()) {
return (capabilities & (MavCmdPreflightStorageCapability | GuidedModeCapability | SetFlightModeCapability | PauseVehicleCapability | OrbitModeCapability)) == capabilities;
return (capabilities & (MavCmdPreflightStorageCapability | GuidedModeCapability | SetFlightModeCapability | PauseVehicleCapability /*| OrbitModeCapability still NYI*/)) == capabilities;
} else {
return (capabilities & (MavCmdPreflightStorageCapability | GuidedModeCapability | SetFlightModeCapability | PauseVehicleCapability)) == capabilities;
}
......
......@@ -15,6 +15,7 @@ import QtQuick.Dialogs 1.2
import QtLocation 5.3
import QtPositioning 5.3
import QtMultimedia 5.5
import QtQuick.Layouts 1.2
import QGroundControl 1.0
import QGroundControl.FlightDisplay 1.0
......@@ -86,6 +87,11 @@ QGCView {
}
}
MissionController {
id: flyMissionController
Component.onCompleted: start(false /* editMode */)
}
MessageDialog {
id: px4JoystickSupport
text: qsTr("Joystick support requires MAVLink MANUAL_CONTROL support. ") +
......@@ -144,11 +150,13 @@ QGCView {
}
]
FlightDisplayViewMap {
id: _flightMap
anchors.fill: parent
flightWidgets: flightDisplayViewWidgets
rightPanelWidth: ScreenTools.defaultFontPixelHeight * 9
qgcView: root
id: _flightMap
anchors.fill: parent
missionController: flyMissionController
guidedActionsController: guidedController
flightWidgets: flightDisplayViewWidgets
rightPanelWidth: ScreenTools.defaultFontPixelHeight * 9
qgcView: root
}
}
......@@ -243,7 +251,7 @@ QGCView {
z: _panel.z + 4
height: ScreenTools.availableHeight
anchors.left: parent.left
anchors.right: parent.right
anchors.right: altitudeSlider.visible ? altitudeSlider.left : parent.right
anchors.bottom: parent.bottom
qgcView: root
useLightColors: isBackgroundDark
......@@ -315,5 +323,371 @@ QGCView {
property Fact _virtualJoystick: QGroundControl.settingsManager.appSettings.virtualJoystick
}
ToolStrip {
id: toolStrip
anchors.leftMargin: ScreenTools.defaultFontPixelWidth
anchors.left: _panel.left
anchors.topMargin: ScreenTools.toolbarHeight + _margins
anchors.top: _panel.top
z: _panel.z + 4
title: qsTr("Fly")
maxHeight: (_flightVideo.visible ? _flightVideo.y : parent.height) - toolStrip.y
buttonVisible: [ guidedController.showTakeoff || !guidedController.showLand, guidedController.showLand, true, true, true, guidedController.smartShotsAvailable ]
buttonEnabled: [ guidedController.showTakeoff, guidedController.showLand, guidedController.showRTL, guidedController.showPause, _anyActionAvailable, _anySmartShotAvailable ]
property bool _anyActionAvailable: guidedController.showEmergenyStop || guidedController.showStartMission || guidedController.showResumeMission || guidedController.showChangeAlt || guidedController.showLandAbort
property bool _anySmartShotAvailable: guidedController.showOrbit
property var _actionModel: [
{
title: guidedController.startMissionTitle,
text: guidedController.startMissionMessage,
action: guidedController.actionStartMission,
visible: guidedController.showStartMission
},
{
title: guidedController.resumeMissionTitle,
text: guidedController.resumeMissionMessage,
action: guidedController.actionResumeMission,
visible: guidedController.showResumeMission
},
{
title: guidedController.changeAltTitle,
text: guidedController.changeAltMessage,
action: guidedController.actionChangeAlt,
visible: guidedController.showChangeAlt
},
{
title: guidedController.landAbortTitle,
text: guidedController.landAbortMessage,
action: guidedController.actionLandAbort,
visible: guidedController.showLandAbort
}
]
property var _smartShotModel: [
{
title: guidedController.orbitTitle,
text: guidedController.orbitMessage,
action: guidedController.actionOrbit,
visible: guidedController.showOrbit
}
]
model: [
{
name: guidedController.takeoffTitle,
iconSource: "/qmlimages/MapCenter.svg",
action: guidedController.actionTakeoff
},
{
name: guidedController.landTitle,
iconSource: "/qmlimages/MapCenter.svg",
action: guidedController.actionLand
},
{
name: guidedController.rtlTitle,
iconSource: "/qmlimages/MapCenter.svg",
action: guidedController.actionRTL
},
{
name: guidedController.pauseTitle,
iconSource: "/qmlimages/MapCenter.svg",
action: guidedController.actionPause
},
{
name: qsTr("Action"),
iconSource: "/qmlimages/MapCenter.svg",
action: -1
},
/*
No firmware support any smart shots yet
{
name: qsTr("Smart"),
iconSource: "/qmlimages/MapCenter.svg",
action: -1
},
*/
]
onClicked: {
guidedActionConfirm.visible = false
guidedActionList.visible = false
altitudeSlider.visible = false
var action = model[index].action
if (action === -1) {
if (index == 4) {
guidedActionList.model = _actionModel
guidedActionList.visible = true
} else if (index == 5) {
guidedActionList.model = _smartShotModel
guidedActionList.visible = true
}
} else {
guidedController.confirmAction(action)
}
}
}
GuidedActionsController {
id: guidedController
missionController: flyMissionController
z: _flightVideoPipControl.z + 1
onShowConfirmAction: {
guidedActionConfirm.title = title
guidedActionConfirm.message = message
guidedActionConfirm.action = action
guidedActionConfirm.actionData = actionData
guidedActionConfirm.visible = true
}
}
Rectangle {
id: guidedActionConfirm
anchors.margins: _margins
anchors.bottom: parent.bottom
anchors.horizontalCenter: parent.horizontalCenter
width: confirmColumn.width + (_margins * 2)
height: confirmColumn.height + (_margins * 2)
radius: ScreenTools.defaultFontPixelHeight / 2
color: qgcPal.window
opacity: 0.9
z: guidedController.z
visible: false
property alias title: titleText.text
property alias message: messageText.text
property int action
property var actionData
property real _margins: ScreenTools.defaultFontPixelWidth
Column {
id: confirmColumn
anchors.margins: _margins
anchors.top: parent.top
anchors.left: parent.left
spacing: _margins
QGCLabel {
id: titleText
anchors.left: slider.left
anchors.right: slider.right
horizontalAlignment: Text.AlignHCenter
}
QGCLabel {
id: messageText
anchors.left: slider.left
anchors.right: slider.right
horizontalAlignment: Text.AlignHCenter
wrapMode: Text.WordWrap
}
// Action confirmation control
SliderSwitch {
id: slider
confirmText: qsTr("Slide to confirm")
width: Math.max(implicitWidth, ScreenTools.defaultFontPixelWidth * 30)
onAccept: {
guidedActionConfirm.visible = false
if (altitudeSlider.visible) {
guidedActionConfirm.actionData = altitudeSlider.getValue()
altitudeSlider.visible = false
}
guidedController.executeAction(guidedActionConfirm.action, guidedActionConfirm.actionData)
}
onReject: {
altitudeSlider.visible = false
guidedActionConfirm.visible = false
}
}
}
QGCColoredImage {
anchors.margins: _margins
anchors.top: parent.top
anchors.right: parent.right
width: ScreenTools.defaultFontPixelHeight
height: width
sourceSize.height: width
source: "/res/XDelete.svg"
fillMode: Image.PreserveAspectFit
color: qgcPal.text
QGCMouseArea {
fillItem: parent
onClicked: {
altitudeSlider.visible = false
guidedActionConfirm.visible = false
}
}
}
}
Rectangle {
id: guidedActionList
anchors.margins: _margins
anchors.bottom: parent.bottom
anchors.horizontalCenter: parent.horizontalCenter
width: actionColumn.width + (_margins * 2)
height: actionColumn.height + (_margins * 2)
radius: _margins / 2
color: qgcPal.window
opacity: 0.9
z: guidedController.z
visible: false
property alias model: actionRepeater.model
property real _margins: Math.round(ScreenTools.defaultFontPixelHeight * 0.66)
ColumnLayout {
id: actionColumn
anchors.margins: guidedActionList._margins
anchors.top: parent.top
anchors.left: parent.left
spacing: _margins
QGCLabel {
text: qsTr("Select Action")
Layout.alignment: Qt.AlignHCenter
}
QGCFlickable {
contentWidth: actionRow.width
contentHeight: actionRow.height
Layout.minimumHeight: actionRow.height
Layout.maximumHeight: actionRow.height
Layout.minimumWidth: _width
Layout.maximumWidth: _width
property real _width: Math.min(root.width * 0.8, actionRow.width)
RowLayout {
id: actionRow
spacing: ScreenTools.defaultFontPixelHeight * 2
Repeater {
id: actionRepeater
ColumnLayout {
spacing: ScreenTools.defaultFontPixelHeight / 2
visible: modelData.visible
Layout.fillHeight: true
QGCLabel {
id: actionMessage
text: modelData.text
horizontalAlignment: Text.AlignHCenter
wrapMode: Text.WordWrap
Layout.minimumWidth: _width
Layout.maximumWidth: _width
Layout.fillHeight: true
property real _width: ScreenTools.defaultFontPixelWidth * 25
}
QGCButton {
id: actionButton
anchors.horizontalCenter: parent.horizontalCenter
text: modelData.title
onClicked: {
if (modelData.action === guidedController.actionChangeAlt) {
altitudeSlider.visible = true
}
guidedActionList.visible = false
guidedController.confirmAction(modelData.action)
}
}
}
}
}
}
}
QGCColoredImage {
anchors.margins: _margins
anchors.top: parent.top
anchors.right: parent.right
width: ScreenTools.defaultFontPixelHeight
height: width
sourceSize.height: width
source: "/res/XDelete.svg"
fillMode: Image.PreserveAspectFit
color: qgcPal.text
QGCMouseArea {
fillItem: parent
onClicked: guidedActionList.visible = false
}
}
}
//-- Altitude slider
Rectangle {
id: altitudeSlider
anchors.margins: _margins
anchors.right: parent.right
anchors.topMargin: ScreenTools.toolbarHeight + _margins
anchors.top: parent.top
anchors.bottom: parent.bottom
z: guidedController.z
radius: ScreenTools.defaultFontPixelWidth / 2
width: ScreenTools.defaultFontPixelWidth * 10
color: qgcPal.window
visible: false
function setValue(value) {
altSlider.value = value
}
function getValue() {
return altSlider.value
}
Column {
id: headerColumn
anchors.margins: _margins
anchors.top: parent.top
anchors.left: parent.left
anchors.right: parent.right
QGCLabel {
anchors.horizontalCenter: parent.horizontalCenter
text: altSlider.value >=0 ? qsTr("Up") : qsTr("Down")
}
QGCLabel {
id: altField
anchors.horizontalCenter: parent.horizontalCenter
text: Math.abs(altSlider.value.toFixed(1)) + " " + QGroundControl.appSettingsDistanceUnitsString
}
}
QGCSlider {
id: altSlider
anchors.margins: _margins
anchors.top: headerColumn.bottom
anchors.bottom: parent.bottom
anchors.left: parent.left
anchors.right: parent.right
orientation: Qt.Vertical
minimumValue: QGroundControl.metersToAppSettingsDistanceUnits(-10)
maximumValue: QGroundControl.metersToAppSettingsDistanceUnits(10)
indicatorCentered: true
rotation: 180
// We want slide up to be positive values
transform: Rotation {
origin.x: altSlider.width / 2
origin.y: altSlider.height / 2
angle: 180
}
}
}
}
}
......@@ -30,19 +30,19 @@ FlightMap {
allowGCSLocationCenter: !userPanned
allowVehicleLocationCenter: !_keepVehicleCentered
property alias missionController: missionController
property var missionController
property var guidedActionsController
property var flightWidgets
property var rightPanelWidth
property var qgcView ///< QGCView control which contains this map
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property var _activeVehicleCoordinate: _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate()
property var _gotoHereCoordinate: QtPositioning.coordinate()
property int _retaskSequence: 0
property real _toolButtonTopMargin: parent.height - ScreenTools.availableHeight + (ScreenTools.defaultFontPixelHeight / 2)
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property var _activeVehicleCoordinate: _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate()
property var _gotoHereCoordinate: QtPositioning.coordinate()
property real _toolButtonTopMargin: parent.height - ScreenTools.availableHeight + (ScreenTools.defaultFontPixelHeight / 2)
property bool _disableVehicleTracking: false
property bool _keepVehicleCentered: _mainIsMap ? false : true
property bool _disableVehicleTracking: false
property bool _keepVehicleCentered: _mainIsMap ? false : true
// Track last known map position and zoom from Fly view in settings
......@@ -124,13 +124,11 @@ FlightMap {
QGCPalette { id: qgcPal; colorGroupEnabled: true }
QGCMapPalette { id: mapPal; lightColors: isSatelliteMap }
MissionController {
id: missionController
Component.onCompleted: start(false /* editMode */)
Connections {
target: missionController
onNewItemsFromVehicle: {
var visualItem = missionController.visualItems
var visualItems = missionController.visualItems
if (visualItems && visualItems.count != 1) {
mapFitFunctions.fitMapViewportToMissionItems()
firstVehiclePositionReceived = true
......@@ -195,50 +193,6 @@ FlightMap {
id: _mapTypeButtonsExclusiveGroup
}
ToolStrip {
id: toolStrip
anchors.leftMargin: ScreenTools.defaultFontPixelWidth
anchors.left: parent.left
anchors.topMargin: _toolButtonTopMargin
anchors.top: parent.top
color: qgcPal.window
title: qsTr("Fly")
z: QGroundControl.zOrderWidgets
buttonVisible: [ true, _showZoom, _showZoom ]
maxHeight: (_flightVideo.visible ? _flightVideo.y : parent.height) - toolStrip.y // Massive reach across hack
property bool _showZoom: !ScreenTools.isMobile
model: [
{
name: "Center",
iconSource: "/qmlimages/MapCenter.svg",
dropPanelComponent: centerMapDropPanel
},
{
name: "In",
iconSource: "/qmlimages/ZoomPlus.svg"
},
{
name: "Out",
iconSource: "/qmlimages/ZoomMinus.svg"
}
]
onClicked: {
switch (index) {
case 1:
_flightMap.zoomLevel += 0.5
break
case 2:
_flightMap.zoomLevel -= 0.5
break
}
}
}
// Toolstrip drop panel compomnents
MapFitFunctions {
id: mapFitFunctions
map: _flightMap
......@@ -250,15 +204,6 @@ FlightMap {
property real leftToolWidth: toolStrip.x + toolStrip.width
}
Component {
id: centerMapDropPanel
CenterMapDropPanel {
map: _flightMap
fitFunctions: mapFitFunctions
}
}
// Add trajectory points to the map
MapItemView {
model: _mainIsMap ? _activeVehicle ? _activeVehicle.trajectoryPoints : 0 : 0
......@@ -293,11 +238,7 @@ FlightMap {
delegate: MissionItemMapVisual {
map: flightMap
onClicked: {
_retaskSequence = object.sequenceNumber
flightWidgets.guidedModeBar.confirmAction(parent.flightWidgets.guidedModeBar.confirmRetask)
}
onClicked: guidedActionsController.confirmAction(guidedActionsController.actionSetWaypoint, object.sequenceNumber)
}
}
......@@ -345,30 +286,24 @@ FlightMap {
}
}
MapScale {
anchors.bottomMargin: ScreenTools.defaultFontPixelHeight * (0.66)
anchors.rightMargin: ScreenTools.defaultFontPixelHeight * (0.33)
anchors.bottom: parent.bottom
anchors.right: parent.right
mapControl: flightMap
visible: !ScreenTools.isTinyScreen
}
// Handle guided mode clicks
MouseArea {
anchors.fill: parent
onClicked: {
if (_activeVehicle) {
if (flightWidgets.guidedModeBar.state != "Shown") {
flightWidgets.guidedModeBar.state = "Shown"
} else {
if (flightWidgets.gotoEnabled) {
_gotoHereCoordinate = flightMap.toCoordinate(Qt.point(mouse.x, mouse.y), false /* clipToViewPort */)
flightWidgets.guidedModeBar.confirmAction(flightWidgets.guidedModeBar.confirmGoTo)
}
}
if (guidedActionsController.showGotoLocation) {
_gotoHereCoordinate = flightMap.toCoordinate(Qt.point(mouse.x, mouse.y), false /* clipToViewPort */)
guidedActionsController.confirmAction(guidedActionsController.actionGoto, _gotoHereCoordinate)
}
}
}
MapScale {
anchors.bottomMargin: ScreenTools.defaultFontPixelHeight * (0.66)
anchors.rightMargin: ScreenTools.defaultFontPixelHeight * (0.33)
anchors.bottom: parent.bottom
anchors.right: parent.right
mapControl: flightMap
visible: !ScreenTools.isTinyScreen
}
}
......@@ -25,8 +25,6 @@ import QGroundControl.FlightMap 1.0
Item {
id: _root
property alias guidedModeBar: _guidedModeBar
property bool gotoEnabled: _activeVehicle && _activeVehicle.guidedMode && _activeVehicle.flying
property var qgcView
property bool useLightColors
property var missionController
......@@ -35,16 +33,6 @@ Item {
property bool _isSatellite: _mainIsMap ? (_flightMap ? _flightMap.isSatelliteMap : true) : true
property bool _lightWidgetBorders: _isSatellite
// Guided bar properties
property bool _missionAvailable: missionController.containsItems
property bool _missionActive: _activeVehicle ? _activeVehicle.flightMode === _activeVehicle.missionFlightMode : false
property bool _vehiclePaused: _activeVehicle ? _activeVehicle.flightMode === _activeVehicle.pauseFlightMode : false
property bool _vehicleInRTLMode: _activeVehicle ? _activeVehicle.flightMode === _activeVehicle.rtlFlightMode : false
property bool _vehicleInLandMode: _activeVehicle ? _activeVehicle.flightMode === _activeVehicle.landFlightMode : false
property int _resumeMissionItem: missionController.resumeMissionItem
property bool _showEmergenyStop: QGroundControl.corePlugin.options.guidedBarShowEmergencyStop
property bool _showOrbit: QGroundControl.corePlugin.options.guidedBarShowOrbit
readonly property real _margins: ScreenTools.defaultFontPixelHeight * 0.5
QGCMapPalette { id: mapPal; lightColors: useLightColors }
......@@ -133,7 +121,7 @@ Item {
Loader {
id: instrumentsLoader
anchors.margins: ScreenTools.defaultFontPixelHeight / 2
anchors.right: altitudeSlider.visible ? altitudeSlider.left : parent.right
anchors.right: parent.right
z: QGroundControl.zOrderWidgets
property var qgcView: _root.qgcView
property real maxHeight:parent.height - (anchors.margins * 2)
......@@ -167,405 +155,4 @@ Item {
}
]
}
//-- Guided mode buttons
Rectangle {
id: _guidedModeBar
anchors.margins: _barMargin
anchors.bottom: parent.bottom
anchors.horizontalCenter: parent.horizontalCenter
width: (guidedModeButtons.visible ? guidedModeButtons.width : guidedModeConfirm.width) + (_margins * 2)
height: (guidedModeButtons.visible ? guidedModeButtons.height : guidedModeConfirm.height) + (_margins * 2)
radius: ScreenTools.defaultFontPixelHeight * 0.25
color: _backgroundColor
visible: _activeVehicle
z: QGroundControl.zOrderWidgets
property real _fontPointSize: ScreenTools.isMobile ? ScreenTools.largeFontPointSize : ScreenTools.defaultFontPointSize
property color _backgroundColor: _isSatellite ? qgcPal.mapWidgetBorderLight : qgcPal.mapWidgetBorderDark
property color _textColor: _isSatellite ? qgcPal.mapWidgetBorderDark : qgcPal.mapWidgetBorderLight
property string _emergencyStopTitle: qsTr("Emergency Stop")
property string _armTitle: qsTr("Arm")
property string _disarmTitle: qsTr("Disarm")
property string _rtlTitle: qsTr("RTL")
property string _takeoffTitle: qsTr("Takeoff")
property string _landTitle: qsTr("Land")
property string _startMissionTitle: qsTr("Start Mission")
property string _resumeMissionTitle: qsTr("Resume Mission")
property string _pauseTitle: _missionActive ? qsTr("Pause Mission") : qsTr("Pause")
property string _changeAltTitle: qsTr("Change Altitude")
property string _orbitTitle: qsTr("Orbit")
property string _abortTitle: qsTr("Abort")
readonly property int confirmHome: 1
readonly property int confirmLand: 2
readonly property int confirmTakeoff: 3
readonly property int confirmArm: 4
readonly property int confirmDisarm: 5
readonly property int confirmEmergencyStop: 6
readonly property int confirmChangeAlt: 7
readonly property int confirmGoTo: 8
readonly property int confirmRetask: 9
readonly property int confirmOrbit: 10
readonly property int confirmAbort: 11
readonly property int confirmStartMission: 12
readonly property int confirmResumeMission: 13
readonly property int confirmResumeMissionReady: 14
property int confirmActionCode
property real _showMargin: _margins
property real _hideMargin: _margins - _guidedModeBar.height
property real _barMargin: _showMargin
function actionConfirmed() {
switch (confirmActionCode) {
case confirmHome:
_activeVehicle.guidedModeRTL()
break;
case confirmLand:
_activeVehicle.guidedModeLand()
break;
case confirmTakeoff:
_activeVehicle.guidedModeTakeoff()
break;
case confirmResumeMission:
missionController.resumeMission(missionController.resumeMissionItem)
break;
case confirmResumeMissionReady:
_activeVehicle.startMission()
break;
case confirmStartMission:
_activeVehicle.startMission()
break;
case confirmArm:
_activeVehicle.armed = true
break;
case confirmDisarm:
_activeVehicle.armed = false
break;
case confirmEmergencyStop:
_activeVehicle.emergencyStop()
break;
case confirmChangeAlt:
_activeVehicle.guidedModeChangeAltitude(altitudeSlider.getValue())
break;
case confirmGoTo:
_activeVehicle.guidedModeGotoLocation(_flightMap._gotoHereCoordinate)
break;
case confirmRetask:
_activeVehicle.setCurrentMissionSequence(_flightMap._retaskSequence)
break;
case confirmOrbit:
//-- All parameters controlled by RC
_activeVehicle.guidedModeOrbit()
//-- Center on current flight map position and orbit with a 50m radius (velocity/direction controlled by the RC)
//_activeVehicle.guidedModeOrbit(QGroundControl.flightMapPosition, 50.0)
break;
case confirmAbort:
_activeVehicle.abortLanding(50) // hardcoded value for climbOutAltitude that is currently ignored
break;
default:
console.warn(qsTr("Internal error: unknown confirmActionCode"), confirmActionCode)
}
}
function rejectGuidedModeConfirm() {
guidedModeButtons.visible = true
guidedModeConfirm.visible = false
altitudeSlider.visible = false
_flightMap._gotoHereCoordinate = QtPositioning.coordinate()
}
function confirmAction(actionCode) {
confirmActionCode = actionCode
switch (confirmActionCode) {
case confirmArm:
guidedModeConfirm.title = _armTitle
guidedModeConfirm.message = qsTr("arm")
break;
case confirmDisarm:
guidedModeConfirm.title = _disarmTitle
guidedModeConfirm.message = qsTr("disarm")
break;
case confirmEmergencyStop:
guidedModeConfirm.title = _emergencyStopTitle
guidedModeConfirm.message = qsTr("WARNING: This still stop all motors. If vehicle is currently in air it will crash.")
break;
case confirmTakeoff:
guidedModeConfirm.title = _takeoffTitle
guidedModeConfirm.message = qsTr("Takeoff from ground and hold position.")
break;
case confirmStartMission:
guidedModeConfirm.title = _startMissionTitle
guidedModeConfirm.message = qsTr("Start the mission which is currently displayed above. If the vehicle is on the ground it will takeoff.")
break;
case confirmResumeMission:
guidedModeConfirm.title = _resumeMissionTitle
guidedModeConfirm.message = qsTr("Resume the mission which is displayed above. This will re-generate the mission from waypoint %1, takeoff and continue the mission.").arg(_resumeMissionItem)
break;
case confirmResumeMissionReady:
guidedModeConfirm.title = _resumeMissionTitle
guidedModeConfirm.message = qsTr("Review the modified mission above. Confirm if you want to takeoff and begin mission.")
break;
case confirmLand:
guidedModeConfirm.title = _landTitle
guidedModeConfirm.message = qsTr("Land the vehicle at the current position.")
break;
case confirmHome:
guidedModeConfirm.title = _rtlTitle
guidedModeConfirm.message = qsTr("Return to the home position of the vehicle.")
break;
case confirmChangeAlt:
altitudeSlider.visible = true
altitudeSlider.setValue(0)
guidedModeConfirm.title = _changeAltTitle
guidedModeConfirm.message = qsTr("Adjust the slider to the left up or down to change the altitude of the vehicle.")
break;
case confirmGoTo:
guidedModeConfirm.title = qsTr("Go To Location")
guidedModeConfirm.message = qsTr("Confirm to move to the new location.")
break;
case confirmRetask:
guidedModeConfirm.title = qsTr("Waypoint Change")
guidedModeConfirm.message = qsTr("Confirm to change current mission item to %1.").arg(_flightMap._retaskSequence)
break;
case confirmOrbit:
guidedModeConfirm.title = _orbitTitle
guidedModeConfirm.message = qsTr("Confirm to enter Orbit mode.")
break;
case confirmAbort:
guidedModeConfirm.title = _abortTitle
guidedModeConfirm.message = qsTr("Confirm to abort the current landing.")
break;
}
guidedModeButtons.visible = false
guidedModeConfirm.visible = true
}
ColumnLayout {
id: guidedModeButtons
anchors.margins: _margins
anchors.top: parent.top
anchors.left: parent.left
spacing: _margins
QGCLabel {
anchors.horizontalCenter: parent.horizontalCenter
color: _guidedModeBar._textColor
text: qsTr("Click in map to move vehicle")
visible: gotoEnabled
}
Row {
spacing: _margins * 2
QGCButton {
pointSize: _guidedModeBar._fontPointSize
text: _guidedModeBar._emergencyStopTitle
visible: _showEmergenyStop && _activeVehicle && _activeVehicle.armed && _activeVehicle.flying
onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmEmergencyStop)
}
QGCButton {
pointSize: _guidedModeBar._fontPointSize
text: _guidedModeBar._disarmTitle
visible: _activeVehicle && _activeVehicle.armed && !_activeVehicle.flying
onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmDisarm)
}
QGCButton {
pointSize: _guidedModeBar._fontPointSize
text: _guidedModeBar._rtlTitle
visible: _activeVehicle && _activeVehicle.armed && _activeVehicle.guidedModeSupported && _activeVehicle.flying && !_vehicleInRTLMode
onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmHome)
}
QGCButton {
pointSize: _guidedModeBar._fontPointSize
text: _guidedModeBar._takeoffTitle
visible: _activeVehicle && _activeVehicle.guidedModeSupported && !_activeVehicle.flying && !_activeVehicle.fixedWing
onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmTakeoff)
}
QGCButton {
pointSize: _guidedModeBar._fontPointSize
text: _guidedModeBar._landTitle
visible: _activeVehicle && _activeVehicle.guidedModeSupported && _activeVehicle.armed && !_activeVehicle.fixedWing && !_vehicleInLandMode
onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmLand)
}
QGCButton {
pointSize: _guidedModeBar._fontPointSize
text: _guidedModeBar._startMissionTitle
visible: _activeVehicle && _missionAvailable && !_missionActive
onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmStartMission)
}
QGCButton {
pointSize: _guidedModeBar._fontPointSize
text: _guidedModeBar._resumeMissionTitle
visible: _activeVehicle && !_activeVehicle.flying && _missionAvailable && _resumeMissionItem !== -1
onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmResumeMission)
}
QGCButton {
pointSize: _guidedModeBar._fontPointSize
text: _guidedModeBar._pauseTitle
visible: _activeVehicle && _activeVehicle.armed && _activeVehicle.pauseVehicleSupported && _activeVehicle.flying && !_vehiclePaused
onClicked: _activeVehicle.pauseVehicle()
}
QGCButton {
pointSize: _guidedModeBar._fontPointSize
text: _guidedModeBar._changeAltTitle
visible: (_activeVehicle && _activeVehicle.flying) && _activeVehicle.guidedModeSupported && _activeVehicle.armed && !_missionActive
onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmChangeAlt)
}
QGCButton {
pointSize: _guidedModeBar._fontPointSize
text: _guidedModeBar._orbitTitle
visible: _showOrbit && _activeVehicle && _activeVehicle.flying && _activeVehicle.orbitModeSupported && _activeVehicle.armed && !_missionActive
onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmOrbit)
}
QGCButton {
pointSize: _guidedModeBar._fontPointSize
text: _guidedModeBar._abortTitle
visible: _activeVehicle && _activeVehicle.flying && _activeVehicle.fixedWing
onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmAbort)
}
}
}
Column {
id: guidedModeConfirm
anchors.margins: _margins
anchors.top: parent.top
anchors.left: parent.left
spacing: _margins
visible: false
property alias title: titleText.text
property alias message: messageText.text
QGCLabel {
id: titleText
anchors.left: slider.left
anchors.right: slider.right
color: _guidedModeBar._textColor
horizontalAlignment: Text.AlignHCenter
}
QGCLabel {
id: messageText
anchors.left: slider.left
anchors.right: slider.right
color: _guidedModeBar._textColor
horizontalAlignment: Text.AlignHCenter
wrapMode: Text.WordWrap
}
// Action confirmation control
SliderSwitch {
id: slider
fontPointSize: _guidedModeBar._fontPointSize
confirmText: qsTr("Slide to confirm")
width: Math.max(implicitWidth, ScreenTools.defaultFontPixelWidth * 30)
onAccept: {
guidedModeButtons.visible = true
guidedModeConfirm.visible = false
altitudeSlider.visible = false
_guidedModeBar.actionConfirmed()
}
onReject: _guidedModeBar.rejectGuidedModeConfirm()
}
}
QGCColoredImage {
anchors.margins: _margins
anchors.top: _guidedModeBar.top
anchors.right: _guidedModeBar.right
width: ScreenTools.defaultFontPixelHeight
height: width
sourceSize.height: width
source: "/res/XDelete.svg"
fillMode: Image.PreserveAspectFit
color: qgcPal.alertText
visible: guidedModeConfirm.visible
QGCMouseArea {
fillItem: parent
onClicked: _guidedModeBar.rejectGuidedModeConfirm()
}
}
} // Rectangle - Guided mode buttons
//-- Altitude slider
Rectangle {
id: altitudeSlider
anchors.margins: _margins
anchors.right: parent.right
anchors.top: parent.top
anchors.bottom: parent.bottom
radius: ScreenTools.defaultFontPixelWidth / 2
width: ScreenTools.defaultFontPixelWidth * 10
color: qgcPal.window
visible: false
function setValue(value) {
altSlider.value = value
}
function getValue() {
return altSlider.value
}
Column {
id: headerColumn
anchors.margins: _margins
anchors.top: parent.top
anchors.left: parent.left
anchors.right: parent.right
QGCLabel {
anchors.horizontalCenter: parent.horizontalCenter
text: altSlider.value >=0 ? qsTr("Up") : qsTr("Down")
}
QGCLabel {
id: altField
anchors.horizontalCenter: parent.horizontalCenter
text: Math.abs(altSlider.value.toFixed(1)) + " " + QGroundControl.appSettingsDistanceUnitsString
}
}
QGCSlider {
id: altSlider
anchors.margins: _margins
anchors.top: headerColumn.bottom
anchors.bottom: parent.bottom
anchors.left: parent.left
anchors.right: parent.right
orientation: Qt.Vertical
//minimumValue: QGroundControl.metersToAppSettingsDistanceUnits(0)
//maximumValue: QGroundControl.metersToAppSettingsDistanceUnits((_activeVehicle && _activeVehicle.flying) ? Math.round((_activeVehicle.altitudeRelative.value + 100) / 100) * 100 : 10)
minimumValue: QGroundControl.metersToAppSettingsDistanceUnits(-10)
maximumValue: QGroundControl.metersToAppSettingsDistanceUnits(10)
indicatorCentered: true
rotation: 180
// We want slide up to be positive values
transform: Rotation {
origin.x: altSlider.width / 2
origin.y: altSlider.height / 2
angle: 180
}
}
}
}
/****************************************************************************
*
* (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
signal showConfirmAction(string title, string message, int action, var actionData)
readonly property string emergencyStopTitle: qsTr("Emergency Stop")
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 resumeMissionTitle: qsTr("Resume Mission")
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")
readonly property string armMessage: qsTr("arm")
readonly property string disarmMessage: qsTr("disarm")
readonly property string emergencyStopMessage: qsTr("WARNING: This still stop all motors. If vehicle is currently in air it will crash.")
readonly property string takeoffMessage: qsTr("Takeoff from ground and hold position.")
readonly property string startMissionMessage: qsTr("Start the mission which is currently displayed above. If the vehicle is on the ground it will takeoff.")
property string resumeMissionMessage: qsTr("Resume the mission which is displayed above. This will re-generate the mission from waypoint %1, takeoff and continue the mission.").arg(_resumeMissionItem)
readonly property string resumeMissionReadyMessage: qsTr("Review the modified mission above. 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.")
readonly property string pauseMessage: qsTr("Pause the vehicle at it's current position.")
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 actionResumeMission: 13
readonly property int actionResumeMissionReady: 14
readonly property int actionPause: 15
property bool showEmergenyStop: !_hideEmergenyStop && _activeVehicle && _activeVehicle.armed && _activeVehicle.flying
property bool showDisarm: _activeVehicle && _activeVehicle.armed && !_activeVehicle.flying
property bool showRTL: _activeVehicle && _activeVehicle.armed && _activeVehicle.guidedModeSupported && _activeVehicle.flying && !_vehicleInRTLMode
property bool showTakeoff: _activeVehicle && _activeVehicle.guidedModeSupported && !_activeVehicle.flying && !_activeVehicle.fixedWing
property bool showLand: _activeVehicle && _activeVehicle.guidedModeSupported && _activeVehicle.armed && !_activeVehicle.fixedWing && !_vehicleInLandMode
property bool showStartMission: _activeVehicle && _missionAvailable && !_missionActive
property bool showResumeMission: _activeVehicle && !_activeVehicle.flying && _missionAvailable && _resumeMissionItem > 1
property bool showPause: _activeVehicle && _activeVehicle.armed && _activeVehicle.pauseVehicleSupported && _activeVehicle.flying && !_vehiclePaused
property bool showChangeAlt: (_activeVehicle && _activeVehicle.flying) && _activeVehicle.guidedModeSupported && _activeVehicle.armed && !_missionActive
property bool showOrbit: !_hideOrbit && _activeVehicle && _activeVehicle.flying && _activeVehicle.orbitModeSupported && _activeVehicle.armed && !_missionActive
property bool showLandAbort: _activeVehicle && _activeVehicle.flying && _activeVehicle.fixedWing
property bool showGotoLocation: _activeVehicle && _activeVehicle.guidedMode && _activeVehicle.flying
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _missionAvailable: missionController.containsItems
property bool _missionActive: _activeVehicle ? _activeVehicle.flightMode === _activeVehicle.missionFlightMode : false
property bool _vehiclePaused: _activeVehicle ? _activeVehicle.flightMode === _activeVehicle.pauseFlightMode : false
property bool _vehicleInRTLMode: _activeVehicle ? _activeVehicle.flightMode === _activeVehicle.rtlFlightMode : false
property bool _vehicleInLandMode: _activeVehicle ? _activeVehicle.flightMode === _activeVehicle.landFlightMode : false
property int _resumeMissionItem: missionController.resumeMissionItem
property bool _hideEmergenyStop: !QGroundControl.corePlugin.options.guidedBarShowEmergencyStop
property bool _hideOrbit: !QGroundControl.corePlugin.options.guidedBarShowOrbit
property var _actionData
// Called when an action is about to be executed in order to confirm
function confirmAction(actionCode, actionData) {
var title
var message
_actionData = actionData
switch (actionCode) {
case actionArm:
title = armTitle
message = armMessage
break;
case actionDisarm:
title = disarmTitle
message = disarmMessage
break;
case actionEmergencyStop:
title = emergencyStopTitle
message = emergencyStopMessage
break;
case actionTakeoff:
title = takeoffTitle
message = takeoffMessage
break;
case actionStartMission:
title = startMissionTitle
message = startMissionMessage
break;
case actionResumeMission:
title = resumeMissionTitle
message = resumeMissionMessage
break;
case actionResumeMissionReady:
title = resumeMissionTitle
message = resumeMissionReadyMessage
break;
case actionLand:
title = landTitle
message = landMessage
break;
case actionRTL:
title = rtlTitle
message = rtlMessage
break;
case actionChangeAlt:
title = changeAltTitle
message = changeAltMessage
break;
case actionGoto:
title = gotoTitle
message = gotoMessage
break;
case actionSetWaypoint:
title = setWaypointTitle
message = setWaypointMessage
break;
case actionOrbit:
title = orbitTitle
message = orbitMessage
break;
case actionLandAbort:
title = landAbortTitle
message = landAbortMessage
break;
case actionPause:
title = pauseTitle
message = pauseMessage
break;
}
showConfirmAction(title, message, actionCode, actionData)
}
// Executes the specified action
function executeAction(actionCode, actionData) {
switch (actionCode) {
case actionRTL:
_activeVehicle.guidedModeRTL()
break
case actionLand:
_activeVehicle.guidedModeLand()
break
case actionTakeoff:
_activeVehicle.guidedModeTakeoff()
break
case actionResumeMission:
missionController.resumeMission(missionController.resumeMissionItem)
break
case actionResumeMissionReady:
_activeVehicle.startMission()
break
case actionStartMission:
_activeVehicle.startMission()
break
case actionArm:
_activeVehicle.armed = true
break
case actionDisarm:
_activeVehicle.armed = false
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()
break
default:
console.warn(qsTr("Internal error: unknown actionCode"), actionCode)
break
}
}
}
......@@ -4,5 +4,6 @@ FlightDisplayView 1.0 FlightDisplayView.qml
FlightDisplayViewMap 1.0 FlightDisplayViewMap.qml
FlightDisplayViewVideo 1.0 FlightDisplayViewVideo.qml
FlightDisplayViewWidgets 1.0 FlightDisplayViewWidgets.qml
GuidedCommands 1.0 GuidedCommands.qml
MultiVehicleList 1.0 MultiVehicleList.qml
......@@ -364,9 +364,6 @@ void MissionSettingsItem::_setDirty(void)
void MissionSettingsItem::setCoordinate(const QGeoCoordinate& coordinate)
{
if (coordinate.isValid()) {
qDebug() << "MissionSettingsItem::setCoordinate" << coordinate.isValid();
}
if (_plannedHomePositionCoordinate != coordinate) {
_plannedHomePositionCoordinate = coordinate;
emit coordinateChanged(coordinate);
......
......@@ -11,7 +11,7 @@ Rectangle {
implicitWidth: label.contentWidth + (_diameter * 2.5) + (_border * 4)
implicitHeight: Math.max(ScreenTools.isMobile ? ScreenTools.minTouchPixels : 0, label.height * 2.5)
radius: height /2
color: qgcPal.window
color: qgcPal.text
signal accept ///< Action confirmed
signal reject ///< Action rejected
......@@ -29,6 +29,7 @@ Rectangle {
anchors.horizontalCenter: parent.horizontalCenter
anchors.verticalCenter: parent.verticalCenter
text: confirmText
color: qgcPal.window
}
Rectangle {
......
......@@ -120,7 +120,10 @@ Rectangle {
property bool checked: false
property ExclusiveGroup exclusiveGroup: dropButtonsExclusiveGroup
property var _iconSource: modelData.iconSource
QGCPalette { id: _repeaterPal; colorGroupEnabled: _buttonEnabled }
property bool _buttonEnabled: _root.buttonEnabled ? _root.buttonEnabled[index] : true
property var _iconSource: modelData.iconSource
property var _alternateIconSource: modelData.alternateIconSource
property var _source: (_root.showAlternateIcon && _root.showAlternateIcon[index]) ? _alternateIconSource : _iconSource
property bool rotateImage: _root.rotateImage ? _root.rotateImage[index] : false
......@@ -160,7 +163,7 @@ Rectangle {
anchors.left: parent.left
anchors.right: parent.right
height: width
color: checked ? qgcPal.buttonHighlight : qgcPal.button
color: checked ? _repeaterPal.buttonHighlight : _repeaterPal.button
QGCColoredImage {
id: button
......@@ -170,7 +173,7 @@ Rectangle {
fillMode: Image.PreserveAspectFit
mipmap: true
smooth: true
color: checked ? qgcPal.buttonHighlightText : qgcPal.buttonText
color: checked ? _repeaterPal.buttonHighlightText : _repeaterPal.buttonText
RotationAnimation on rotation {
id: imageRotation
......@@ -199,7 +202,7 @@ Rectangle {
anchors.right: parent.right
anchors.top: parent.top
height: parent.height + (_showOptionalElements? buttonLabel.height + buttonColumn.spacing : 0)
visible: _root.buttonEnabled ? _root.buttonEnabled[index] : true
visible: _buttonEnabled
preventStealing: true
onClicked: {
......@@ -233,6 +236,7 @@ Rectangle {
font.pointSize: ScreenTools.smallFontPointSize
text: modelData.name
visible: _showOptionalElements
enabled: _buttonEnabled
}
}
}
......
......@@ -1433,7 +1433,6 @@ void Vehicle::setActive(bool active)
QGeoCoordinate Vehicle::homePosition(void)
{
qDebug() << "Vehicle::homePosition" << _homePosition.isValid();
return _homePosition;
}
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment