Baro: update climb rate only if healthy

This commit is contained in:
Randy Mackay 2015-07-29 14:47:51 +09:00
parent cb9cb7fdc4
commit d2f7c21eb3

View File

@ -347,7 +347,9 @@ void AP_Baro::update(void)
}
// ensure the climb rate filter is updated
_climb_rate_filter.update(get_altitude(), get_last_update());
if (healthy()) {
_climb_rate_filter.update(get_altitude(), get_last_update());
}
}
/*