Unverified Commit 63527b4c authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #7395 from DonLakeFlyer/ArduCopterPID

ArduCopter PID tuning support
parents 64eebbef 707b16d8
......@@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes.
### 3.6.0 - Daily Build
* ArduCopter: Add PID Tuning page to Tuning Setup
* ArduPilot: Copter - Advanced Tuning support
* ArduPilot: Rover - Frame setup support
* ArduPilot: Copter - Update support to 3.5+
......
......@@ -27,15 +27,12 @@ SetupPage {
Column {
width: availableWidth
spacing: _margins
FactPanelController { id: controller; factPanel: tuningPage.viewPanel }
QGCPalette { id: palette; colorGroupEnabled: true }
property bool _rcFeelAvailable: controller.parameterExists(-1, "RC_FEEL")
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 _rateRollP: controller.getParameterFact(-1, "ATC_RAT_RLL_P")
property Fact _rateRollI: controller.getParameterFact(-1, "ATC_RAT_RLL_I")
......@@ -69,6 +66,7 @@ SetupPage {
ExclusiveGroup { id: returnAltRadioGroup }
Component.onCompleted: {
showAdvanced = !ScreenTools.isMobile
// 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
// 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.
rollPitch.value = _rateRollP.value
climb.value = _rateClimbP.value
if (_rcFeelAvailable) {
rcFeel.value = _rcFeel.value
}
if (_atcInputTCAvailable) {
atcInputTC.value = _atcInputTC.value
}
......@@ -124,6 +119,12 @@ SetupPage {
Connections { target: _ch11Opt; onValueChanged: calcAutoTuneChannel() }
Connections { target: _ch12Opt; onValueChanged: calcAutoTuneChannel() }
Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margins
visible: !advanced
QGCLabel {
text: qsTr("Basic Tuning")
font.family: ScreenTools.demiboldFontFamily
......@@ -209,37 +210,6 @@ SetupPage {
}
}
Column {
anchors.left: parent.left
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
......@@ -270,30 +240,10 @@ SetupPage {
}
}
}
}
} // Rectangle - Basic tuning
QGCLabel {
text: qsTr("Advanced Tuning")
font.family: ScreenTools.demiboldFontFamily
}
Rectangle {
anchors.left: parent.left
anchors.right: parent.right
height: advColumnLayout.y + advColumnLayout.height + _margins
color: palette.windowShade
ColumnLayout {
id: advColumnLayout
anchors.margins: _margins
Column {
anchors.left: parent.left
anchors.right: parent.right
anchors.top: parent.top
spacing: _margins
Column {
Layout.fillWidth: true
QGCLabel {
text: qsTr("Spin While Armed")
......@@ -322,8 +272,8 @@ SetupPage {
}
Column {
id: lastAdvTuningColumn
Layout.fillWidth: true
anchors.left: parent.left
anchors.right: parent.right
QGCLabel {
text: qsTr("Minimum Thrust")
......@@ -331,7 +281,7 @@ SetupPage {
}
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 {
......@@ -357,12 +307,11 @@ SetupPage {
}
}
}
} // Rectangle - Advanced tuning
} // Rectangle - Basic tuning
Flow {
id: flowLayout
anchors.left: parent.left
anchors.right: parent.right
Layout.fillWidth: true
spacing: _margins
Rectangle {
......@@ -500,6 +449,35 @@ SetupPage {
} // Rectangle - Channel 6 Tuning options
} // Rectangle - Channel 6 Tuning options wrap
} // 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
} // Component
} // SetupView
......@@ -323,7 +323,7 @@ RowLayout {
}
Item { width: 1; height: 1 }
QGCLabel { text: qsTr("Saved Tuning Values:") }
QGCLabel { text: qsTr("Clipboard Values:") }
GridLayout {
rows: savedRepeater.model.length
......@@ -348,12 +348,12 @@ RowLayout {
spacing: _margins
QGCButton {
text: qsTr("Save Values")
text: qsTr("Save To Clipboard")
onClicked: saveTuningParamValues()
}
QGCButton {
text: qsTr("Reset To Saved Values")
text: qsTr("Restore From Clipboard")
onClicked: resetToSavedTuningParamValues()
}
}
......
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