AP_NavEKF3: Fix yaw alignment bug

When the  yaw is aligned to the GPS yaw, the recordYawResetsCompleted() function should be called the same as for any other yaw reset.
This commit is contained in:
Paul Riseborough 2024-07-25 05:42:46 +09:30 committed by Peter Barker
parent 05d8b0db8a
commit 4904c718a5

View File

@ -294,6 +294,7 @@ void NavEKF3_core::SelectMagFusion()
have_fused_gps_yaw = true;
lastSynthYawTime_ms = imuSampleTime_ms;
last_gps_yaw_fuse_ms = imuSampleTime_ms;
recordYawResetsCompleted();
} else if (tiltAlignComplete && yawAlignComplete) {
have_fused_gps_yaw = fuseEulerYaw(yawFusionMethod::GPS);
if (have_fused_gps_yaw) {