25 #define RX_BOUNCE_BUFSIZE 128 26 #define TX_BOUNCE_BUFSIZE 64 28 #define UART_MAX_DRIVERS 7 34 void begin(uint32_t b);
35 void begin(uint32_t b, uint16_t rxS, uint16_t txS);
45 int16_t
read()
override;
48 size_t write(uint8_t c);
56 size_t write_locked(
const uint8_t *buffer,
size_t size, uint32_t key)
override;
120 #if HAL_USE_SERIAL == TRUE 164 static void tx_complete(
void*
self, uint32_t flags);
static void rxbuff_full_irq(void *self, uint32_t flags)
bool _lock_rx_in_timer_tick
const thread_t * _uart_owner_thd
bool wait_timeout(uint16_t n, uint32_t timeout_ms) override
static void rx_irq_cb(void *sd)
void set_stop_bits(int n) override
void configure_parity(uint8_t v) override
void dma_tx_allocate(Shared_DMA *ctx)
static thread_t * uart_thread_ctx
#define RX_BOUNCE_BUFSIZE
enum flow_control _flow_control
BaseSequentialStream * serial
static uint8_t buffer[SRXL_FRAMELEN_MAX]
bool lock_port(uint32_t key) override
enum flow_control get_flow_control(void) override
const stm32_dma_stream_t * rxdma
void write_pending_bytes_DMA(uint32_t n)
uint8_t _receive_timestamp_idx
void dma_tx_deallocate(Shared_DMA *ctx)
uint32_t _first_write_started_us
uint64_t _receive_timestamp[2]
struct ChibiOS::UARTDriver::@41 _wait
#define TX_BOUNCE_BUFSIZE
bool set_unbuffered_writes(bool on) override
void set_blocking_writes(bool blocking)
static const SerialDef _serial_tab[]
uint32_t txspace() override
uint32_t _last_write_completed_us
uint32_t dma_rx_channel_id
size_t write_locked(const uint8_t *buffer, size_t size, uint32_t key) override
void check_dma_tx_completion(void)
static void uart_thread(void *)
static uint32_t last_thread_run_us
const stm32_dma_stream_t * txdma
void receive_timestamp_update(void)
void update_rts_line(void)
uint32_t available() override
void set_flow_control(enum flow_control flow_control) override
void write_pending_bytes(void)
uint8_t rx_bounce_buf[RX_BOUNCE_BUFSIZE]
uint8_t tx_bounce_buf[TX_BOUNCE_BUFSIZE]
uint8_t get_index(void) const
uint64_t receive_time_constraint_us(uint16_t nbytes) override
static UARTDriver * uart_drivers[UART_MAX_DRIVERS]
void _timer_tick(void) override
static void tx_complete(void *self, uint32_t flags)
void write_pending_bytes_NODMA(uint32_t n)
uint32_t dma_tx_channel_id