mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_InertialSensor: removed use of hrt_absolute_time()
This commit is contained in:
parent
e143acd8bf
commit
5c9e5fbc11
@ -212,12 +212,12 @@ void AP_InertialSensor_PX4::_get_sample(void)
|
||||
_last_gyro_timestamp[i] = gyro_report.timestamp;
|
||||
}
|
||||
}
|
||||
_last_get_sample_timestamp = hrt_absolute_time();
|
||||
_last_get_sample_timestamp = hal.scheduler->micros64();
|
||||
}
|
||||
|
||||
bool AP_InertialSensor_PX4::_sample_available(void)
|
||||
{
|
||||
uint64_t tnow = hrt_absolute_time();
|
||||
uint64_t tnow = hal.scheduler->micros64();
|
||||
while (tnow - _last_sample_timestamp > _sample_time_usec) {
|
||||
_have_sample_available = true;
|
||||
_last_sample_timestamp += _sample_time_usec;
|
||||
@ -230,9 +230,9 @@ bool AP_InertialSensor_PX4::wait_for_sample(uint16_t timeout_ms)
|
||||
if (_sample_available()) {
|
||||
return true;
|
||||
}
|
||||
uint32_t start = hal.scheduler->millis();
|
||||
while ((hal.scheduler->millis() - start) < timeout_ms) {
|
||||
uint64_t tnow = hrt_absolute_time();
|
||||
uint64_t start = hal.scheduler->millis64();
|
||||
while ((hal.scheduler->millis64() - start) < timeout_ms) {
|
||||
uint64_t tnow = hal.scheduler->micros64();
|
||||
// we spin for the last timing_lag microseconds. Before that
|
||||
// we yield the CPU to allow IO to happen
|
||||
const uint16_t timing_lag = 400;
|
||||
|
@ -212,12 +212,12 @@ void AP_InertialSensor_VRBRAIN::_get_sample(void)
|
||||
_last_gyro_timestamp[i] = gyro_report.timestamp;
|
||||
}
|
||||
}
|
||||
_last_get_sample_timestamp = hrt_absolute_time();
|
||||
_last_get_sample_timestamp = hal.scheduler->micros64();
|
||||
}
|
||||
|
||||
bool AP_InertialSensor_VRBRAIN::_sample_available(void)
|
||||
{
|
||||
uint64_t tnow = hrt_absolute_time();
|
||||
uint64_t tnow = hal.scheduler->micros64();
|
||||
while (tnow - _last_sample_timestamp > _sample_time_usec) {
|
||||
_have_sample_available = true;
|
||||
_last_sample_timestamp += _sample_time_usec;
|
||||
@ -232,7 +232,7 @@ bool AP_InertialSensor_VRBRAIN::wait_for_sample(uint16_t timeout_ms)
|
||||
}
|
||||
uint32_t start = hal.scheduler->millis();
|
||||
while ((hal.scheduler->millis() - start) < timeout_ms) {
|
||||
uint64_t tnow = hrt_absolute_time();
|
||||
uint64_t tnow = hal.scheduler->micros64();
|
||||
// we spin for the last timing_lag microseconds. Before that
|
||||
// we yield the CPU to allow IO to happen
|
||||
const uint16_t timing_lag = 400;
|
||||
|
Loading…
Reference in New Issue
Block a user