mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: mark semaphore take operations as WARN_IF_UNUSED
this prevents common bugs
This commit is contained in:
parent
90523ae975
commit
e76c77e86a
|
@ -8,8 +8,8 @@
|
|||
|
||||
class AP_HAL::Semaphore {
|
||||
public:
|
||||
virtual bool take(uint32_t timeout_ms) = 0;
|
||||
virtual bool take_nonblocking() = 0;
|
||||
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED = 0 ;
|
||||
virtual bool take_nonblocking() WARN_IF_UNUSED = 0;
|
||||
virtual bool give() = 0;
|
||||
};
|
||||
|
||||
|
|
Loading…
Reference in New Issue