forked from Archive/PX4-Autopilot
platforms: use CLOCK_MONOTONIC
For the non-lockstep case we want to use CLOCK_MONOTONIC if possible.
This commit is contained in:
parent
d94748c831
commit
06c5037025
|
@ -58,6 +58,12 @@ int px4_sem_init(px4_sem_t *s, int pshared, unsigned value)
|
|||
pthread_cond_init(&(s->wait), nullptr);
|
||||
pthread_mutex_init(&(s->lock), nullptr);
|
||||
|
||||
// We want to use CLOCK_MONOTONIC if possible.
|
||||
pthread_condattr_t attr;
|
||||
pthread_condattr_init(&attr);
|
||||
pthread_condattr_setclock(&attr, CLOCK_MONOTONIC);
|
||||
pthread_cond_init(&(s->wait), &attr);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
|
|
@ -379,7 +379,8 @@ extern "C" {
|
|||
|
||||
// Get the current time
|
||||
struct timespec ts;
|
||||
// px4_sem_timedwait is implemented using CLOCK_MONOTONIC.
|
||||
// px4_sem_timedwait is implemented using CLOCK_MONOTONIC,
|
||||
// at least for lockstep, on Qurt and on Linux.
|
||||
px4_clock_gettime(CLOCK_MONOTONIC, &ts);
|
||||
|
||||
// Calculate an absolute time in the future
|
||||
|
|
Loading…
Reference in New Issue