QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
PX4TuningComponentCopterVelocity.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 _mcPosMode: controller.getParameterFact(-1, "MPC_POS_MODE", false)
13
14 GridLayout {
15 columns: 2
16
17 QGCLabel {
18 text: qsTr("Position control mode (set this to 'simple' during tuning):")
19 visible: _mcPosMode
20 }
21 FactComboBox {
22 fact: _mcPosMode
23 indexModel: false
24 visible: _mcPosMode
25 }
26 }
27
28 PIDTuning {
29 id: pidTuning
30 availableWidth: _availableWidth
31 availableHeight: _availableHeight - pidTuning.y
32
33 property var horizontal: QtObject {
34 property string name: qsTr("Horizontal")
35 property string plotTitle: qsTr("Horizontal (Y direction, sidewards)")
36 property var plot: [
37 { name: "Response", value: globals.activeVehicle.localPosition.vy.value },
38 { name: "Setpoint", value: globals.activeVehicle.localPositionSetpoint.vy.value }
39 ]
40 property var params: ListModel {
41 ListElement {
42 title: qsTr("Proportional gain (MPC_XY_VEL_P_ACC)")
43 description: qsTr("Increase for more responsiveness, reduce if the velocity overshoots (and increasing D does not help).")
44 param: "MPC_XY_VEL_P_ACC"
45 min: 1.2
46 max: 5
47 step: 0.05
48 }
49 ListElement {
50 title: qsTr("Integral gain (MPC_XY_VEL_I_ACC)")
51 description: qsTr("Increase to reduce steady-state error (e.g. wind)")
52 param: "MPC_XY_VEL_I_ACC"
53 min: 0.2
54 max: 10
55 step: 0.2
56 }
57 ListElement {
58 title: qsTr("Differential gain (MPC_XY_VEL_D_ACC)")
59 description: qsTr("Damping: increase to reduce overshoots and oscillations, but not higher than really needed.")
60 param: "MPC_XY_VEL_D_ACC"
61 min: 0.1
62 max: 2
63 step: 0.05
64 }
65 }
66 }
67 property var vertical: QtObject {
68 property string name: qsTr("Vertical")
69 property var plot: [
70 { name: "Response", value: globals.activeVehicle.localPosition.vz.value },
71 { name: "Setpoint", value: globals.activeVehicle.localPositionSetpoint.vz.value }
72 ]
73 property var params: ListModel {
74 ListElement {
75 title: qsTr("Proportional gain (MPC_Z_VEL_P_ACC)")
76 description: qsTr("Increase for more responsiveness, reduce if the velocity overshoots (and increasing D does not help).")
77 param: "MPC_Z_VEL_P_ACC"
78 min: 2
79 max: 15
80 step: 0.5
81 }
82 ListElement {
83 title: qsTr("Integral gain (MPC_Z_VEL_I_ACC)")
84 description: qsTr("Increase to reduce steady-state error")
85 param: "MPC_Z_VEL_I_ACC"
86 min: 0.2
87 max: 3
88 step: 0.05
89 }
90 ListElement {
91 title: qsTr("Differential gain (MPC_Z_VEL_D_ACC)")
92 description: qsTr("Damping: increase to reduce overshoots and oscillations, but not higher than really needed.")
93 param: "MPC_Z_VEL_D_ACC"
94 min: 0
95 max: 2
96 step: 0.05
97 }
98 }
99 }
100 title: "Velocity"
101 tuningMode: Vehicle.ModeVelocityAndPosition
102 unit: "m/s"
103 axis: [ horizontal, vertical ]
104 }
105}