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
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
/****************************************************************************
*
* (c) 2009-2020 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 _flyViewSettings: QGroundControl.settingsManager.flyViewSettings
property real _vehicleAltitude: activeVehicle ? activeVehicle.altitudeRelative.rawValue : 0
property bool _fixedWing: activeVehicle ? activeVehicle.fixedWing : false
property real _sliderMaxAlt: _flyViewSettings ? _flyViewSettings.guidedMaximumAltitude.rawValue : 0
property real _sliderMinAlt: _flyViewSettings ? _flyViewSettings.guidedMinimumAltitude.rawValue : 0
property bool _flying: activeVehicle ? activeVehicle.flying : false
function reset() {
altSlider.value = 0
}
function setToMinimumTakeoff() {
altField.setToMinimumTakeoff()
}
/// Returns the user specified change in altitude from the current vehicle altitude
function getAltitudeChangeValue() {
return altField.newAltitudeMeters - _vehicleAltitude
}
function log10(value) {
if (value === 0) {
return 0
} else {
return Math.log(value) / Math.LN10
}
}
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: newAltitudeAppUnits + " " + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString
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 newAltitudeMeters: _vehicleAltitude + altLossGain
property string newAltitudeAppUnits: QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(newAltitudeMeters).toFixed(1)
function setToMinimumTakeoff() {
altSlider.value = Math.pow(activeVehicle.minimumTakeoffAltitude() / altGainRange, 1.0/3.0)
}
}
}
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: _flying ? -1 : 0
maximumValue: 1
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
}
}
}