mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_Common: make WithSemaphore use an AP_HAL::Semaphore reference
We don't need the specialized one inside WithSemaphore, so use the abstract one which allows us to more easily convert between current API and the HAL_Semaphore one. While at it also remove additional pragma and allow constructor to receive a pointer for convenience (we will just dereference it).
This commit is contained in:
parent
cd9b08dbae
commit
1715714488
@ -14,8 +14,6 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
a method to make semaphores less error prone. The WITH_SEMAPHORE()
|
||||
macro will block forever for a semaphore, and will automatically
|
||||
@ -28,11 +26,16 @@
|
||||
|
||||
The WITH_SEMAPHORE() macro can be used with either type of semaphore
|
||||
*/
|
||||
|
||||
namespace AP_HAL {
|
||||
class Semaphore;
|
||||
}
|
||||
|
||||
class WithSemaphore {
|
||||
public:
|
||||
WithSemaphore(HAL_Semaphore &mtx) :
|
||||
_mtx(mtx)
|
||||
{
|
||||
WithSemaphore(AP_HAL::Semaphore *mtx) : WithSemaphore(*mtx) { }
|
||||
|
||||
WithSemaphore(AP_HAL::Semaphore &mtx) : _mtx(mtx) {
|
||||
_mtx.take_blocking();
|
||||
}
|
||||
|
||||
@ -40,7 +43,7 @@ public:
|
||||
_mtx.give();
|
||||
}
|
||||
private:
|
||||
HAL_Semaphore &_mtx;
|
||||
AP_HAL::Semaphore &_mtx;
|
||||
};
|
||||
|
||||
#define WITH_SEMAPHORE(sem) WithSemaphore _getsem(sem)
|
||||
|
Loading…
Reference in New Issue
Block a user