mirror of https://github.com/ArduPilot/ardupilot
40 lines
829 B
C++
40 lines
829 B
C++
#include <AP_HAL.h>
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
|
|
|
#include "Semaphores.h"
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
using namespace Linux;
|
|
|
|
bool LinuxSemaphore::give()
|
|
{
|
|
return pthread_mutex_unlock(&_lock) == 0;
|
|
}
|
|
|
|
bool LinuxSemaphore::take(uint32_t timeout_ms)
|
|
{
|
|
if (timeout_ms == 0) {
|
|
return pthread_mutex_lock(&_lock) == 0;
|
|
}
|
|
if (take_nonblocking()) {
|
|
return true;
|
|
}
|
|
uint32_t start = hal.scheduler->micros();
|
|
do {
|
|
hal.scheduler->delay_microseconds(200);
|
|
if (take_nonblocking()) {
|
|
return true;
|
|
}
|
|
} while ((hal.scheduler->micros() - start) < timeout_ms*1000);
|
|
return false;
|
|
}
|
|
|
|
bool LinuxSemaphore::take_nonblocking()
|
|
{
|
|
return pthread_mutex_trylock(&_lock) == 0;
|
|
}
|
|
|
|
#endif // CONFIG_HAL_BOARD
|