mirror of https://github.com/ArduPilot/ardupilot
Baro_PX4: use healthy flag
This commit is contained in:
parent
d29fe51cb3
commit
76634ee8c3
|
@ -46,9 +46,9 @@ uint8_t AP_Baro_PX4::read(void)
|
||||||
_accumulate();
|
_accumulate();
|
||||||
|
|
||||||
// consider the baro healthy if we got a reading in the last 0.2s
|
// consider the baro healthy if we got a reading in the last 0.2s
|
||||||
healthy = (hrt_absolute_time() - _last_timestamp < 200000);
|
_flags.healthy = (hrt_absolute_time() - _last_timestamp < 200000);
|
||||||
if (!healthy || _sum_count == 0) {
|
if (!_flags.healthy || _sum_count == 0) {
|
||||||
return healthy;
|
return _flags.healthy;
|
||||||
}
|
}
|
||||||
|
|
||||||
_pressure = (_pressure_sum / _sum_count) * 100.0f;
|
_pressure = (_pressure_sum / _sum_count) * 100.0f;
|
||||||
|
|
Loading…
Reference in New Issue