AP_NavEKF3: fix logic bug introduced by magnetometer use changes

This commit is contained in:
priseborough 2016-12-29 08:51:26 +11:00 committed by Randy Mackay
parent a133d55b6d
commit 52e8f687d9
1 changed files with 1 additions and 1 deletions

View File

@ -278,7 +278,7 @@ void NavEKF3_core::SelectMagFusion()
// from becoming badly conditioned. For planes we only do this on-ground because they can align the yaw from GPS when
// airborne. For other platform types we do this all the time.
if (!use_compass()) {
if ((onGround || assume_zero_sideslip()) && (imuSampleTime_ms - lastSynthYawTime_ms > 140)) {
if ((onGround || !assume_zero_sideslip()) && (imuSampleTime_ms - lastSynthYawTime_ms > 140)) {
fuseEulerYaw();
magTestRatio.zero();
yawTestRatio = 0.0f;