4 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 32 void begin(uint32_t b, uint16_t rxS, uint16_t txS);
51 int16_t
read()
override;
54 size_t write(uint8_t c);
static bool _select_check(int)
bool set_unbuffered_writes(bool on) override
void _tcp_start_connection(uint16_t port, bool wait_for_connection)
static uint8_t buffer[SRXL_FRAMELEN_MAX]
void _tcp_start_client(const char *address, uint16_t port)
static void _set_nonblocking(int)
bool set_speed(int speed)
UARTDriver(const uint8_t portNumber, SITL_State *sitlState)
void configure_parity(uint8_t v) override
uint64_t receive_time_constraint_us(uint16_t nbytes) override
void _check_connection(void)
enum flow_control get_flow_control(void)
uint32_t available() override
const char * _tcp_client_addr
uint32_t txspace() override
static SITL_State sitlState
static UARTDriver * from(AP_HAL::UARTDriver *uart)
uint64_t _receive_timestamp
void _uart_start_connection(void)
void set_blocking_writes(bool blocking)
void set_stop_bits(int n) override