ardupilot/libraries/AP_HAL_Linux/Semaphores.cpp

40 lines
795 B
C++
Raw Normal View History

2013-09-29 01:24:55 -03:00
#include <AP_HAL.h>
2014-07-06 23:03:26 -03:00
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
2013-09-22 03:01:24 -03:00
#include "Semaphores.h"
extern const AP_HAL::HAL& hal;
2013-09-22 03:01:24 -03:00
using namespace Linux;
bool LinuxSemaphore::give()
{
return pthread_mutex_unlock(&_lock) == 0;
2013-09-22 03:01:24 -03:00
}
bool LinuxSemaphore::take(uint32_t timeout_ms)
{
if (timeout_ms == 0) {
return pthread_mutex_lock(&_lock) == 0;
}
if (take_nonblocking()) {
return true;
}
uint64_t start = hal.scheduler->micros64();
do {
hal.scheduler->delay_microseconds(200);
if (take_nonblocking()) {
return true;
}
} while ((hal.scheduler->micros64() - start) < timeout_ms*1000);
return false;
2013-09-22 03:01:24 -03:00
}
bool LinuxSemaphore::take_nonblocking()
{
return pthread_mutex_trylock(&_lock) == 0;
2013-09-22 03:01:24 -03:00
}
2013-09-29 01:24:55 -03:00
#endif // CONFIG_HAL_BOARD