Browse Source

AP_HAL_SITL: use OS clock for get_hw_rtc

master
Peter Barker 7 years ago committed by Andrew Tridgell
parent
commit
00153f513c
  1. 10
      libraries/AP_HAL_SITL/Util.cpp
  2. 3
      libraries/AP_HAL_SITL/Util.h

10
libraries/AP_HAL_SITL/Util.cpp

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#include "Util.h"
uint64_t HALSITL::Util::get_hw_rtc() const
{
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);
}

3
libraries/AP_HAL_SITL/Util.h

@ -28,6 +28,9 @@ public: @@ -28,6 +28,9 @@ public:
const char* get_custom_defaults_file() const override {
return sitlState->defaults_path;
}
uint64_t get_hw_rtc() const override;
private:
SITL_State *sitlState;
};

Loading…
Cancel
Save