AP_HAL_SITL: removed native_millis/micros

This commit is contained in:
Andrew Tridgell 2023-08-22 11:41:17 +10:00 committed by Peter Barker
parent 8ed289a514
commit 85c2c3609b
3 changed files with 6 additions and 67 deletions

View File

@ -310,7 +310,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);
@ -342,7 +342,7 @@ bool CANIface::_pollRead()
while (iterations_count < CAN_MAX_POLL_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;
int res;
res = _read(rx.frame, rx.timestamp_us, loopback);
@ -423,7 +423,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;
}
@ -558,8 +558,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

@ -109,7 +109,7 @@ void SITL_State::init(int argc, char * const argv[]) {
}
void SITL_State::wait_clock(uint64_t wait_time_usec) {
while (AP_HAL::native_micros64() < wait_time_usec) {
while (AP_HAL::micros64() < wait_time_usec) {
usleep(1000);
}
}

View File

@ -193,65 +193,4 @@ uint64_t millis64()
return ret;
}
uint32_t native_micros()
{
#if AP_TEST_DRONECAN_DRIVERS
return micros();
#else
return native_micros64() & 0xFFFFFFFF;
#endif
}
uint32_t native_millis()
{
#if AP_TEST_DRONECAN_DRIVERS
return millis();
#else
return native_millis64() & 0xFFFFFFFF;
#endif
}
/*
we define a millis16() here to avoid an issue with sitl builds in cygwin
*/
uint16_t native_millis16()
{
#if AP_TEST_DRONECAN_DRIVERS
return millis16();
#else
return native_millis64() & 0xFFFF;
#endif
}
uint64_t native_micros64()
{
#if AP_TEST_DRONECAN_DRIVERS
return micros64();
#else
struct timeval tp;
gettimeofday(&tp, nullptr);
uint64_t ret = 1.0e6 * ((tp.tv_sec + (tp.tv_usec * 1.0e-6)) -
(state.start_time.tv_sec +
(state.start_time.tv_usec * 1.0e-6)));
return ret;
#endif
}
uint64_t native_millis64()
{
#if AP_TEST_DRONECAN_DRIVERS
return millis64();
#else
struct timeval tp;
gettimeofday(&tp, nullptr);
uint64_t ret = 1.0e3*((tp.tv_sec + (tp.tv_usec*1.0e-6)) -
(state.start_time.tv_sec +
(state.start_time.tv_usec*1.0e-6)));
return ret;
#endif
}
} // namespace AP_HAL