Skip to content

Commit

Permalink
AP_NavEKF3: Fix yaw alignment bug
Browse files Browse the repository at this point in the history
When the  yaw is aligned to the GPS yaw, the recordYawResetsCompleted() function should be called the same as for any other yaw reset.
  • Loading branch information
priseborough authored and peterbarker committed Jul 24, 2024
1 parent 05d8b0d commit 4904c71
Showing 1 changed file with 1 addition and 0 deletions.
1 change: 1 addition & 0 deletions libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down

0 comments on commit 4904c71

Please sign in to comment.