APM:Libraries
Semaphores.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #include "Semaphores.h"
4 
5 extern const AP_HAL::HAL& hal;
6 
7 using namespace Linux;
8 
10 {
11  return pthread_mutex_unlock(&_lock) == 0;
12 }
13 
14 bool Semaphore::take(uint32_t timeout_ms)
15 {
16  if (timeout_ms == HAL_SEMAPHORE_BLOCK_FOREVER) {
17  return pthread_mutex_lock(&_lock) == 0;
18  }
19  if (take_nonblocking()) {
20  return true;
21  }
22  uint64_t start = AP_HAL::micros64();
23  do {
24  hal.scheduler->delay_microseconds(200);
25  if (take_nonblocking()) {
26  return true;
27  }
28  } while ((AP_HAL::micros64() - start) < timeout_ms*1000);
29  return false;
30 }
31 
33 {
34  return pthread_mutex_trylock(&_lock) == 0;
35 }
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
bool take(uint32_t timeout_ms)
Definition: Semaphores.cpp:14
uint64_t micros64()
Definition: system.cpp:162
bool take_nonblocking()
Definition: Semaphores.cpp:32
virtual void delay_microseconds(uint16_t us)=0
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
pthread_mutex_t _lock
Definition: Semaphores.h:20