Semaphores.cpp 1.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051
  1. #include <AP_HAL/AP_HAL.h>
  2. #include "Semaphores.h"
  3. extern const AP_HAL::HAL& hal;
  4. using namespace Linux;
  5. // construct a semaphore
  6. Semaphore::Semaphore()
  7. {
  8. pthread_mutex_init(&_lock, nullptr);
  9. }
  10. // construct a recursive semaphore (allows a thread to take it more than once)
  11. Semaphore_Recursive::Semaphore_Recursive()
  12. {
  13. pthread_mutexattr_t attr;
  14. pthread_mutexattr_init(&attr);
  15. pthread_mutexattr_settype(&attr, PTHREAD_MUTEX_RECURSIVE);
  16. pthread_mutex_init(&_lock, &attr);
  17. }
  18. bool Semaphore::give()
  19. {
  20. return pthread_mutex_unlock(&_lock) == 0;
  21. }
  22. bool Semaphore::take(uint32_t timeout_ms)
  23. {
  24. if (timeout_ms == HAL_SEMAPHORE_BLOCK_FOREVER) {
  25. return pthread_mutex_lock(&_lock) == 0;
  26. }
  27. if (take_nonblocking()) {
  28. return true;
  29. }
  30. uint64_t start = AP_HAL::micros64();
  31. do {
  32. hal.scheduler->delay_microseconds(200);
  33. if (take_nonblocking()) {
  34. return true;
  35. }
  36. } while ((AP_HAL::micros64() - start) < timeout_ms*1000);
  37. return false;
  38. }
  39. bool Semaphore::take_nonblocking()
  40. {
  41. return pthread_mutex_trylock(&_lock) == 0;
  42. }