ardupilot/libraries/AP_HAL_Linux/Semaphores.h

22 lines
397 B
C
Raw Normal View History

#pragma once
2013-09-22 03:01:24 -03:00
#include <AP_HAL/AP_HAL_Boards.h>
#include <stdint.h>
#include <AP_HAL/AP_HAL_Macros.h>
#include <AP_HAL/Semaphores.h>
#include <pthread.h>
2013-09-22 03:01:24 -03:00
namespace Linux {
class Semaphore : public AP_HAL::Semaphore {
2013-09-22 03:01:24 -03:00
public:
2018-08-19 22:09:05 -03:00
Semaphore();
bool give() override;
bool take(uint32_t timeout_ms) override;
bool take_nonblocking() override;
2018-08-19 22:09:05 -03:00
protected:
pthread_mutex_t _lock;
2013-09-22 03:01:24 -03:00
};
}