mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
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:
parent
05d8b0db8a
commit
4904c718a5
@ -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) {
|
||||
|
Loading…
Reference in New Issue
Block a user