Browse Source

PX4 MC PID tuning page: remove hover+throttle sliders & make advanced the default

PX4 has hover thrust estimation.
QGC4.4
Beat Küng 4 years ago committed by Lorenz Meier
parent
commit
a000653e39
  1. 185
      src/AutoPilotPlugins/PX4/PX4TuningComponentCopter.qml
  2. 86
      src/QmlControls/PIDTuning.qml

185
src/AutoPilotPlugins/PX4/PX4TuningComponentCopter.qml

@ -28,132 +28,91 @@ SetupPage { @@ -28,132 +28,91 @@ SetupPage {
Column {
width: availableWidth
Component.onCompleted: {
// We use QtCharts only on Desktop platforms
showAdvanced = !ScreenTools.isMobile
}
FactPanelController {
id: controller
}
// Standard tuning page
FactSliderPanel {
width: availableWidth
visible: !advanced
sliderModel: ListModel {
PIDTuning {
width: availableWidth
property var rollList: ListModel {
ListElement {
title: qsTr("Hover Throttle")
description: qsTr("Adjust throttle so hover is at mid-throttle. Slide to the left if hover is lower than throttle center. Slide to the right if hover is higher than throttle center.")
param: "MPC_THR_HOVER"
min: 20
max: 80
step: 1
title: qsTr("Overall Multiplier (MC_ROLLRATE_K)")
description: qsTr("Multiplier for P, I and D gains: increase for more responsiveness, reduce if the rates overshoot (and increasing D does not help).")
param: "MC_ROLLRATE_K"
min: 0.3
max: 3
step: 0.05
}
ListElement {
title: qsTr("Differential Gain (MC_ROLLRATE_D)")
description: qsTr("Damping: increase to reduce overshoots and oscillations, but not higher than really needed.")
param: "MC_ROLLRATE_D"
min: 0.0004
max: 0.01
step: 0.0002
}
ListElement {
title: qsTr("Manual minimum throttle")
description: qsTr("Slide to the left to start the motors with less idle power. Slide to the right if descending in manual flight becomes unstable.")
param: "MPC_MANTHR_MIN"
min: 0
max: 15
step: 1
title: qsTr("Integral Gain (MC_ROLLRATE_I)")
description: qsTr("Generally does not need much adjustment, reduce this when seeing slow oscillations.")
param: "MC_ROLLRATE_I"
min: 0.1
max: 0.5
step: 0.025
}
}
}
Loader {
anchors.left: parent.left
anchors.right: parent.right
sourceComponent: advanced ? advancePageComponent : undefined
}
Component {
id: advancePageComponent
PIDTuning {
property var rollList: ListModel {
ListElement {
title: qsTr("Overall Multiplier (MC_ROLLRATE_K)")
description: qsTr("Multiplier for P, I and D gains: increase for more responsiveness, reduce if the rates overshoot (and increasing D does not help).")
param: "MC_ROLLRATE_K"
min: 0.3
max: 3
step: 0.05
}
ListElement {
title: qsTr("Differential Gain (MC_ROLLRATE_D)")
description: qsTr("Damping: increase to reduce overshoots and oscillations, but not higher than really needed.")
param: "MC_ROLLRATE_D"
min: 0.0004
max: 0.01
step: 0.0002
}
ListElement {
title: qsTr("Integral Gain (MC_ROLLRATE_I)")
description: qsTr("Generally does not need much adjustment, reduce this when seeing slow oscillations.")
param: "MC_ROLLRATE_I"
min: 0.1
max: 0.5
step: 0.025
}
property var pitchList: ListModel {
ListElement {
title: qsTr("Overall Multiplier (MC_PITCHRATE_K)")
description: qsTr("Multiplier for P, I and D gains: increase for more responsiveness, reduce if the rates overshoot (and increasing D does not help).")
param: "MC_PITCHRATE_K"
min: 0.3
max: 3
step: 0.05
}
ListElement {
title: qsTr("Differential Gain (MC_PITCHRATE_D)")
description: qsTr("Damping: increase to reduce overshoots and oscillations, but not higher than really needed.")
param: "MC_PITCHRATE_D"
min: 0.0004
max: 0.01
step: 0.0002
}
ListElement {
title: qsTr("Integral Gain (MC_PITCHRATE_I)")
description: qsTr("Generally does not need much adjustment, reduce this when seeing slow oscillations.")
param: "MC_PITCHRATE_I"
min: 0.1
max: 0.5
step: 0.025
}
property var pitchList: ListModel {
ListElement {
title: qsTr("Overall Multiplier (MC_PITCHRATE_K)")
description: qsTr("Multiplier for P, I and D gains: increase for more responsiveness, reduce if the rates overshoot (and increasing D does not help).")
param: "MC_PITCHRATE_K"
min: 0.3
max: 3
step: 0.05
}
ListElement {
title: qsTr("Differential Gain (MC_PITCHRATE_D)")
description: qsTr("Damping: increase to reduce overshoots and oscillations, but not higher than really needed.")
param: "MC_PITCHRATE_D"
min: 0.0004
max: 0.01
step: 0.0002
}
ListElement {
title: qsTr("Integral Gain (MC_PITCHRATE_I)")
description: qsTr("Generally does not need much adjustment, reduce this when seeing slow oscillations.")
param: "MC_PITCHRATE_I"
min: 0.1
max: 0.5
step: 0.025
}
}
property var yawList: ListModel {
ListElement {
title: qsTr("Overall Multiplier (MC_YAWRATE_K)")
description: qsTr("Multiplier for P, I and D gains: increase for more responsiveness, reduce if the rates overshoot (and increasing D does not help).")
param: "MC_YAWRATE_K"
min: 0.3
max: 3
step: 0.05
}
property var yawList: ListModel {
ListElement {
title: qsTr("Overall Multiplier (MC_YAWRATE_K)")
description: qsTr("Multiplier for P, I and D gains: increase for more responsiveness, reduce if the rates overshoot (and increasing D does not help).")
param: "MC_YAWRATE_K"
min: 0.3
max: 3
step: 0.05
}
ListElement {
title: qsTr("Integral Gain (MC_YAWRATE_I)")
description: qsTr("Generally does not need much adjustment, reduce this when seeing slow oscillations.")
param: "MC_YAWRATE_I"
min: 0.04
max: 0.4
step: 0.02
}
ListElement {
title: qsTr("Integral Gain (MC_YAWRATE_I)")
description: qsTr("Generally does not need much adjustment, reduce this when seeing slow oscillations.")
param: "MC_YAWRATE_I"
min: 0.04
max: 0.4
step: 0.02
}
anchors.left: parent.left
anchors.right: parent.right
tuneList: [ qsTr("Roll"), qsTr("Pitch"), qsTr("Yaw") ]
params: [
rollList,
pitchList,
yawList
]
}
} // Component - Advanced Page
anchors.left: parent.left
anchors.right: parent.right
tuneList: [ qsTr("Roll"), qsTr("Pitch"), qsTr("Yaw") ]
params: [
rollList,
pitchList,
yawList
]
}
} // Column
} // Component - pageComponent
} // SetupPage

86
src/QmlControls/PIDTuning.qml

@ -38,6 +38,7 @@ RowLayout { @@ -38,6 +38,7 @@ RowLayout {
property int _msecs: 0
property double _last_t: 0
property var _savedTuningParamValues: [ ]
property bool _showCharts: !ScreenTools.isMobile // TODO: test and enable on mobile
// The following are set when getValues is called
property real _valueRate
@ -190,7 +191,7 @@ RowLayout { @@ -190,7 +191,7 @@ RowLayout {
Column {
spacing: _margins
Layout.alignment: Qt.AlignTop
width: parent.width * 0.4
width: parent.width * (_showCharts ? 0.4 : 1)
Column {
QGCLabel { text: qsTr("Tuning Axis:") }
@ -267,53 +268,12 @@ RowLayout { @@ -267,53 +268,12 @@ RowLayout {
onClicked: resetToSavedTuningParamValues()
}
}
Item { width: 1; height: 1 }
QGCLabel { text: qsTr("Chart:") }
RowLayout {
spacing: _margins
QGCButton {
text: qsTr("Clear")
onClicked: resetGraphs()
}
QGCButton {
text: dataTimer.running ? qsTr("Stop") : qsTr("Start")
onClicked: {
dataTimer.running = !dataTimer.running
_last_t = 0
if (autoModeChange.checked) {
globals.activeVehicle.flightMode = dataTimer.running ? "Stabilized" : globals.activeVehicle.pauseFlightMode
}
}
}
}
QGCCheckBox {
id: autoModeChange
text: qsTr("Automatic Flight Mode Switching")
}
Column {
visible: autoModeChange.checked
QGCLabel {
text: qsTr("Switches to 'Stabilized' when you click Start.")
font.pointSize: ScreenTools.smallFontPointSize
}
QGCLabel {
text: qsTr("Switches to '%1' when you click Stop.").arg(globals.activeVehicle.pauseFlightMode)
font.pointSize: ScreenTools.smallFontPointSize
}
}
}
Column {
Layout.fillWidth: true
Layout.alignment: Qt.AlignTop
visible: _showCharts
ChartView {
id: ratesChart
@ -365,5 +325,45 @@ RowLayout { @@ -365,5 +325,45 @@ RowLayout {
}
}
}
Item { width: 1; height: 1 }
RowLayout {
spacing: _margins
QGCButton {
text: qsTr("Clear")
onClicked: resetGraphs()
}
QGCButton {
text: dataTimer.running ? qsTr("Stop") : qsTr("Start")
onClicked: {
dataTimer.running = !dataTimer.running
_last_t = 0
if (autoModeChange.checked) {
globals.activeVehicle.flightMode = dataTimer.running ? "Stabilized" : globals.activeVehicle.pauseFlightMode
}
}
}
}
QGCCheckBox {
id: autoModeChange
text: qsTr("Automatic Flight Mode Switching")
}
Column {
visible: autoModeChange.checked
QGCLabel {
text: qsTr("Switches to 'Stabilized' when you click Start.")
font.pointSize: ScreenTools.smallFontPointSize
}
QGCLabel {
text: qsTr("Switches to '%1' when you click Stop.").arg(globals.activeVehicle.pauseFlightMode)
font.pointSize: ScreenTools.smallFontPointSize
}
}
}
} // RowLayout

Loading…
Cancel
Save