AP_Baro: remove usage of hrt_absolute_time()
use a single time base in all code
This commit is contained in:
parent
a14f8dbd0a
commit
5280d8936d
@ -46,7 +46,7 @@ uint8_t AP_Baro_PX4::read(void)
|
||||
_accumulate();
|
||||
|
||||
// consider the baro healthy if we got a reading in the last 0.2s
|
||||
_flags.healthy = (hrt_absolute_time() - _last_timestamp < 200000);
|
||||
_flags.healthy = (hal.scheduler->micros64() - _last_timestamp < 200000);
|
||||
if (!_flags.healthy || _sum_count == 0) {
|
||||
return _flags.healthy;
|
||||
}
|
||||
|
@ -46,7 +46,7 @@ uint8_t AP_Baro_VRBRAIN::read(void)
|
||||
_accumulate();
|
||||
|
||||
// consider the baro healthy if we got a reading in the last 0.2s
|
||||
_flags.healthy = (hrt_absolute_time() - _last_timestamp < 200000);
|
||||
_flags.healthy = (hal.scheduler->micros64() - _last_timestamp < 200000);
|
||||
if (!_flags.healthy || _sum_count == 0) {
|
||||
return _flags.healthy;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user