diff --git a/platforms/posix/src/px4/common/lockstep_scheduler/src/lockstep_components.cpp b/platforms/posix/src/px4/common/lockstep_scheduler/src/lockstep_components.cpp index 88aa1f12a2..01151a9d06 100644 --- a/platforms/posix/src/px4/common/lockstep_scheduler/src/lockstep_components.cpp +++ b/platforms/posix/src/px4/common/lockstep_scheduler/src/lockstep_components.cpp @@ -44,6 +44,7 @@ #include #include +#if defined(__PX4_WINDOWS) static uint64_t lockstep_wall_time_us() { timespec ts{}; @@ -71,6 +72,7 @@ static uint64_t lockstep_component_wait_budget_us() return wait_budget_us; } +#endif // __PX4_WINDOWS LockstepComponents::LockstepComponents(bool no_cleanup_on_destroy) : _no_cleanup_on_destroy(no_cleanup_on_destroy) @@ -158,10 +160,14 @@ void LockstepComponents::wait_for_components() return; } -#if defined(__PX4_WINDOWS) || defined(__PX4_LINUX) - // Do not let one temporarily blocked component stall the simulator forever. - // Keep the watchdog short: high lockstep speed factors need sub-millisecond - // barrier overhead, and active components normally release the latch first. +#if defined(__PX4_WINDOWS) + // Windows-only: winpthreads occasionally drops pthread_cond_broadcast + // wakes, which can leave the producer blocked here forever. Use a + // short wall-time watchdog so a lost wake caps barrier latency at + // ~100 us instead of stalling the simulator. Linux uses the original + // blocking wait below because POSIX condition variables on Linux + // reliably deliver every broadcast and the blocking path preserves + // strict producer/consumer ordering at startup. const uint64_t wait_start_us = lockstep_wall_time_us(); const uint64_t max_wait_us = lockstep_component_wait_budget_us(); unsigned spin_count = 0;