From 82f7bf454827c6c1e0858d5deb3381ac8b67397a Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Thu, 23 Sep 2021 07:50:20 +1000 Subject: [PATCH] CurrentState: add gpsyaw2 --- ExtLibs/ArduPilot/CurrentState.cs | 38 +++++++++++++++++++++++++++++++ 1 file changed, 38 insertions(+) diff --git a/ExtLibs/ArduPilot/CurrentState.cs b/ExtLibs/ArduPilot/CurrentState.cs index 194ff1b70d..d32f8eca5c 100644 --- a/ExtLibs/ArduPilot/CurrentState.cs +++ b/ExtLibs/ArduPilot/CurrentState.cs @@ -389,6 +389,27 @@ public float altasl [GroupText("Position")] public float groundcourse2 { get; set; } + + [DisplayText("Horizontal Accuracy")] + [GroupText("Position")] + public float gpsh_acc2 { get; private set; } + + [DisplayText("Vertical Accuracy")] + [GroupText("Position")] + public float gpsv_acc2 { get; private set; } + + [DisplayText("Velocity Accuracy")] + [GroupText("Position")] + public float gpsvel_acc2 { get; private set; } + + [DisplayText("Heading Accuracy")] + [GroupText("Position")] + public float gpshdg_acc2 { get; private set; } + + [DisplayText("GPS Yaw (deg)")] + [GroupText("Position")] + public float gpsyaw2 { get; private set; } + [DisplayText("Sat Count Blend")] [GroupText("Position")] public float satcountB => satcount + satcount2; @@ -2859,6 +2880,23 @@ private void Parent_OnPacketReceived(object sender, MAVLink.MAVLinkMessage mavLi groundspeed2 = gps.vel * 1.0e-2f; groundcourse2 = gps.cog * 1.0e-2f; + + if (mavLinkMessage.ismavlink2) + { + gpsh_acc2 = gps.h_acc / 1000.0f; + gpsv_acc2 = gps.v_acc / 1000.0f; + gpsvel_acc2 = gps.vel_acc / 1000.0f; + gpshdg_acc2 = gps.hdg_acc / 1e5f; + gpsyaw2 = gps.yaw / 100.0f; + } + else + { + gpsh_acc2 = -1; + gpsv_acc2 = -1; + gpsvel_acc2 = -1; + gpshdg_acc2 = -1; + gpsyaw2 = -1; + } } break;