APM:Libraries
Semaphores.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
4 
5 #include "Semaphores.h"
6 #include <nuttx/arch.h>
7 
8 extern const AP_HAL::HAL& hal;
9 
10 using namespace VRBRAIN;
11 
13 {
14  return pthread_mutex_unlock(&_lock) == 0;
15 }
16 
17 bool Semaphore::take(uint32_t timeout_ms)
18 {
19  if (up_interrupt_context()) {
20  // don't ever wait on a semaphore in interrupt context
21  return take_nonblocking();
22  }
23  if (timeout_ms == HAL_SEMAPHORE_BLOCK_FOREVER) {
24  return pthread_mutex_lock(&_lock) == 0;
25  }
26  if (take_nonblocking()) {
27  return true;
28  }
29  uint64_t start = AP_HAL::micros64();
30  do {
31  hal.scheduler->delay_microseconds(200);
32  if (take_nonblocking()) {
33  return true;
34  }
35  } while ((AP_HAL::micros64() - start) < timeout_ms*1000);
36  return false;
37 }
38 
40 {
41  return pthread_mutex_trylock(&_lock) == 0;
42 }
43 
44 #endif // CONFIG_HAL_BOARD
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:17
uint64_t micros64()
Definition: system.cpp:162
virtual void delay_microseconds(uint16_t us)=0
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
pthread_mutex_t _lock
Definition: Semaphores.h:18