6import QGroundControl.Controls
7import QGroundControl.FactControls
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)
16 spacing: ScreenTools.defaultFontPixelWidth
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)
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
42 fact: _thrustModelFactor
43 visible: _thrustModelFactor
49 availableWidth: _availableWidth
50 availableHeight: _availableHeight - pidTuning.y
52 tuningMode: Vehicle.ModeRateAndAttitude
54 axis: [ roll, pitch, yaw ]
56 showAutoModeChange: true
59 property var roll: QtObject {
60 property string name: qsTr("Roll")
62 { name: "Response", value: globals.activeVehicle.rollRate.value },
63 { name: "Setpoint", value: globals.activeVehicle.setpoint.rollRate.value }
65 property var params: ListModel {
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"
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"
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"
92 property var pitch: QtObject {
93 property string name: qsTr("Pitch")
95 { name: "Response", value: globals.activeVehicle.pitchRate.value },
96 { name: "Setpoint", value: globals.activeVehicle.setpoint.pitchRate.value }
98 property var params: ListModel {
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"
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"
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"
125 property var yaw: QtObject {
126 property string name: qsTr("Yaw")
128 { name: "Response", value: globals.activeVehicle.yawRate.value },
129 { name: "Setpoint", value: globals.activeVehicle.setpoint.yawRate.value }
131 property var params: ListModel {
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"
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"