ardupilot/libraries/AP_HAL_Linux/RPIOUARTDriver.h

40 lines
763 B
C
Raw Normal View History

#pragma once
2015-08-18 00:29:58 -03:00
#include "AP_HAL_Linux.h"
#include "UARTDriver.h"
#include <AP_HAL/SPIDevice.h>
2015-08-18 00:29:58 -03:00
class Linux::RPIOUARTDriver : public Linux::UARTDriver {
2015-08-18 00:29:58 -03:00
public:
RPIOUARTDriver();
static RPIOUARTDriver *from(AP_HAL::UARTDriver *uart) {
return static_cast<RPIOUARTDriver*>(uart);
}
2015-08-18 00:29:58 -03:00
void begin(uint32_t b, uint16_t rxS, uint16_t txS);
void _timer_tick(void);
bool isExternal(void);
protected:
int _write_fd(const uint8_t *buf, uint16_t n);
int _read_fd(uint8_t *buf, uint16_t n);
private:
bool _in_timer;
bool sem_take_nonblocking();
void sem_give();
AP_HAL::OwnPtr<AP_HAL::SPIDevice> _dev;
2015-08-18 00:29:58 -03:00
uint32_t _last_update_timestamp;
bool _external;
bool _need_set_baud;
uint32_t _baudrate;
};