Browse Source

AP_Compass: removed use of hrt_absolute_time()

master
Andrew Tridgell 11 years ago
parent
commit
9f6d1f987b
  1. 2
      libraries/AP_Compass/AP_Compass_PX4.cpp
  2. 2
      libraries/AP_Compass/AP_Compass_VRBRAIN.cpp

2
libraries/AP_Compass/AP_Compass_PX4.cpp

@ -94,7 +94,7 @@ bool AP_Compass_PX4::read(void) @@ -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++) {

2
libraries/AP_Compass/AP_Compass_VRBRAIN.cpp

@ -97,7 +97,7 @@ bool AP_Compass_VRBRAIN::read(void) @@ -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++) {

Loading…
Cancel
Save