mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
0816937ab1
this provides RC onput, RC output, scheduling, storage, UARTs and all necessary support routines to fly ArduPilot on QURT
23 lines
513 B
C++
23 lines
513 B
C++
#pragma once
|
|
|
|
#include <AP_HAL/AP_HAL_Boards.h>
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_QURT
|
|
#include "AP_HAL_QURT.h"
|
|
#include <pthread.h>
|
|
|
|
class QURT::Semaphore : public AP_HAL::Semaphore {
|
|
public:
|
|
Semaphore() {
|
|
HAP_PRINTF("%s constructor", __FUNCTION__);
|
|
pthread_mutex_init(&_lock, NULL);
|
|
HAP_PRINTF("%s constructor2", __FUNCTION__);
|
|
}
|
|
bool give();
|
|
bool take(uint32_t timeout_ms);
|
|
bool take_nonblocking();
|
|
private:
|
|
pthread_mutex_t _lock;
|
|
};
|
|
#endif // CONFIG_HAL_BOARD
|