diff --git a/libraries/AP_NavEKF/EKFGSF_yaw.cpp b/libraries/AP_NavEKF/EKFGSF_yaw.cpp index e58150600f..2bba0d49d1 100644 --- a/libraries/AP_NavEKF/EKFGSF_yaw.cpp +++ b/libraries/AP_NavEKF/EKFGSF_yaw.cpp @@ -230,6 +230,11 @@ void EKFGSF_yaw::predictAHRS(const uint8_t mdl_idx) if (spinRate_squared < sq(0.175f)) { AHRS[mdl_idx].gyro_bias -= tilt_error_gyro_correction * (EKFGSF_gyroBiasGain * angle_dt); + // sanity check + if (AHRS[mdl_idx].gyro_bias.is_nan()) { + AHRS[mdl_idx].gyro_bias.zero(); + } + for (uint8_t i = 0; i < 3; i++) { AHRS[mdl_idx].gyro_bias[i] = constrain_ftype(AHRS[mdl_idx].gyro_bias[i], -gyro_bias_limit, gyro_bias_limit); }