mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: added take_blocking() method
this avoids the need to check return result
This commit is contained in:
parent
49dfccbcee
commit
e2ea654b77
|
@ -8,6 +8,13 @@ class AP_HAL::Semaphore {
|
||||||
public:
|
public:
|
||||||
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED = 0 ;
|
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED = 0 ;
|
||||||
virtual bool take_nonblocking() WARN_IF_UNUSED = 0;
|
virtual bool take_nonblocking() WARN_IF_UNUSED = 0;
|
||||||
|
|
||||||
|
// a varient that blocks forever
|
||||||
|
#pragma GCC diagnostic push
|
||||||
|
#pragma GCC diagnostic ignored "-Wunused-result"
|
||||||
|
virtual void take_blocking() { take(HAL_SEMAPHORE_BLOCK_FOREVER); };
|
||||||
|
#pragma GCC diagnostic pop
|
||||||
|
|
||||||
virtual bool give() = 0;
|
virtual bool give() = 0;
|
||||||
virtual ~Semaphore(void) {}
|
virtual ~Semaphore(void) {}
|
||||||
};
|
};
|
||||||
|
|
Loading…
Reference in New Issue