mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
SITL: get_wall_time_us() to use a monotonic clock on non-Windows systems
This commit is contained in:
parent
0d5a0f392c
commit
d73043fc2f
@ -447,9 +447,9 @@ uint64_t Aircraft::get_wall_time_us() const
|
||||
tPrev = now;
|
||||
return last_ret_us;
|
||||
#else
|
||||
struct timeval tp;
|
||||
gettimeofday(&tp, nullptr);
|
||||
return static_cast<uint64_t>(tp.tv_sec * 1.0e6 + tp.tv_usec);
|
||||
struct timespec ts;
|
||||
clock_gettime(CLOCK_MONOTONIC, &ts);
|
||||
return uint64_t(ts.tv_sec * 1000000ULL + ts.tv_nsec / 1000ULL);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -248,7 +248,7 @@ protected:
|
||||
/* add noise based on throttle level (from 0..1) */
|
||||
void add_noise(float throttle);
|
||||
|
||||
/* return wall clock time in microseconds since 1970 */
|
||||
/* return a monotonic wall clock time in microseconds */
|
||||
uint64_t get_wall_time_us(void) const;
|
||||
|
||||
// update attitude and relative position
|
||||
|
Loading…
Reference in New Issue
Block a user