Browse Source

AP_HAL_PX4: use HAL_SEMAPHORE_BLOCK_FOREVER

mission-4.1.18
Peter Barker 8 years ago committed by Francisco Ferreira
parent
commit
3ff4cd8c07
  1. 2
      libraries/AP_HAL_PX4/Semaphores.cpp

2
libraries/AP_HAL_PX4/Semaphores.cpp

@ -20,7 +20,7 @@ bool Semaphore::take(uint32_t timeout_ms) @@ -20,7 +20,7 @@ bool Semaphore::take(uint32_t timeout_ms)
// don't ever wait on a semaphore in interrupt context
return take_nonblocking();
}
if (timeout_ms == 0) {
if (timeout_ms == HAL_SEMAPHORE_BLOCK_FOREVER) {
return pthread_mutex_lock(&_lock) == 0;
}
if (take_nonblocking()) {

Loading…
Cancel
Save