QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
PX4TuningComponentCopterRate.qml
Go to the documentation of this file.
1import QtQuick
2import QtQuick.Controls
3import QtQuick.Layouts
4
5import QGroundControl
6import QGroundControl.Controls
7import QGroundControl.FactControls
8
9ColumnLayout {
10 property real _availableHeight: availableHeight
11 property real _availableWidth: availableWidth
12 property Fact _airmode: controller.getParameterFact(-1, "MC_AIRMODE", false)
13 property Fact _thrustModelFactor: controller.getParameterFact(-1, "THR_MDL_FAC", false)
14
15 RowLayout {
16 spacing: ScreenTools.defaultFontPixelWidth
17
18 QGCLabel {
19 textFormat: Text.RichText
20 text: qsTr("Airmode (disable during tuning) <b><a href=\"https://docs.px4.io/main/en/config_mc/pid_tuning_guide_multicopter.html#airmode-mixer-saturation\">?</a></b>")
21 onLinkActivated: (link) => Qt.openUrlExternally(link)
22 visible: _airmode
23 }
24 FactComboBox {
25 fact: _airmode
26 indexModel: false
27 visible: _airmode
28 }
29
30 Item {
31 width: 1
32 height: 1
33 }
34
35 QGCLabel {
36 textFormat: Text.RichText
37 text: qsTr("Thrust curve <b><a href=\"https://docs.px4.io/main/en/config_mc/pid_tuning_guide_multicopter.html#thrust-curve\">?</a></b>")
38 onLinkActivated: (link) => Qt.openUrlExternally(link)
39 visible: _thrustModelFactor
40 }
41 FactTextField {
42 fact: _thrustModelFactor
43 visible: _thrustModelFactor
44 }
45 }
46
47 PIDTuning {
48 id: pidTuning
49 availableWidth: _availableWidth
50 availableHeight: _availableHeight - pidTuning.y
51 title: qsTr("Rate")
52 tuningMode: Vehicle.ModeRateAndAttitude
53 unit: qsTr("deg/s")
54 axis: [ roll, pitch, yaw ]
55 chartDisplaySec: 3
56 showAutoModeChange: true
57 showAutoTuning: true
58
59 property var roll: QtObject {
60 property string name: qsTr("Roll")
61 property var plot: [
62 { name: "Response", value: globals.activeVehicle.rollRate.value },
63 { name: "Setpoint", value: globals.activeVehicle.setpoint.rollRate.value }
64 ]
65 property var params: ListModel {
66 ListElement {
67 title: qsTr("Overall Multiplier (MC_ROLLRATE_K)")
68 description: qsTr("Multiplier for P, I and D gains: increase for more responsiveness, reduce if the rates overshoot (and increasing D does not help).")
69 param: "MC_ROLLRATE_K"
70 min: 0.3
71 max: 3
72 step: 0.05
73 }
74 ListElement {
75 title: qsTr("Differential Gain (MC_ROLLRATE_D)")
76 description: qsTr("Damping: increase to reduce overshoots and oscillations, but not higher than really needed.")
77 param: "MC_ROLLRATE_D"
78 min: 0.0004
79 max: 0.01
80 step: 0.0002
81 }
82 ListElement {
83 title: qsTr("Integral Gain (MC_ROLLRATE_I)")
84 description: qsTr("Generally does not need much adjustment, reduce this when seeing slow oscillations.")
85 param: "MC_ROLLRATE_I"
86 min: 0.1
87 max: 0.5
88 step: 0.025
89 }
90 }
91 }
92 property var pitch: QtObject {
93 property string name: qsTr("Pitch")
94 property var plot: [
95 { name: "Response", value: globals.activeVehicle.pitchRate.value },
96 { name: "Setpoint", value: globals.activeVehicle.setpoint.pitchRate.value }
97 ]
98 property var params: ListModel {
99 ListElement {
100 title: qsTr("Overall Multiplier (MC_PITCHRATE_K)")
101 description: qsTr("Multiplier for P, I and D gains: increase for more responsiveness, reduce if the rates overshoot (and increasing D does not help).")
102 param: "MC_PITCHRATE_K"
103 min: 0.3
104 max: 3
105 step: 0.05
106 }
107 ListElement {
108 title: qsTr("Differential Gain (MC_PITCHRATE_D)")
109 description: qsTr("Damping: increase to reduce overshoots and oscillations, but not higher than really needed.")
110 param: "MC_PITCHRATE_D"
111 min: 0.0004
112 max: 0.01
113 step: 0.0002
114 }
115 ListElement {
116 title: qsTr("Integral Gain (MC_PITCHRATE_I)")
117 description: qsTr("Generally does not need much adjustment, reduce this when seeing slow oscillations.")
118 param: "MC_PITCHRATE_I"
119 min: 0.1
120 max: 0.5
121 step: 0.025
122 }
123 }
124 }
125 property var yaw: QtObject {
126 property string name: qsTr("Yaw")
127 property var plot: [
128 { name: "Response", value: globals.activeVehicle.yawRate.value },
129 { name: "Setpoint", value: globals.activeVehicle.setpoint.yawRate.value }
130 ]
131 property var params: ListModel {
132 ListElement {
133 title: qsTr("Overall Multiplier (MC_YAWRATE_K)")
134 description: qsTr("Multiplier for P, I and D gains: increase for more responsiveness, reduce if the rates overshoot (and increasing D does not help).")
135 param: "MC_YAWRATE_K"
136 min: 0.3
137 max: 3
138 step: 0.05
139 }
140 ListElement {
141 title: qsTr("Integral Gain (MC_YAWRATE_I)")
142 description: qsTr("Generally does not need much adjustment, reduce this when seeing slow oscillations.")
143 param: "MC_YAWRATE_I"
144 min: 0.04
145 max: 0.4
146 step: 0.02
147 }
148 }
149 }
150 }
151}