Commit 566167ab authored by Don Gagne's avatar Don Gagne

Cubic relative altitude slider

parent 703c7d41
...@@ -21,18 +21,27 @@ Rectangle { ...@@ -21,18 +21,27 @@ Rectangle {
readonly property real _maxAlt: 121.92 // 400 feet readonly property real _maxAlt: 121.92 // 400 feet
readonly property real _minAlt: 3 readonly property real _minAlt: 3
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property var _guidedSettings: QGroundControl.settingsManager.guidedSettings
property real _vehicleAltitude: _activeVehicle ? _activeVehicle.altitudeRelative.rawValue : 0 property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _fixedWing: _activeVehicle ? _activeVehicle.fixedWing : false property real _vehicleAltitude: _activeVehicle ? _activeVehicle.altitudeRelative.rawValue : 0
property real _sliderMaxAlt: _fixedWing ? _maxAlt : Math.min(_vehicleAltitude + 10, _maxAlt) property bool _fixedWing: _activeVehicle ? _activeVehicle.fixedWing : false
property real _sliderMinAlt: _fixedWing ? _minAlt : Math.max(_vehicleAltitude - 10, _minAlt) property real _sliderMaxAlt: _fixedWing ? _guidedSettings.fixedWingMaximumAltitude.value : _guidedSettings.vehicleMaximumAltitude.value
property real _sliderMinAlt: _fixedWing ? _guidedSettings.fixedWingMinimumAltitude.value : _guidedSettings.vehicleMinimumAltitude.value
function reset() { function reset() {
altSlider.value = Math.min(Math.max(altSlider.minimumValue, 0), altSlider.maximumValue) altSlider.value = 0
} }
function getValue() { function getValue() {
return altSlider.value return altField.newAltitude - _vehicleAltitude
}
function log10(value) {
if (value === 0) {
return 0
} else {
return Math.log(value) / Math.LN10
}
} }
Column { Column {
...@@ -55,7 +64,11 @@ Rectangle { ...@@ -55,7 +64,11 @@ Rectangle {
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
text: Math.abs(newAltitude.toFixed(1)) + " " + QGroundControl.appSettingsDistanceUnitsString text: Math.abs(newAltitude.toFixed(1)) + " " + QGroundControl.appSettingsDistanceUnitsString
property real newAltitude: QGroundControl.metersToAppSettingsDistanceUnits(_root._vehicleAltitude + altSlider.value).toFixed(1) property real altGainRange: Math.max(_sliderMaxAlt - _vehicleAltitude, 0)
property real altLossRange: Math.max(_vehicleAltitude - _sliderMinAlt, 0)
property real altExp: Math.pow(altSlider.value, 3)
property real altLossGain: altExp * (altSlider.value > 0 ? altGainRange : altLossRange)
property real newAltitude: _vehicleAltitude + altLossGain // QGroundControl.metersToAppSettingsDistanceUnits(_root._vehicleAltitude + altSlider.value).toFixed(1)
} }
} }
...@@ -67,9 +80,9 @@ Rectangle { ...@@ -67,9 +80,9 @@ Rectangle {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
orientation: Qt.Vertical orientation: Qt.Vertical
minimumValue: _root._sliderMinAlt - _root._vehicleAltitude minimumValue: -1
maximumValue: _root._sliderMaxAlt - _root._vehicleAltitude maximumValue: 1
zeroCentered: true zeroCentered: true
rotation: 180 rotation: 180
// We want slide up to be positive values // We want slide up to be positive values
......
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