9 #pragma GCC optimize ("O2") 24 .clk = RCC_APB2Periph_USART1,
31 .gpio_af = GPIO_AF_USART1
36 #if defined(BOARD_USART2_RX_PIN) && defined(BOARD_USART2_RX_PIN) 43 .clk = RCC_APB1Periph_USART2,
48 .rx_pin = BOARD_USART2_RX_PIN,
49 .tx_pin = BOARD_USART2_TX_PIN,
50 .gpio_af = GPIO_AF_USART2
64 .clk = RCC_APB1Periph_USART3,
71 .gpio_af = GPIO_AF_USART3
76 #if defined(BOARD_USART4_RX_PIN) && defined(BOARD_USART4_TX_PIN) 83 .clk = RCC_APB1Periph_UART4,
90 .gpio_af = GPIO_AF_UART4
96 #if defined(BOARD_USART5_RX_PIN) && defined(BOARD_USART5_TX_PIN) 103 .clk = RCC_APB1Periph_UART5,
110 .gpio_af = GPIO_AF_UART5
116 #if defined(BOARD_USART6_RX_PIN) && defined(BOARD_USART6_TX_PIN) 123 .clk = RCC_APB2Periph_USART6,
124 .txrb = &usart6_txrb,
125 .rxrb = &usart6_rxrb,
130 .gpio_af = GPIO_AF_USART6
139 #if defined(BOARD_USART2_RX_PIN) && defined(BOARD_USART2_RX_PIN) 145 #if defined(BOARD_USART4_RX_PIN) && defined(BOARD_USART4_TX_PIN) 150 #if defined(BOARD_USART5_RX_PIN) && defined(BOARD_USART5_TX_PIN) 155 #if defined(BOARD_USART6_RX_PIN) && defined(BOARD_USART6_TX_PIN) 166 #if defined(BOARD_USART2_RX_PIN) && defined(BOARD_USART2_RX_PIN) 170 #if defined(BOARD_USART4_RX_PIN) && defined(BOARD_USART4_TX_PIN) 173 #if defined(BOARD_USART5_RX_PIN) && defined(BOARD_USART5_TX_PIN) 176 #if defined(BOARD_USART6_RX_PIN) && defined(BOARD_USART6_TX_PIN) 193 RCC_APB2PeriphClockCmd(dev->
clk, ENABLE);
195 RCC_APB1PeriphClockCmd(dev->
clk, ENABLE);
200 uint16_t stopBits, uint16_t parity, uint16_t mode, uint16_t hardwareFlowControl)
209 assert_param(IS_USART_HARDWARE_FLOW_CONTROL(hardwareFlowControl));
223 USART_OverSampling8Cmd(dev->
USARTx, ENABLE);
225 USART_ClockInitTypeDef USART_InitClock;
226 USART_ClockStructInit(&USART_InitClock);
227 USART_ClockInit(dev->
USARTx, &USART_InitClock);
229 USART_InitTypeDef USART_config;
230 USART_StructInit(&USART_config);
231 USART_config.USART_BaudRate = baudRate;
232 USART_config.USART_WordLength = wordLength;
233 USART_config.USART_StopBits = stopBits;
234 USART_config.USART_Parity = parity;
235 USART_config.USART_Mode = mode;
236 USART_config.USART_HardwareFlowControl = hardwareFlowControl;
238 USART_Init(dev->
USARTx, &USART_config);
244 if(mode & USART_Mode_Rx) {
245 USART_ClearFlag(dev->
USARTx, USART_FLAG_RXNE);
249 if(mode & USART_Mode_Tx) {
250 USART_ClearFlag(dev->
USARTx, USART_FLAG_TC);
264 uint32_t tosend = len;
287 digits[i++] = val % 10 +
'0';
307 uint16_t sr = dev->
USARTx->SR;
309 #ifdef USART_SAFE_INSERT 329 if(t>max_isr_time) max_isr_time=t;
339 uint16_t sr = dev->
USARTx->SR;
357 if(t>max_isr_time) max_isr_time=t;
368 #if defined(BOARD_USART2_RX_PIN) && defined(BOARD_USART2_RX_PIN) 382 #if defined( BOARD_USART4_RX_PIN) && defined( BOARD_USART4_TX_PIN) 390 #if defined( BOARD_USART5_RX_PIN) && defined( BOARD_USART5_TX_PIN) 398 #if defined( BOARD_USART6_RX_PIN) && defined( BOARD_USART6_TX_PIN) #define BOARD_USART5_TX_PIN
static uint32_t stopwatch_getticks()
void usart_putudec(const usart_dev *dev, uint32_t val)
Transmit an unsigned integer to the specified serial port in decimal format.
static void rb_insert(ring_buffer *rb, uint8_t element)
#define BOARD_USART3_TX_PIN
static ring_buffer usart1_txrb IN_CCM
static int rb_is_empty(ring_buffer *rb)
Returns true if and only if the ring buffer is empty.
#define assert_param(expr)
void usart_setup(const usart_dev *dev, uint32_t baudRate, uint16_t wordLength, uint16_t stopBits, uint16_t parity, uint16_t mode, uint16_t hardwareFlowControl)
Configure a serial port's baud rate.
#define BOARD_USART1_TX_PIN
uint8_t tx_buf[USART_TX_BUF_SIZE]
void USART3_IRQHandler(void)
static uint8_t rb_remove(ring_buffer *rb)
Remove and return the first item from a ring buffer.
void UART5_IRQHandler(void)
void USART2_IRQHandler(void)
void UART4_IRQHandler(void)
const usart_dev *const _UART4
#define USART_RX_BUF_SIZE
const usart_dev *const UARTS[]
#define UART_INT_PRIORITY
#define BOARD_USART5_RX_PIN
static const usart_dev usart3
static int rb_is_full(ring_buffer *rb)
Returns true if and only if the ring buffer is full.
#define USART_MASK_RXNEIE
static AP_HAL::OwnPtr< AP_HAL::Device > dev
static uint32_t usart_putc(const usart_dev *dev, uint8_t bt)
Transmit one character on a serial port.
static void rb_init(ring_buffer *rb, uint16_t size, uint8_t *buf)
#define BOARD_USART1_RX_PIN
static const usart_dev usart1
void USART1_IRQHandler(void)
void enable_nvic_irq(uint8_t irq, uint8_t prio)
#define USART_MASK_IDLEIE
#define USART_TX_BUF_SIZE
uint32_t usart_tx(const usart_dev *dev, const uint8_t *buf, uint32_t len)
Nonblocking USART transmit.
uint8_t rx_buf[USART_RX_BUF_SIZE]
static void usart_tx_irq(const usart_dev *dev)
static int rb_safe_insert(ring_buffer *rb, uint8_t element)
Attempt to insert an element into a ring buffer.
const usart_dev *const _USART1
const usart_dev *const _USART3
#define USART_MASK2_LBDIE
#define USART_MASK3_CTSIE
#define BOARD_USART6_TX_PIN
void usart_init(const usart_dev *dev)
Initialize a serial port.
static void usart_disable(const usart_dev *dev)
Turn off a serial port.
void usart_foreach(void(*fn)(const usart_dev *))
Call a function on each USART.
const usart_dev *const _UART5
static void usart_rx_irq(const usart_dev *dev)
#define BOARD_USART6_RX_PIN
#define BOARD_USART4_TX_PIN
#define BOARD_USART4_RX_PIN
void USART6_IRQHandler(void)
static int rb_push_insert(ring_buffer *rb, uint8_t element)
Append an item onto the end of a non-full ring buffer.
void revo_call_handler(Handler h, uint32_t arg)
#define BOARD_USART3_RX_PIN
const usart_dev *const _USART6