2016-02-17 21:25:25 -04:00
|
|
|
#pragma once
|
2012-11-28 21:53:15 -04:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include "AP_HAL_Namespace.h"
|
2012-11-28 21:53:15 -04:00
|
|
|
|
2019-02-11 01:39:37 -04:00
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
|
2016-11-03 07:32:09 -03:00
|
|
|
#define HAL_SEMAPHORE_BLOCK_FOREVER 0
|
2012-11-28 21:53:15 -04:00
|
|
|
|
2013-01-02 20:27:01 -04:00
|
|
|
class AP_HAL::Semaphore {
|
|
|
|
public:
|
2020-10-12 03:06:08 -03:00
|
|
|
|
|
|
|
Semaphore() {}
|
|
|
|
|
|
|
|
// do not allow copying
|
2022-09-30 06:50:43 -03:00
|
|
|
CLASS_NO_COPY(Semaphore);
|
2020-10-12 03:06:08 -03:00
|
|
|
|
2013-01-09 05:42:02 -04:00
|
|
|
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED = 0 ;
|
|
|
|
virtual bool take_nonblocking() WARN_IF_UNUSED = 0;
|
2018-05-24 20:33:24 -03:00
|
|
|
|
2020-12-23 22:02:11 -04:00
|
|
|
// a variant that blocks forever
|
2018-05-24 20:33:24 -03:00
|
|
|
#pragma GCC diagnostic push
|
|
|
|
#pragma GCC diagnostic ignored "-Wunused-result"
|
|
|
|
virtual void take_blocking() { take(HAL_SEMAPHORE_BLOCK_FOREVER); };
|
|
|
|
#pragma GCC diagnostic pop
|
|
|
|
|
2013-01-02 20:27:01 -04:00
|
|
|
virtual bool give() = 0;
|
2016-11-19 01:47:50 -04:00
|
|
|
virtual ~Semaphore(void) {}
|
2012-11-28 21:53:15 -04:00
|
|
|
};
|
2019-05-11 05:13:08 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
a method to make semaphores less error prone. The WITH_SEMAPHORE()
|
|
|
|
macro will block forever for a semaphore, and will automatically
|
|
|
|
release the semaphore when it goes out of scope
|
|
|
|
|
|
|
|
Note that we have two types of semaphores. A normal semaphore can
|
|
|
|
only be taken once. A recursive semaphore allows for the thread
|
|
|
|
holding the semaphore to take it again. It must be released the same
|
|
|
|
number of times it is taken.
|
|
|
|
|
|
|
|
The WITH_SEMAPHORE() macro can be used with either type of semaphore
|
|
|
|
*/
|
|
|
|
|
|
|
|
class WithSemaphore {
|
|
|
|
public:
|
|
|
|
WithSemaphore(AP_HAL::Semaphore *mtx, uint32_t line);
|
|
|
|
WithSemaphore(AP_HAL::Semaphore &mtx, uint32_t line);
|
|
|
|
|
|
|
|
~WithSemaphore();
|
|
|
|
private:
|
|
|
|
AP_HAL::Semaphore &_mtx;
|
|
|
|
};
|
|
|
|
|
|
|
|
// From: https://stackoverflow.com/questions/19666142/why-is-a-level-of-indirection-needed-for-this-concatenation-macro
|
|
|
|
#define WITH_SEMAPHORE( sem ) JOIN( sem, __LINE__, __COUNTER__ )
|
|
|
|
#define JOIN( sem, line, counter ) _DO_JOIN( sem, line, counter )
|
|
|
|
#define _DO_JOIN( sem, line, counter ) WithSemaphore _getsem ## counter(sem, line)
|