mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
platforms: fix clock build for macOS (yet again)
This commit is contained in:
parent
06c5037025
commit
14e5ebbbbc
@ -594,20 +594,29 @@ void abstime_to_ts(struct timespec *ts, hrt_abstime abstime)
|
||||
ts->tv_nsec = abstime * 1000;
|
||||
}
|
||||
|
||||
#if defined(ENABLE_LOCKSTEP_SCHEDULER)
|
||||
int px4_clock_gettime(clockid_t clk_id, struct timespec *tp)
|
||||
{
|
||||
if (clk_id == CLOCK_MONOTONIC) {
|
||||
|
||||
#if defined(ENABLE_LOCKSTEP_SCHEDULER)
|
||||
const uint64_t abstime = lockstep_scheduler.get_absolute_time();
|
||||
abstime_to_ts(tp, abstime - px4_timestart_monotonic);
|
||||
return 0;
|
||||
#else // defined(ENABLE_LOCKSTEP_SCHEDULER)
|
||||
#if defined(__PX4_DARWIN)
|
||||
// We don't have CLOCK_MONOTONIC on macOS, so we just have to
|
||||
// resort back to CLOCK_REALTIME here.
|
||||
return system_clock_gettime(CLOCK_REALTIME, tp);
|
||||
#else // defined(__PX4_DARWIN)
|
||||
return system_clock_gettime(clk_id, tp);
|
||||
#endif // defined(__PX4_DARWIN)
|
||||
#endif // defined(ENABLE_LOCKSTEP_SCHEDULER)
|
||||
|
||||
} else {
|
||||
return system_clock_gettime(clk_id, tp);
|
||||
}
|
||||
}
|
||||
|
||||
#if defined(ENABLE_LOCKSTEP_SCHEDULER)
|
||||
int px4_clock_settime(clockid_t clk_id, const struct timespec *ts)
|
||||
{
|
||||
if (clk_id == CLOCK_REALTIME) {
|
||||
|
||||
@ -58,11 +58,14 @@ 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.
|
||||
#if !defined(__PX4_DARWIN)
|
||||
// We want to use CLOCK_MONOTONIC if possible but we can't on macOS
|
||||
// because it's not available.
|
||||
pthread_condattr_t attr;
|
||||
pthread_condattr_init(&attr);
|
||||
pthread_condattr_setclock(&attr, CLOCK_MONOTONIC);
|
||||
pthread_cond_init(&(s->wait), &attr);
|
||||
#endif
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -1 +1 @@
|
||||
Subproject commit 701a35b42ab2f5e4969630be262df023dbd04670
|
||||
Subproject commit 28ccde918b00403d0c6ccb1b818751c3cc573f08
|
||||
@ -379,8 +379,8 @@ extern "C" {
|
||||
|
||||
// Get the current time
|
||||
struct timespec ts;
|
||||
// px4_sem_timedwait is implemented using CLOCK_MONOTONIC,
|
||||
// at least for lockstep, on Qurt and on Linux.
|
||||
// Note, we can't actually use CLOCK_MONOTONIC on macOS
|
||||
// but that's hidden and implemented in px4_clock_gettime.
|
||||
px4_clock_gettime(CLOCK_MONOTONIC, &ts);
|
||||
|
||||
// Calculate an absolute time in the future
|
||||
|
||||
@ -9,10 +9,11 @@
|
||||
#define clockid_t int
|
||||
#endif
|
||||
|
||||
__EXPORT int px4_clock_gettime(clockid_t clk_id, struct timespec *tp);
|
||||
|
||||
#if defined(ENABLE_LOCKSTEP_SCHEDULER) || defined(__PX4_QURT)
|
||||
|
||||
__BEGIN_DECLS
|
||||
__EXPORT int px4_clock_gettime(clockid_t clk_id, struct timespec *tp);
|
||||
__EXPORT int px4_clock_settime(clockid_t clk_id, const struct timespec *tp);
|
||||
|
||||
__EXPORT int px4_usleep(useconds_t usec);
|
||||
@ -24,7 +25,6 @@ __END_DECLS
|
||||
|
||||
#else
|
||||
|
||||
#define px4_clock_gettime system_clock_gettime
|
||||
#define px4_clock_settime system_clock_settime
|
||||
#define px4_usleep system_usleep
|
||||
#define px4_sleep system_sleep
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user