|
|
@ -27,15 +27,12 @@ SetupPage { |
|
|
|
|
|
|
|
|
|
|
|
Column { |
|
|
|
Column { |
|
|
|
width: availableWidth |
|
|
|
width: availableWidth |
|
|
|
spacing: _margins |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
FactPanelController { id: controller; factPanel: tuningPage.viewPanel } |
|
|
|
FactPanelController { id: controller; factPanel: tuningPage.viewPanel } |
|
|
|
|
|
|
|
|
|
|
|
QGCPalette { id: palette; colorGroupEnabled: true } |
|
|
|
QGCPalette { id: palette; colorGroupEnabled: true } |
|
|
|
|
|
|
|
|
|
|
|
property bool _rcFeelAvailable: controller.parameterExists(-1, "RC_FEEL") |
|
|
|
|
|
|
|
property bool _atcInputTCAvailable: controller.parameterExists(-1, "ATC_INPUT_TC") |
|
|
|
property bool _atcInputTCAvailable: controller.parameterExists(-1, "ATC_INPUT_TC") |
|
|
|
property Fact _rcFeel: controller.getParameterFact(-1, "RC_FEEL", false) |
|
|
|
|
|
|
|
property Fact _atcInputTC: controller.getParameterFact(-1, "ATC_INPUT_TC", false) |
|
|
|
property Fact _atcInputTC: controller.getParameterFact(-1, "ATC_INPUT_TC", false) |
|
|
|
property Fact _rateRollP: controller.getParameterFact(-1, "ATC_RAT_RLL_P") |
|
|
|
property Fact _rateRollP: controller.getParameterFact(-1, "ATC_RAT_RLL_P") |
|
|
|
property Fact _rateRollI: controller.getParameterFact(-1, "ATC_RAT_RLL_I") |
|
|
|
property Fact _rateRollI: controller.getParameterFact(-1, "ATC_RAT_RLL_I") |
|
|
@ -69,6 +66,7 @@ SetupPage { |
|
|
|
ExclusiveGroup { id: returnAltRadioGroup } |
|
|
|
ExclusiveGroup { id: returnAltRadioGroup } |
|
|
|
|
|
|
|
|
|
|
|
Component.onCompleted: { |
|
|
|
Component.onCompleted: { |
|
|
|
|
|
|
|
showAdvanced = !ScreenTools.isMobile |
|
|
|
// Qml Sliders have a strange behavior in which they first set Slider::value to some internal |
|
|
|
// Qml Sliders have a strange behavior in which they first set Slider::value to some internal |
|
|
|
// setting and then set Slider::value to the bound properties value. If you have an onValueChanged |
|
|
|
// setting and then set Slider::value to the bound properties value. If you have an onValueChanged |
|
|
|
// handler which updates your property with the new value, this first value change will trash |
|
|
|
// handler which updates your property with the new value, this first value change will trash |
|
|
@ -76,9 +74,6 @@ SetupPage { |
|
|
|
// after Qml load is done. We also don't track value changes until Qml load completes. |
|
|
|
// after Qml load is done. We also don't track value changes until Qml load completes. |
|
|
|
rollPitch.value = _rateRollP.value |
|
|
|
rollPitch.value = _rateRollP.value |
|
|
|
climb.value = _rateClimbP.value |
|
|
|
climb.value = _rateClimbP.value |
|
|
|
if (_rcFeelAvailable) { |
|
|
|
|
|
|
|
rcFeel.value = _rcFeel.value |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
if (_atcInputTCAvailable) { |
|
|
|
if (_atcInputTCAvailable) { |
|
|
|
atcInputTC.value = _atcInputTC.value |
|
|
|
atcInputTC.value = _atcInputTC.value |
|
|
|
} |
|
|
|
} |
|
|
@ -124,6 +119,12 @@ SetupPage { |
|
|
|
Connections { target: _ch11Opt; onValueChanged: calcAutoTuneChannel() } |
|
|
|
Connections { target: _ch11Opt; onValueChanged: calcAutoTuneChannel() } |
|
|
|
Connections { target: _ch12Opt; onValueChanged: calcAutoTuneChannel() } |
|
|
|
Connections { target: _ch12Opt; onValueChanged: calcAutoTuneChannel() } |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
Column { |
|
|
|
|
|
|
|
anchors.left: parent.left |
|
|
|
|
|
|
|
anchors.right: parent.right |
|
|
|
|
|
|
|
spacing: _margins |
|
|
|
|
|
|
|
visible: !advanced |
|
|
|
|
|
|
|
|
|
|
|
QGCLabel { |
|
|
|
QGCLabel { |
|
|
|
text: qsTr("Basic Tuning") |
|
|
|
text: qsTr("Basic Tuning") |
|
|
|
font.family: ScreenTools.demiboldFontFamily |
|
|
|
font.family: ScreenTools.demiboldFontFamily |
|
|
@ -212,37 +213,6 @@ SetupPage { |
|
|
|
Column { |
|
|
|
Column { |
|
|
|
anchors.left: parent.left |
|
|
|
anchors.left: parent.left |
|
|
|
anchors.right: parent.right |
|
|
|
anchors.right: parent.right |
|
|
|
visible: _rcFeelAvailable |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
QGCLabel { |
|
|
|
|
|
|
|
text: qsTr("RC Roll/Pitch Feel") |
|
|
|
|
|
|
|
font.family: ScreenTools.demiboldFontFamily |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
QGCLabel { |
|
|
|
|
|
|
|
text: qsTr("Slide to the left for soft control, slide to the right for crisp control") |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
Slider { |
|
|
|
|
|
|
|
id: rcFeel |
|
|
|
|
|
|
|
anchors.left: parent.left |
|
|
|
|
|
|
|
anchors.right: parent.right |
|
|
|
|
|
|
|
minimumValue: 0 |
|
|
|
|
|
|
|
maximumValue: 100 |
|
|
|
|
|
|
|
stepSize: 5.0 |
|
|
|
|
|
|
|
tickmarksEnabled: true |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
onValueChanged: { |
|
|
|
|
|
|
|
if (_loadComplete) { |
|
|
|
|
|
|
|
_rcFeel.value = value |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
Column { |
|
|
|
|
|
|
|
anchors.left: parent.left |
|
|
|
|
|
|
|
anchors.right: parent.right |
|
|
|
|
|
|
|
visible: _atcInputTCAvailable |
|
|
|
visible: _atcInputTCAvailable |
|
|
|
|
|
|
|
|
|
|
|
QGCLabel { |
|
|
|
QGCLabel { |
|
|
@ -270,30 +240,10 @@ SetupPage { |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
} // Rectangle - Basic tuning |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
QGCLabel { |
|
|
|
|
|
|
|
text: qsTr("Advanced Tuning") |
|
|
|
|
|
|
|
font.family: ScreenTools.demiboldFontFamily |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
Rectangle { |
|
|
|
Column { |
|
|
|
anchors.left: parent.left |
|
|
|
|
|
|
|
anchors.right: parent.right |
|
|
|
|
|
|
|
height: advColumnLayout.y + advColumnLayout.height + _margins |
|
|
|
|
|
|
|
color: palette.windowShade |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
ColumnLayout { |
|
|
|
|
|
|
|
id: advColumnLayout |
|
|
|
|
|
|
|
anchors.margins: _margins |
|
|
|
|
|
|
|
anchors.left: parent.left |
|
|
|
anchors.left: parent.left |
|
|
|
anchors.right: parent.right |
|
|
|
anchors.right: parent.right |
|
|
|
anchors.top: parent.top |
|
|
|
|
|
|
|
spacing: _margins |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
Column { |
|
|
|
|
|
|
|
Layout.fillWidth: true |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
QGCLabel { |
|
|
|
QGCLabel { |
|
|
|
text: qsTr("Spin While Armed") |
|
|
|
text: qsTr("Spin While Armed") |
|
|
@ -322,8 +272,8 @@ SetupPage { |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
Column { |
|
|
|
Column { |
|
|
|
id: lastAdvTuningColumn |
|
|
|
anchors.left: parent.left |
|
|
|
Layout.fillWidth: true |
|
|
|
anchors.right: parent.right |
|
|
|
|
|
|
|
|
|
|
|
QGCLabel { |
|
|
|
QGCLabel { |
|
|
|
text: qsTr("Minimum Thrust") |
|
|
|
text: qsTr("Minimum Thrust") |
|
|
@ -331,7 +281,7 @@ SetupPage { |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
QGCLabel { |
|
|
|
QGCLabel { |
|
|
|
text: qsTr("Adjust the minimum amount of thrust for a stable minimum throttle descent") |
|
|
|
text: qsTr("Adjust the minimum amount of thrust require for the vehicle to move") |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
QGCLabel { |
|
|
|
QGCLabel { |
|
|
@ -357,12 +307,11 @@ SetupPage { |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} // Rectangle - Advanced tuning |
|
|
|
} // Rectangle - Basic tuning |
|
|
|
|
|
|
|
|
|
|
|
Flow { |
|
|
|
Flow { |
|
|
|
id: flowLayout |
|
|
|
id: flowLayout |
|
|
|
anchors.left: parent.left |
|
|
|
Layout.fillWidth: true |
|
|
|
anchors.right: parent.right |
|
|
|
|
|
|
|
spacing: _margins |
|
|
|
spacing: _margins |
|
|
|
|
|
|
|
|
|
|
|
Rectangle { |
|
|
|
Rectangle { |
|
|
@ -500,6 +449,35 @@ SetupPage { |
|
|
|
} // Rectangle - Channel 6 Tuning options |
|
|
|
} // Rectangle - Channel 6 Tuning options |
|
|
|
} // Rectangle - Channel 6 Tuning options wrap |
|
|
|
} // Rectangle - Channel 6 Tuning options wrap |
|
|
|
} // Flow - Tune |
|
|
|
} // Flow - Tune |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
Loader { |
|
|
|
|
|
|
|
anchors.left: parent.left |
|
|
|
|
|
|
|
anchors.right: parent.right |
|
|
|
|
|
|
|
sourceComponent: advanced ? advancePageComponent : undefined |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
Component { |
|
|
|
|
|
|
|
id: advancePageComponent |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
PIDTuning { |
|
|
|
|
|
|
|
anchors.left: parent.left |
|
|
|
|
|
|
|
anchors.right: parent.right |
|
|
|
|
|
|
|
tuneList: [ qsTr("Roll"), qsTr("Pitch"), qsTr("Yaw") ] |
|
|
|
|
|
|
|
params: [ |
|
|
|
|
|
|
|
[ controller.getParameterFact(-1, "ATC_ANG_RLL_P"), |
|
|
|
|
|
|
|
controller.getParameterFact(-1, "ATC_RAT_RLL_P"), |
|
|
|
|
|
|
|
controller.getParameterFact(-1, "ATC_RAT_RLL_I"), |
|
|
|
|
|
|
|
controller.getParameterFact(-1, "ATC_RAT_RLL_D") ], |
|
|
|
|
|
|
|
[ controller.getParameterFact(-1, "ATC_ANG_PIT_P"), |
|
|
|
|
|
|
|
controller.getParameterFact(-1, "ATC_RAT_PIT_P"), |
|
|
|
|
|
|
|
controller.getParameterFact(-1, "ATC_RAT_PIT_I"), |
|
|
|
|
|
|
|
controller.getParameterFact(-1, "ATC_RAT_PIT_D") ], |
|
|
|
|
|
|
|
[ controller.getParameterFact(-1, "ATC_ANG_YAW_P"), |
|
|
|
|
|
|
|
controller.getParameterFact(-1, "ATC_RAT_YAW_P"), |
|
|
|
|
|
|
|
controller.getParameterFact(-1, "ATC_RAT_YAW_I") ] ] |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} // Component - Advanced Page |
|
|
|
} // Column |
|
|
|
} // Column |
|
|
|
} // Component |
|
|
|
} // Component |
|
|
|
} // SetupView |
|
|
|
} // SetupView |
|
|
|