Browse Source

Baro: update climb rate only if healthy

master
Randy Mackay 10 years ago
parent
commit
5732a6a144
  1. 4
      libraries/AP_Baro/AP_Baro.cpp

4
libraries/AP_Baro/AP_Baro.cpp

@ -347,7 +347,9 @@ void AP_Baro::update(void) @@ -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());
}
}
/*

Loading…
Cancel
Save