AP_AHRS: ensure AHRS never uses an unhealthy gyro

This commit is contained in:
Andrew Tridgell 2019-04-22 13:53:47 +10:00
parent c630a87e37
commit edffc3001b
1 changed files with 2 additions and 2 deletions

View File

@ -180,7 +180,7 @@ void AP_AHRS_NavEKF::update_EKF2(void)
// calculate corrected gyro estimate for get_gyro()
_gyro_estimate.zero();
if (primary_imu == -1) {
if (primary_imu == -1 || !_ins.get_gyro_health(primary_imu)) {
// the primary IMU is undefined so use an uncorrected default value from the INS library
_gyro_estimate = _ins.get_gyro();
} else {
@ -253,7 +253,7 @@ void AP_AHRS_NavEKF::update_EKF3(void)
// calculate corrected gyro estimate for get_gyro()
_gyro_estimate.zero();
if (primary_imu == -1) {
if (primary_imu == -1 || !_ins.get_gyro_health(primary_imu)) {
// the primary IMU is undefined so use an uncorrected default value from the INS library
_gyro_estimate = _ins.get_gyro();
} else {