From e19402529ae056b675b21afc598b6a8820446001 Mon Sep 17 00:00:00 2001 From: Bob Long Date: Thu, 14 Nov 2024 16:51:54 +1100 Subject: [PATCH] CurrentState: add individual SRate variables Allows the SRate for Roll/Pitch/Yaw to be displayed simultaneously, rather than needing to set GCS_PID_MASK to one axis at a time. This is useful since tuning one axis may trigger an oscillation in another. --- ExtLibs/ArduPilot/CurrentState.cs | 38 +++++++++++++++++++++++++++++-- 1 file changed, 36 insertions(+), 2 deletions(-) diff --git a/ExtLibs/ArduPilot/CurrentState.cs b/ExtLibs/ArduPilot/CurrentState.cs index 3fb2792786..b3401219a9 100644 --- a/ExtLibs/ArduPilot/CurrentState.cs +++ b/ExtLibs/ArduPilot/CurrentState.cs @@ -2074,6 +2074,18 @@ public float ter_alt [GroupText("PID")] public float pidPDmod { get; set; } + [GroupText("PID")] public float pidSRateRoll { get; set; } + + [GroupText("PID")] public float pidSRatePitch { get; set; } + + [GroupText("PID")] public float pidSRateYaw { get; set; } + + [GroupText("PID")] public float pidSRateAccZ { get; set; } + + [GroupText("PID")] public float pidSRateSteer { get; set; } + + [GroupText("PID")] public float pidSRateLanding { get; set; } + [GroupText("Vibe")] public uint vibeclip0 { get; set; } [GroupText("Vibe")] public uint vibeclip1 { get; set; } @@ -3686,8 +3698,7 @@ private void Parent_OnPacketReceived(object sender, MAVLink.MAVLinkMessage mavLi { var pid = mavLinkMessage.ToStructure(); - //todo: currently only deals with single axis at once - + // These variables currently only deal a with single axis at once, but SRate can be reported for multiple at once pidff = pid.FF; pidP = pid.P; pidI = pid.I; @@ -3697,6 +3708,29 @@ private void Parent_OnPacketReceived(object sender, MAVLink.MAVLinkMessage mavLi pidachieved = pid.achieved; pidSRate = pid.SRate; pidPDmod = pid.PDmod; + + switch (pid.axis) + { + case (byte)MAVLink.PID_TUNING_AXIS.PID_TUNING_ROLL: + pidSRateRoll = pid.SRate; + break; + case (byte)MAVLink.PID_TUNING_AXIS.PID_TUNING_PITCH: + pidSRatePitch = pid.SRate; + break; + case (byte)MAVLink.PID_TUNING_AXIS.PID_TUNING_YAW: + pidSRateYaw = pid.SRate; + break; + case (byte)MAVLink.PID_TUNING_AXIS.PID_TUNING_ACCZ: + pidSRateAccZ = pid.SRate; + break; + case (byte)MAVLink.PID_TUNING_AXIS.PID_TUNING_STEER: + pidSRateSteer = pid.SRate; + break; + case (byte)MAVLink.PID_TUNING_AXIS.PID_TUNING_LANDING: + pidSRateLanding = pid.SRate; + break; + } + } break;