Browse Source

PX4: add PIDTuning UI for fixed wing vehicles (#10384)

This commit adds a pid tuning UI for fixed wing vehicles for attitude and rate controllers
QGC4.4
JaeyoungLim 3 years ago committed by GitHub
parent
commit
d868f8a583
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 2
      src/AutoPilotPlugins/PX4/PX4TuningComponent.cc
  2. 8
      src/AutoPilotPlugins/PX4/PX4TuningComponentPlaneAll.qml
  3. 71
      src/AutoPilotPlugins/PX4/PX4TuningComponentPlaneAttitude.qml
  4. 173
      src/AutoPilotPlugins/PX4/PX4TuningComponentPlaneRate.qml
  5. 2
      src/FirmwarePlugin/PX4/PX4Resources.qrc

2
src/AutoPilotPlugins/PX4/PX4TuningComponent.cc

@ -54,7 +54,7 @@ QUrl PX4TuningComponent::setupSource(void) const @@ -54,7 +54,7 @@ QUrl PX4TuningComponent::setupSource(void) const
switch (_vehicle->vehicleType()) {
case MAV_TYPE_FIXED_WING:
qmlFile = ""; // TODO: "qrc:/qml/PX4TuningComponentPlane.qml";
qmlFile = "qrc:/qml/PX4TuningComponentPlane.qml";
break;
case MAV_TYPE_QUADROTOR:
case MAV_TYPE_COAXIAL:

8
src/AutoPilotPlugins/PX4/PX4TuningComponentPlaneAll.qml

@ -28,12 +28,16 @@ Item { @@ -28,12 +28,16 @@ Item {
width: parent.width
anchors.top: parent.top
QGCTabButton {
text: qsTr("TECS")
text: qsTr("Rate Controller")
}
QGCTabButton {
text: qsTr("Attitude Controller")
}
}
property var pages: [
"PX4TuningComponentPlaneTECS.qml",
"PX4TuningComponentPlaneRate.qml",
"PX4TuningComponentPlaneAttitude.qml",
]
Loader {

71
src/AutoPilotPlugins/PX4/PX4TuningComponentPlaneAttitude.qml

@ -0,0 +1,71 @@ @@ -0,0 +1,71 @@
/****************************************************************************
*
* (c) 2021 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Layouts 1.2
import QGroundControl 1.0
import QGroundControl.Controls 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Vehicle 1.0
ColumnLayout {
width: availableWidth
anchors.fill: parent
property alias autotuningEnabled: pidTuning.autotuningEnabled
PIDTuning {
width: availableWidth
id: pidTuning
property var roll: QtObject {
property string name: qsTr("Roll")
property var plot: [
{ name: "Response", value: globals.activeVehicle.roll.value },
{ name: "Setpoint", value: globals.activeVehicle.setpoint.roll.value }
]
property var params: ListModel {
ListElement {
title: qsTr("Time constant (FW_R_TC)")
description: qsTr("The latency between a roll step input and the achieved setpoint (inverse to a P gain)")
param: "FW_R_TC"
min: 0.4
max: 1.0
step: 0.05
}
}
}
property var pitch: QtObject {
property string name: qsTr("Pitch")
property var plot: [
{ name: "Response", value: globals.activeVehicle.pitch.value },
{ name: "Setpoint", value: globals.activeVehicle.setpoint.pitch.value }
]
property var params: ListModel {
ListElement {
title: qsTr("Time Constant (FW_P_TC)")
description: qsTr("The latency between a pitch step input and the achieved setpoint (inverse to a P gain)")
param: "FW_P_TC"
min: 0.2
max: 1.0
step: 0.05
}
}
}
title: "Attitude"
tuningMode: Vehicle.ModeRateAndAttitude
unit: "deg"
axis: [ roll, pitch ]
showAutoModeChange: true
showAutoTuning: true
}
}

173
src/AutoPilotPlugins/PX4/PX4TuningComponentPlaneRate.qml

@ -0,0 +1,173 @@ @@ -0,0 +1,173 @@
/****************************************************************************
*
* (c) 2021 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Layouts 1.2
import QGroundControl 1.0
import QGroundControl.Controls 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Vehicle 1.0
ColumnLayout {
width: availableWidth
anchors.fill: parent
property alias autotuningEnabled: pidTuning.autotuningEnabled
GridLayout {
columns: 2
}
PIDTuning {
width: availableWidth
id: pidTuning
property var roll: QtObject {
property string name: qsTr("Roll")
property var plot: [
{ name: "Response", value: globals.activeVehicle.rollRate.value },
{ name: "Setpoint", value: globals.activeVehicle.setpoint.rollRate.value }
]
property var params: ListModel {
ListElement {
title: qsTr("Porportional gain (FW_RR_P)")
description: qsTr("Porportional gain.")
param: "FW_RR_P"
min: 0.0
max: 1
step: 0.005
}
ListElement {
title: qsTr("Differential Gain (FW_RR_D)")
description: qsTr("Damping: increase to reduce overshoots and oscillations, but not higher than really needed.")
param: "FW_RR_D"
min: 0.0
max: 1.0
step: 0.005
}
ListElement {
title: qsTr("Integral Gain (FW_RR_I)")
description: qsTr("Generally does not need much adjustment, reduce this when seeing slow oscillations.")
param: "FW_RR_I"
min: 0.0
max: 0.5
step: 0.005
}
ListElement {
title: qsTr("Feedforward Gain (FW_RR_FF)")
description: qsTr("Feedforward gused to compensate for aerodynamic damping.")
param: "FW_RR_FF"
min: 0.0
max: 10.0
step: 0.05
}
}
}
property var pitch: QtObject {
property string name: qsTr("Pitch")
property var plot: [
{ name: "Response", value: globals.activeVehicle.pitchRate.value },
{ name: "Setpoint", value: globals.activeVehicle.setpoint.pitchRate.value }
]
property var params: ListModel {
ListElement {
title: qsTr("Porportional Gain (FW_PR_P)")
description: qsTr("Porportional Gain.")
param: "FW_PR_P"
min: 0.0
max: 1
step: 0.005
}
ListElement {
title: qsTr("Differential Gain (FW_PR_D)")
description: qsTr("Damping: increase to reduce overshoots and oscillations, but not higher than really needed.")
param: "FW_PR_D"
min: 0.0
max: 1.00
step: 0.005
}
ListElement {
title: qsTr("Integral Gain (FW_PR_I)")
description: qsTr("Generally does not need much adjustment, reduce this when seeing slow oscillations.")
param: "FW_PR_I"
min: 0.0
max: 0.5
step: 0.005
}
ListElement {
title: qsTr("Feedforward Gain (FW_PR_FF)")
description: qsTr("Feedforward gused to compensate for aerodynamic damping.")
param: "FW_PR_FF"
min: 0.0
max: 10.0
step: 0.05
}
}
}
property var yaw: QtObject {
property string name: qsTr("Yaw")
property var plot: [
{ name: "Response", value: globals.activeVehicle.yawRate.value },
{ name: "Setpoint", value: globals.activeVehicle.setpoint.yawRate.value }
]
property var params: ListModel {
ListElement {
title: qsTr("Porportional Gain (FW_YR_P)")
description: qsTr("Porportional Gain.")
param: "FW_YR_P"
min: 0.0
max: 1
step: 0.005
}
ListElement {
title: qsTr("Integral Gain (FW_YR_D)")
description: qsTr("Generally does not need much adjustment, reduce this when seeing slow oscillations.")
param: "FW_YR_D"
min: 0.0
max: 1.0
step: 0.005
}
ListElement {
title: qsTr("Integral Gain (FW_YR_I)")
description: qsTr("Generally does not need much adjustment, reduce this when seeing slow oscillations.")
param: "FW_YR_I"
min: 0.0
max: 50.0
step: 0.5
}
ListElement {
title: qsTr("Feedforward Gain (FW_YR_FF)")
description: qsTr("Feedforward gused to compensate for aerodynamic damping.")
param: "FW_YR_FF"
min: 0.0
max: 10.0
step: 0.05
}
ListElement {
title: qsTr("Roll control to yaw feedforward (FW_RLL_TO_YAW_FF)")
description: qsTr("Used to counteract the adverse yaw effect for fixed wings.")
param: "FW_RLL_TO_YAW_FF"
min: 0.0
max: 1.0
step: 0.01
}
}
}
title: "Rate"
tuningMode: Vehicle.ModeRateAndAttitude
unit: "deg/s"
axis: [ roll, pitch, yaw ]
chartDisplaySec: 3
showAutoModeChange: true
showAutoTuning: true
}
}

2
src/FirmwarePlugin/PX4/PX4Resources.qrc

@ -19,6 +19,8 @@ @@ -19,6 +19,8 @@
<file alias="PX4TuningComponentCopterPosition.qml">../../AutoPilotPlugins/PX4/PX4TuningComponentCopterPosition.qml</file>
<file alias="PX4TuningComponentPlane.qml">../../AutoPilotPlugins/PX4/PX4TuningComponentPlane.qml</file>
<file alias="PX4TuningComponentPlaneAll.qml">../../AutoPilotPlugins/PX4/PX4TuningComponentPlaneAll.qml</file>
<file alias="PX4TuningComponentPlaneAttitude.qml">../../AutoPilotPlugins/PX4/PX4TuningComponentPlaneAttitude.qml</file>
<file alias="PX4TuningComponentPlaneRate.qml">../../AutoPilotPlugins/PX4/PX4TuningComponentPlaneRate.qml</file>
<file alias="PX4TuningComponentPlaneTECS.qml">../../AutoPilotPlugins/PX4/PX4TuningComponentPlaneTECS.qml</file>
<file alias="PX4TuningComponentVTOL.qml">../../AutoPilotPlugins/PX4/PX4TuningComponentVTOL.qml</file>
<file alias="SafetyComponent.qml">../../AutoPilotPlugins/PX4/SafetyComponent.qml</file>

Loading…
Cancel
Save