Browse Source

Baro_PX4: use healthy flag

mission-4.1.18
Randy Mackay 11 years ago
parent
commit
76634ee8c3
  1. 6
      libraries/AP_Baro/AP_Baro_PX4.cpp

6
libraries/AP_Baro/AP_Baro_PX4.cpp

@ -46,9 +46,9 @@ uint8_t AP_Baro_PX4::read(void) @@ -46,9 +46,9 @@ uint8_t AP_Baro_PX4::read(void)
_accumulate();
// consider the baro healthy if we got a reading in the last 0.2s
healthy = (hrt_absolute_time() - _last_timestamp < 200000);
if (!healthy || _sum_count == 0) {
return healthy;
_flags.healthy = (hrt_absolute_time() - _last_timestamp < 200000);
if (!_flags.healthy || _sum_count == 0) {
return _flags.healthy;
}
_pressure = (_pressure_sum / _sum_count) * 100.0f;

Loading…
Cancel
Save