mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
HAL_SITL: use integer maths for clocks
same fix as for HAL_Linux
This commit is contained in:
parent
55d2404e4c
commit
350be1b24f
@ -18,12 +18,19 @@ using HALSITL::Scheduler;
|
|||||||
namespace AP_HAL {
|
namespace AP_HAL {
|
||||||
|
|
||||||
static struct {
|
static struct {
|
||||||
struct timeval start_time;
|
uint64_t start_time_ns;
|
||||||
} state;
|
} state;
|
||||||
|
|
||||||
|
static uint64_t ts_to_nsec(struct timespec &ts)
|
||||||
|
{
|
||||||
|
return ts.tv_sec*1000000000ULL + ts.tv_nsec;
|
||||||
|
}
|
||||||
|
|
||||||
void init()
|
void init()
|
||||||
{
|
{
|
||||||
gettimeofday(&state.start_time, nullptr);
|
struct timespec ts {};
|
||||||
|
clock_gettime(CLOCK_MONOTONIC, &ts);
|
||||||
|
state.start_time_ns = ts_to_nsec(ts);
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(__CYGWIN__) || defined(__CYGWIN64__) || defined(CYGWIN_BUILD)
|
#if defined(__CYGWIN__) || defined(__CYGWIN64__) || defined(CYGWIN_BUILD)
|
||||||
@ -170,12 +177,9 @@ uint64_t micros64()
|
|||||||
return stopped_usec;
|
return stopped_usec;
|
||||||
}
|
}
|
||||||
|
|
||||||
struct timeval tp;
|
struct timespec ts;
|
||||||
gettimeofday(&tp, nullptr);
|
clock_gettime(CLOCK_MONOTONIC, &ts);
|
||||||
uint64_t ret = 1.0e6 * ((tp.tv_sec + (tp.tv_usec * 1.0e-6)) -
|
return uint64_div1000(ts_to_nsec(ts) - state.start_time_ns);
|
||||||
(state.start_time.tv_sec +
|
|
||||||
(state.start_time.tv_usec * 1.0e-6)));
|
|
||||||
return ret;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
uint64_t millis64()
|
uint64_t millis64()
|
||||||
|
Loading…
Reference in New Issue
Block a user