AP_HAL_Linux: removed native_millis/micros

This commit is contained in:
Andrew Tridgell 2023-08-22 11:41:16 +10:00 committed by Peter Barker
parent 6a54c5e952
commit 8ed289a514
2 changed files with 5 additions and 44 deletions

View File

@ -269,7 +269,7 @@ void CANIface::_pollWrite()
while (_hasReadyTx()) {
WITH_SEMAPHORE(sem);
const CanTxItem tx = _tx_queue.top();
uint64_t curr_time = AP_HAL::native_micros64();
uint64_t curr_time = AP_HAL::micros64();
if (tx.deadline >= curr_time) {
// hal.console->printf("%x TDEAD: %lu CURRT: %lu DEL: %lu\n",tx.frame.id, tx.deadline, curr_time, tx.deadline-curr_time);
const int res = _write(tx.frame);
@ -302,7 +302,7 @@ bool CANIface::_pollRead()
{
iterations_count++;
CanRxItem rx;
rx.timestamp_us = AP_HAL::native_micros64(); // Monotonic timestamp is not required to be precise (unlike UTC)
rx.timestamp_us = AP_HAL::micros64(); // Monotonic timestamp is not required to be precise (unlike UTC)
bool loopback = false;
const int res = _read(rx.frame, rx.timestamp_us, loopback);
if (res == 1) {
@ -389,7 +389,7 @@ int CANIface::_read(AP_HAL::CANFrame& frame, uint64_t& timestamp_us, bool& loopb
/*
* Timestamp
*/
timestamp_us = AP_HAL::native_micros64();
timestamp_us = AP_HAL::micros64();
return 1;
}
@ -506,8 +506,8 @@ bool CANIface::select(bool &read_select, bool &write_select,
stats.num_tx_poll_req++;
}
}
if (_evt_handle != nullptr && blocking_deadline > AP_HAL::native_micros64()) {
_evt_handle->wait(blocking_deadline - AP_HAL::native_micros64());
if (_evt_handle != nullptr && blocking_deadline > AP_HAL::micros64()) {
_evt_handle->wait(blocking_deadline - AP_HAL::micros64());
}
}

View File

@ -79,43 +79,4 @@ uint64_t millis64()
(state.start_time.tv_nsec*1.0e-9)));
}
uint32_t native_micros()
{
return native_micros64() & 0xFFFFFFFF;
}
uint32_t native_millis()
{
return native_millis64() & 0xFFFFFFFF;
}
/*
we define a millis16() here to avoid an issue with sitl builds in cygwin
*/
uint16_t native_millis16()
{
return native_millis64() & 0xFFFF;
}
uint64_t native_micros64()
{
struct timespec ts;
clock_gettime(CLOCK_MONOTONIC, &ts);
return 1.0e6*((ts.tv_sec + (ts.tv_nsec*1.0e-9)) -
(state.start_time.tv_sec +
(state.start_time.tv_nsec*1.0e-9)));
}
uint64_t native_millis64()
{
struct timespec ts;
clock_gettime(CLOCK_MONOTONIC, &ts);
return 1.0e3*((ts.tv_sec + (ts.tv_nsec*1.0e-9)) -
(state.start_time.tv_sec +
(state.start_time.tv_nsec*1.0e-9)));
}
} // namespace AP_HAL