mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: Add get_system_clock_us in utils
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
f6c0639120
commit
3102846b8b
|
@ -66,6 +66,24 @@ uint64_t AP_HAL::Util::get_system_clock_ms() const
|
|||
#endif
|
||||
}
|
||||
|
||||
uint64_t AP_HAL::Util::get_system_clock_us() const
|
||||
{
|
||||
#if defined(__APPLE__) && defined(__MACH__)
|
||||
struct timeval ts;
|
||||
gettimeofday(&ts, nullptr);
|
||||
return ((long long)((ts.tv_sec * 1000000) + ts.tv_usec));
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
// ChibiOS is not ready for that
|
||||
return 0;
|
||||
#else
|
||||
struct timespec ts;
|
||||
clock_gettime(CLOCK_REALTIME, &ts);
|
||||
const uint64_t seconds = ts.tv_sec;
|
||||
const uint64_t nanoseconds = ts.tv_nsec;
|
||||
return (seconds * 1000000ULL + nanoseconds/1000ULL);
|
||||
#endif
|
||||
}
|
||||
|
||||
void AP_HAL::Util::get_system_clock_utc(int32_t &hour, int32_t &min, int32_t &sec, int32_t &ms) const
|
||||
{
|
||||
// get time of day in ms
|
||||
|
|
|
@ -50,6 +50,11 @@ public:
|
|||
*/
|
||||
uint64_t get_system_clock_ms() const;
|
||||
|
||||
/*
|
||||
get system clock in UTC microseconds
|
||||
*/
|
||||
uint64_t get_system_clock_us() const;
|
||||
|
||||
/*
|
||||
get system time in UTC hours, minutes, seconds and milliseconds
|
||||
*/
|
||||
|
@ -120,4 +125,7 @@ protected:
|
|||
// values until the vehicle code has fully started
|
||||
bool soft_armed = false;
|
||||
uint64_t capabilities = 0;
|
||||
|
||||
// by default we consider system_time was not set
|
||||
bool _system_time_was_set = false;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue