Semaphores.h 1.6 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950
  1. #pragma once
  2. #include "AP_HAL_Namespace.h"
  3. #include <AP_Common/AP_Common.h>
  4. #define HAL_SEMAPHORE_BLOCK_FOREVER 0
  5. class AP_HAL::Semaphore {
  6. public:
  7. virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED = 0 ;
  8. virtual bool take_nonblocking() WARN_IF_UNUSED = 0;
  9. // a varient that blocks forever
  10. #pragma GCC diagnostic push
  11. #pragma GCC diagnostic ignored "-Wunused-result"
  12. virtual void take_blocking() { take(HAL_SEMAPHORE_BLOCK_FOREVER); };
  13. #pragma GCC diagnostic pop
  14. virtual bool give() = 0;
  15. virtual ~Semaphore(void) {}
  16. };
  17. /*
  18. a method to make semaphores less error prone. The WITH_SEMAPHORE()
  19. macro will block forever for a semaphore, and will automatically
  20. release the semaphore when it goes out of scope
  21. Note that we have two types of semaphores. A normal semaphore can
  22. only be taken once. A recursive semaphore allows for the thread
  23. holding the semaphore to take it again. It must be released the same
  24. number of times it is taken.
  25. The WITH_SEMAPHORE() macro can be used with either type of semaphore
  26. */
  27. class WithSemaphore {
  28. public:
  29. WithSemaphore(AP_HAL::Semaphore *mtx, uint32_t line);
  30. WithSemaphore(AP_HAL::Semaphore &mtx, uint32_t line);
  31. ~WithSemaphore();
  32. private:
  33. AP_HAL::Semaphore &_mtx;
  34. };
  35. // From: https://stackoverflow.com/questions/19666142/why-is-a-level-of-indirection-needed-for-this-concatenation-macro
  36. #define WITH_SEMAPHORE( sem ) JOIN( sem, __LINE__, __COUNTER__ )
  37. #define JOIN( sem, line, counter ) _DO_JOIN( sem, line, counter )
  38. #define _DO_JOIN( sem, line, counter ) WithSemaphore _getsem ## counter(sem, line)