mirror of https://github.com/ArduPilot/ardupilot
HAL_SITL: fixed build on older MacOS
This commit is contained in:
parent
8ea7df3efe
commit
c72f2e57b0
|
@ -1,12 +1,19 @@
|
||||||
#include "Util.h"
|
#include "Util.h"
|
||||||
|
#include <sys/time.h>
|
||||||
|
|
||||||
uint64_t HALSITL::Util::get_hw_rtc() const
|
uint64_t HALSITL::Util::get_hw_rtc() const
|
||||||
{
|
{
|
||||||
|
#ifndef CLOCK_REALTIME
|
||||||
|
struct timeval ts;
|
||||||
|
gettimeofday(&ts, nullptr);
|
||||||
|
return ((long long)((ts.tv_sec * 1000000) + ts.tv_usec));
|
||||||
|
#else
|
||||||
struct timespec ts;
|
struct timespec ts;
|
||||||
clock_gettime(CLOCK_REALTIME, &ts);
|
clock_gettime(CLOCK_REALTIME, &ts);
|
||||||
const uint64_t seconds = ts.tv_sec;
|
const uint64_t seconds = ts.tv_sec;
|
||||||
const uint64_t nanoseconds = ts.tv_nsec;
|
const uint64_t nanoseconds = ts.tv_nsec;
|
||||||
return (seconds * 1000000ULL + nanoseconds/1000ULL);
|
return (seconds * 1000000ULL + nanoseconds/1000ULL);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
Loading…
Reference in New Issue