diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index bfcbdcf..d8363b2 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -129,6 +129,7 @@
src/FlightDisplay/FlightDisplayViewVideo.qml
src/FlightDisplay/FlightDisplayViewWidgets.qml
src/FlightDisplay/GuidedActionsController.qml
+ src/FlightDisplay/GuidedAltitudeSlider.qml
src/FlightDisplay/MultiVehicleList.qml
src/FlightDisplay/qmldir
src/FlightMap/Widgets/CenterMapDropButton.qml
diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
index 9ab17eb..2fb2b2a 100644
--- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
+++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
@@ -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;
diff --git a/src/FlightDisplay/FlightDisplayView.qml b/src/FlightDisplay/FlightDisplayView.qml
index d76c503..bee4184 100644
--- a/src/FlightDisplay/FlightDisplayView.qml
+++ b/src/FlightDisplay/FlightDisplayView.qml
@@ -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
- }
- }
}
}
}
diff --git a/src/FlightDisplay/GuidedAltitudeSlider.qml b/src/FlightDisplay/GuidedAltitudeSlider.qml
new file mode 100644
index 0000000..feafee1
--- /dev/null
+++ b/src/FlightDisplay/GuidedAltitudeSlider.qml
@@ -0,0 +1,82 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * 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
+ }
+ }
+}
diff --git a/src/FlightDisplay/qmldir b/src/FlightDisplay/qmldir
index ebe28ee..a1015a2 100644
--- a/src/FlightDisplay/qmldir
+++ b/src/FlightDisplay/qmldir
@@ -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
diff --git a/src/QmlControls/QGCSlider.qml b/src/QmlControls/QGCSlider.qml
index 4df568b..ff317b1 100644
--- a/src/QmlControls/QGCSlider.qml
+++ b/src/QmlControls/QGCSlider.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