Browse Source

AP_RangeFinder: removed use of hrt_absolute_time()

master
Andrew Tridgell 11 years ago
parent
commit
43e8b36e5b
  1. 2
      libraries/AP_RangeFinder/AP_RangeFinder_PX4.cpp

2
libraries/AP_RangeFinder/AP_RangeFinder_PX4.cpp

@ -122,7 +122,7 @@ void AP_RangeFinder_PX4::update(void) @@ -122,7 +122,7 @@ void AP_RangeFinder_PX4::update(void)
}
// consider the range finder healthy if we got a reading in the last 0.2s
state.healthy = (hrt_absolute_time() - _last_timestamp < 200000);
state.healthy = (hal.scheduler->micros64() - _last_timestamp < 200000);
if (count != 0) {
state.distance_cm = sum / count * 100.0f;

Loading…
Cancel
Save