20 void begin(uint32_t b);
21 void begin(uint32_t b, uint16_t rxS, uint16_t txS);
31 int16_t
read()
override;
34 size_t write(uint8_t c);
98 virtual int _write_fd(
const uint8_t *buf, uint16_t n);
99 virtual int _read_fd(uint8_t *buf, uint16_t n);
uint64_t _last_write_time
AP_HAL::OwnPtr< SerialDevice > _parseDevicePath(const char *arg)
void set_blocking_writes(bool blocking)
static UARTDriver * from(AP_HAL::UARTDriver *uart)
bool _write_pending_bytes(void)
virtual void set_flow_control(enum flow_control flow_control_setting) override
void _allocate_buffers(uint16_t rxS, uint16_t txS)
uint8_t _receive_timestamp_idx
virtual void _timer_tick(void) override
void set_device_path(const char *path)
uint64_t _receive_timestamp[2]
virtual AP_HAL::UARTDriver::flow_control get_flow_control(void)
uint64_t receive_time_constraint_us(uint16_t nbytes) override
virtual void set_flow_control(AP_HAL::UARTDriver::flow_control flow_control_setting)
volatile bool _initialised
uint32_t txspace() override
uint32_t available() override
virtual int _write_fd(const uint8_t *buf, uint16_t n)
virtual int _read_fd(uint8_t *buf, uint16_t n)
AP_HAL::OwnPtr< SerialDevice > _device
void _deallocate_buffers()
virtual enum flow_control get_flow_control(void) override