AP_HAL_PX4: use HAL_SEMAPHORE_BLOCK_FOREVER

This commit is contained in:
Peter Barker 2017-04-29 10:07:13 +10:00 committed by Francisco Ferreira
parent b11ca5d538
commit 3ff4cd8c07
1 changed files with 1 additions and 1 deletions

View File

@ -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()) {