Commit 2db30a14 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #4964 from DonLakeFlyer/AltSlider

Usability changes to guided altitude slider
parents ae16fc1f cc905caa
......@@ -129,6 +129,7 @@
<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/GuidedAltitudeSlider.qml">src/FlightDisplay/GuidedAltitudeSlider.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>
......
......@@ -179,6 +179,8 @@ void ArduCopterFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double
altitudeChange = 3 - currentAltRel;
}
setGuidedMode(vehicle, true);
mavlink_message_t msg;
mavlink_set_position_target_local_ned_t cmd;
......
......@@ -619,6 +619,7 @@ QGCView {
onClicked: {
if (modelData.action === guidedController.actionChangeAlt) {
altitudeSlider.reset()
altitudeSlider.visible = true
}
guidedActionList.visible = false
......@@ -650,7 +651,7 @@ QGCView {
}
//-- Altitude slider
Rectangle {
GuidedAltitudeSlider {
id: altitudeSlider
anchors.margins: _margins
anchors.right: parent.right
......@@ -662,54 +663,6 @@ QGCView {
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
}
}
}
}
}
/****************************************************************************
*
* (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 QGroundControl 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Vehicle 1.0
/// Altitude slider for guided change altitude command
Rectangle {
id: _root
readonly property real _maxAlt: 121.92 // 400 feet
readonly property real _minAlt: 3
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property real _vehicleAltitude: _activeVehicle ? _activeVehicle.altitudeRelative.rawValue : 0
property bool _fixedWing: _activeVehicle ? _activeVehicle.fixedWing : false
property real _sliderMaxAlt: _fixedWing ? _maxAlt : Math.min(_vehicleAltitude + 10, _maxAlt)
property real _sliderMinAlt: _fixedWing ? _minAlt : Math.max(_vehicleAltitude - 10, _minAlt)
function reset() {
altSlider.value = Math.min(Math.max(altSlider.minimumValue, 0), altSlider.maximumValue)
}
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.left: parent.left
anchors.right: parent.right
wrapMode: Text.WordWrap
horizontalAlignment: Text.AlignHCenter
text: qsTr("New Alt(rel)")
}
QGCLabel {
id: altField
anchors.horizontalCenter: parent.horizontalCenter
text: Math.abs(newAltitude.toFixed(1)) + " " + QGroundControl.appSettingsDistanceUnitsString
property real newAltitude: QGroundControl.metersToAppSettingsDistanceUnits(_root._vehicleAltitude + altSlider.value).toFixed(1)
}
}
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: _root._sliderMinAlt - _root._vehicleAltitude
maximumValue: _root._sliderMaxAlt - _root._vehicleAltitude
zeroCentered: 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
}
}
}
......@@ -4,6 +4,7 @@ FlightDisplayView 1.0 FlightDisplayView.qml
FlightDisplayViewMap 1.0 FlightDisplayViewMap.qml
FlightDisplayViewVideo 1.0 FlightDisplayViewVideo.qml
FlightDisplayViewWidgets 1.0 FlightDisplayViewWidgets.qml
GuidedAltitudeSlider 1.0 GuidedAltitudeSlider.qml
GuidedCommands 1.0 GuidedCommands.qml
MultiVehicleList 1.0 MultiVehicleList.qml
......@@ -19,8 +19,8 @@ Slider {
id: _root
implicitHeight: ScreenTools.implicitSliderHeight
// Value indicator starts display from center instead of min value
property bool indicatorCentered: false
// Value indicator starts display from zero instead of min value
property bool zeroCentered: false
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
......@@ -39,14 +39,16 @@ Slider {
}
Item {
id: indicatorBar
clip: true
x: _root.indicatorCentered ? indicatorCenteredIndicatorStart : 0
width: _root.indicatorCentered ? centerIndicatorWidth : styleData.handlePosition
x: _root.zeroCentered ? zeroCenteredIndicatorStart : 0
width: _root.zeroCentered ? centerIndicatorWidth : styleData.handlePosition
height: parent.height
property real indicatorCenteredIndicatorStart: Math.min(styleData.handlePosition, parent.width / 2)
property real indicatorCenteredIndicatorStop: Math.max(styleData.handlePosition, parent.width / 2)
property real centerIndicatorWidth: indicatorCenteredIndicatorStop - indicatorCenteredIndicatorStart
property real zeroValuePosition: (Math.abs(control.minimumValue) / (control.maximumValue - control.minimumValue)) * parent.width
property real zeroCenteredIndicatorStart: Math.min(styleData.handlePosition, zeroValuePosition)
property real zeroCenteredIndicatorStop: Math.max(styleData.handlePosition, zeroValuePosition)
property real centerIndicatorWidth: zeroCenteredIndicatorStop - zeroCenteredIndicatorStart
Rectangle {
anchors.fill: parent
......
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