AP_Compass: removed use of hrt_absolute_time()

This commit is contained in:
Andrew Tridgell 2014-08-20 08:41:28 +10:00
parent 5280d8936d
commit 9f6d1f987b
2 changed files with 2 additions and 2 deletions

View File

@ -94,7 +94,7 @@ bool AP_Compass_PX4::read(void)
// consider the compass healthy if we got a reading in the last 0.2s
for (uint8_t i=0; i<_num_instances; i++) {
_healthy[i] = (hrt_absolute_time() - _last_timestamp[i] < 200000);
_healthy[i] = (hal.scheduler->micros64() - _last_timestamp[i] < 200000);
}
for (uint8_t i=0; i<_num_instances; i++) {

View File

@ -97,7 +97,7 @@ bool AP_Compass_VRBRAIN::read(void)
// consider the compass healthy if we got a reading in the last 0.2s
for (uint8_t i=0; i<_num_instances; i++) {
_healthy[i] = (hrt_absolute_time() - _last_timestamp[i] < 200000);
_healthy[i] = (hal.scheduler->micros64() - _last_timestamp[i] < 200000);
}
for (uint8_t i=0; i<_num_instances; i++) {