Skip to content

Commit

Permalink
CurrentState: add individual SRate variables
Browse files Browse the repository at this point in the history
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.
  • Loading branch information
robertlong13 authored and meee1 committed Nov 27, 2024
1 parent 718162a commit e194025
Showing 1 changed file with 36 additions and 2 deletions.
38 changes: 36 additions & 2 deletions ExtLibs/ArduPilot/CurrentState.cs
Original file line number Diff line number Diff line change
Expand Up @@ -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; }
Expand Down Expand Up @@ -3686,8 +3698,7 @@ private void Parent_OnPacketReceived(object sender, MAVLink.MAVLinkMessage mavLi
{
var pid = mavLinkMessage.ToStructure<MAVLink.mavlink_pid_tuning_t>();

//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;
Expand All @@ -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;
Expand Down

0 comments on commit e194025

Please sign in to comment.