From a2247a3400393a62b52aaf7d4efcd9088f5591ac Mon Sep 17 00:00:00 2001 From: Hauke Petersen Date: Wed, 28 Oct 2015 11:46:08 +0100 Subject: [PATCH] cpu/stm32f4: significantly optimized UART driver --- cpu/stm32f4/include/periph_cpu.h | 125 +++++++++++- cpu/stm32f4/periph/uart.c | 333 ++++++++++++++----------------- 2 files changed, 262 insertions(+), 196 deletions(-) diff --git a/cpu/stm32f4/include/periph_cpu.h b/cpu/stm32f4/include/periph_cpu.h index 4131cef10a..39de8e4f33 100644 --- a/cpu/stm32f4/include/periph_cpu.h +++ b/cpu/stm32f4/include/periph_cpu.h @@ -16,11 +16,10 @@ * @author Hauke Petersen */ -#ifndef CPU_PERIPH_H_ -#define CPU_PERIPH_H_ +#ifndef PERIPH_CPU_H +#define PERIPH_CPU_H #include "cpu.h" -#include "periph/dev_enums.h" #ifdef __cplusplus extern "C" { @@ -44,6 +43,15 @@ typedef uint32_t gpio_t; */ #define GPIO_PIN(x, y) ((GPIOA_BASE + (x << 10)) | y) +/** + * @brief declare needed generic SPI functions + * @{ + */ +#define PERIPH_SPI_NEEDS_TRANSFER_BYTES +#define PERIPH_SPI_NEEDS_TRANSFER_REG +#define PERIPH_SPI_NEEDS_TRANSFER_REGS +/** @} */ + /** * @brief Available ports on the STM32F4 family */ @@ -80,6 +88,22 @@ typedef enum { GPIO_AF14 /**< use alternate function 14 */ } gpio_af_t; +/** + * @brief Structure for UART configuration data + * @{ + */ +typedef struct { + USART_TypeDef *dev; /**< UART device base register address */ + uint32_t rcc_mask; /**< bit in clock enable register */ + gpio_t rx_pin; /**< RX pin */ + gpio_t tx_pin; /**< TX pin */ + gpio_af_t af; /**< alternate pin function to use */ + uint8_t irqn; /**< IRQ channel */ + uint8_t dma_stream; /**< DMA stream used for TX */ + uint8_t dma_chan; /**< DMA channel used for TX */ +} uart_conf_t; +/** @} */ + /** * @brief Configure the alternate function for the given pin * @@ -91,17 +115,98 @@ typedef enum { void gpio_init_af(gpio_t pin, gpio_af_t af); /** - * @brief declare needed generic SPI functions - * @{ + * @brief Power on the DMA device the given stream belongs to + * + * @param[in] stream logical DMA stream */ -#define PERIPH_SPI_NEEDS_TRANSFER_BYTES -#define PERIPH_SPI_NEEDS_TRANSFER_REG -#define PERIPH_SPI_NEEDS_TRANSFER_REGS -/** @} */ +static inline void dma_poweron(int stream) +{ + if (stream < 8) { + RCC->AHB1ENR |= RCC_AHB1ENR_DMA1EN; + } else { + RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN; + } +} + +/** + * @brief Get DMA base register + * + * For simplifying DMA stream handling, we map the DMA channels transparently to + * one integer number, such that DMA1 stream0 equals 0, DMA2 stream0 equals 8, + * DMA2 stream 7 equals 15 and so on. + * + * @param[in] stream logical DMA stream + */ +static inline DMA_TypeDef *dma_base(int stream) +{ + return (stream < 8) ? DMA1 : DMA2; +} + +/** + * @brief Get the DMA stream base address + * + * @param[in] stream logical DMA stream + * + * @return base address for the selected DMA stream + */ +static inline DMA_Stream_TypeDef *dma_stream(int stream) +{ + uint32_t base = (uint32_t)dma_base(stream); + return (DMA_Stream_TypeDef *)(base + (0x10 + (0x18 * (stream & 0x7)))); +} + +/** + * @brief Select high or low DMA interrupt register based on stream number + * + * @param[in] stream logical DMA stream + * + * @return 0 for streams 0-3, 1 for streams 3-7 + */ +static inline int dma_hl(int stream) +{ + return ((stream & 0x4) >> 2); +} + +/** + * @brief Get the interrupt flag clear bit position in the DMA LIFCR register + * + * @param[in] stream logical DMA stream + */ +static inline uint32_t dma_ifc(int stream) +{ + switch (stream & 0x3) { + case 0: + return (1 << 5); + case 1: + return (1 << 11); + case 2: + return (1 << 21); + case 3: + return (1 << 27); + default: + return 0; + } +} + +static inline void dma_isr_enable(int stream) +{ + if (stream < 7) { + NVIC_EnableIRQ((IRQn_Type)((int)DMA1_Stream0_IRQn + stream)); + } + else if (stream == 8) { + NVIC_EnableIRQ(DMA1_Stream7_IRQn); + } + else if (stream < 14) { + NVIC_EnableIRQ((IRQn_Type)((int)DMA2_Stream0_IRQn + stream)); + } + else if (stream < 17) { + NVIC_EnableIRQ((IRQn_Type)((int)DMA2_Stream5_IRQn + stream)); + } +} #ifdef __cplusplus } #endif -#endif /* CPU_PERIPH_H_ */ +#endif /* PERIPH_CPU_H */ /** @} */ diff --git a/cpu/stm32f4/periph/uart.c b/cpu/stm32f4/periph/uart.c index 108bb029a3..b3c367fd13 100644 --- a/cpu/stm32f4/periph/uart.c +++ b/cpu/stm32f4/periph/uart.c @@ -1,9 +1,9 @@ /* * Copyright (C) 2014-2015 Freie Universität Berlin * - * This file is subject to the terms and conditions of the GNU Lesser General - * Public License v2.1. See the file LICENSE in the top level directory for more - * details. + * This file is subject to the terms and conditions of the GNU Lesser + * General Public License v2.1. See the file LICENSE in the top level + * directory for more details. */ /** @@ -22,250 +22,211 @@ #include "cpu.h" #include "thread.h" #include "sched.h" -#include "periph_conf.h" +#include "mutex.h" #include "periph/uart.h" +#include "periph/gpio.h" /** - * @brief Allocate memory to store the callback functions. + * @brief Allocate memory to store the callback functions */ -static uart_isr_ctx_t uart_config[UART_NUMOF]; +static uart_isr_ctx_t uart_ctx[UART_NUMOF]; /** - * @todo Remodel this UART driver and merge init functions... + * @brief Get the base register for the given UART device */ -static int init_base(uart_t uart, uint32_t baudrate); +static inline USART_TypeDef *_dev(uart_t uart) +{ + return uart_config[uart].dev; +} + +/** + * @brief Transmission locks + */ +static mutex_t tx_sync[UART_NUMOF]; + +/** + * @brief Find out which peripheral bus the UART device is connected to + * + * @return 1: APB1 + * @return 2: APB2 + */ +static inline int _bus(uart_t uart) +{ + return (uart_config[uart].rcc_mask < RCC_APB1ENR_USART2EN) ? 2 : 1; +} int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, void *arg) { - /* do basic initialization */ - int res = init_base(uart, baudrate); - if (res < 0) { - return res; - } - - /* remember callback addresses */ - uart_config[uart].rx_cb = rx_cb; - uart_config[uart].arg = arg; - - /* enable receive interrupt */ - switch (uart) { -#if UART_0_EN - case UART_0: - NVIC_SetPriority(UART_0_IRQ_CHAN, UART_IRQ_PRIO); - NVIC_EnableIRQ(UART_0_IRQ_CHAN); - UART_0_DEV->CR1 |= USART_CR1_RXNEIE; - break; -#endif -#if UART_1_EN - case UART_1: - NVIC_SetPriority(UART_1_IRQ_CHAN, UART_IRQ_PRIO); - NVIC_EnableIRQ(UART_1_IRQ_CHAN); - UART_1_DEV->CR1 |= USART_CR1_RXNEIE; - break; -#endif -#if UART_2_EN - case UART_2: - NVIC_SetPriority(UART_2_IRQ_CHAN, UART_IRQ_PRIO); - NVIC_EnableIRQ(UART_2_IRQ_CHAN); - UART_2_DEV->CR1 |= USART_CR1_RXNEIE; - break; -#endif - } - - return 0; -} - -static int init_base(uart_t uart, uint32_t baudrate) -{ - USART_TypeDef *dev = 0; - GPIO_TypeDef *port = 0; - uint32_t tx_pin = 0; - uint32_t rx_pin = 0; - uint8_t af = 0; - uint32_t clk = 0; + USART_TypeDef *dev; + DMA_Stream_TypeDef *stream; + float divider; uint16_t mantissa; uint8_t fraction; - switch (uart) { -#if UART_0_EN - case UART_0: - dev = UART_0_DEV; - port = UART_0_PORT; - clk = UART_0_CLK; - tx_pin = UART_0_TX_PIN; - rx_pin = UART_0_RX_PIN; - af = UART_0_AF; - UART_0_CLKEN(); - UART_0_PORT_CLKEN(); - break; -#endif -#if UART_1_EN - case UART_1: - dev = UART_1_DEV; - port = UART_1_PORT; - clk = UART_1_CLK; - tx_pin = UART_1_TX_PIN; - rx_pin = UART_1_RX_PIN; - af = UART_1_AF; - UART_1_CLKEN(); - UART_1_PORT_CLKEN(); - break; -#endif -#if UART_2_EN - case UART_2: - dev = UART_2_DEV; - port = UART_2_PORT; - clk = UART_2_CLK; - tx_pin = UART_2_TX_PIN; - rx_pin = UART_2_RX_PIN; - af = UART_2_AF; - UART_2_CLKEN(); - UART_2_PORT_CLKEN(); - break; -#endif - default: - return -1; + /* check if given UART device does exist */ + if (uart < 0 || uart >= UART_NUMOF) { + return -1; } - /* configure pp mode with no pull for RX and TX pins */ - port->OTYPER &= ~(1 << rx_pin | 1 << tx_pin); - port->PUPDR &= ~(3 << (rx_pin * 2) | 3 << (tx_pin * 2)); + /* get UART base address */ + dev = _dev(uart); + /* remember callback addresses and argument */ + uart_ctx[uart].rx_cb = rx_cb; + uart_ctx[uart].arg = arg; + /* init tx lock */ + mutex_init(&tx_sync[uart]); + mutex_lock(&tx_sync[uart]); - /* configure RX and TX pins, set pin to use alternative function mode */ - port->MODER &= ~(3 << (rx_pin * 2) | 3 << (tx_pin * 2)); - port->MODER |= 2 << (rx_pin * 2) | 2 << (tx_pin * 2); - /* and assign alternative function */ - if (rx_pin < 8) { - port->AFR[0] &= ~(0xf << (rx_pin * 4)); - port->AFR[0] |= af << (rx_pin * 4); + /* configure pins */ + gpio_init(uart_config[uart].rx_pin, GPIO_DIR_IN, GPIO_NOPULL); + gpio_init(uart_config[uart].tx_pin, GPIO_DIR_OUT, GPIO_NOPULL); + gpio_init_af(uart_config[uart].rx_pin, uart_config[uart].af); + gpio_init_af(uart_config[uart].tx_pin, uart_config[uart].af); + /* enable UART clock */ + uart_poweron(uart); + + /* calculate and set baudrate */ + if (_bus(uart) == 1) { + divider = CLOCK_APB1 / (16 * baudrate); } else { - port->AFR[1] &= ~(0xf << ((rx_pin - 8) * 4)); - port->AFR[1] |= af << ((rx_pin - 8) * 4); + divider = CLOCK_APB2 / (16 * baudrate); } - if (tx_pin < 8) { - port->AFR[0] &= ~(0xf << (tx_pin * 4)); - port->AFR[0] |= af << (tx_pin * 4); - } - else { - port->AFR[1] &= ~(0xf << ((tx_pin - 8) * 4)); - port->AFR[1] |= af << ((tx_pin - 8) * 4); - } - - /* configure UART to mode 8N1 with given baudrate */ - clk /= baudrate; - mantissa = (uint16_t)(clk / 16); - fraction = (uint8_t)(clk - (mantissa * 16)); + mantissa = (uint16_t)divider; + fraction = (uint8_t)((divider - mantissa) * 16); dev->BRR = ((mantissa & 0x0fff) << 4) | (0x0f & fraction); - - /* enable receive and transmit mode */ - dev->CR3 = 0; + /* configure UART to 8N1 and enable receive and transmit mode */ + dev->CR3 = USART_CR3_DMAT; dev->CR2 = 0; dev->CR1 = USART_CR1_UE | USART_CR1_TE | USART_CR1_RE; - + /* configure the DMA stream for transmission */ + dma_poweron(uart_config[uart].dma_stream); + stream = dma_stream(uart_config[uart].dma_stream); + stream->CR = ((uart_config[uart].dma_chan << 25) | + DMA_SxCR_PL_0 | + DMA_SxCR_MINC | + DMA_SxCR_DIR_0 | + DMA_SxCR_TCIE); + stream->PAR = (uint32_t)&(dev->DR); + stream->FCR = 0; + /* enable global and receive interrupts */ + NVIC_EnableIRQ(uart_config[uart].irqn); + dma_isr_enable(uart_config[uart].dma_stream); + dev->CR1 |= USART_CR1_RXNEIE; return 0; } void uart_write(uart_t uart, const uint8_t *data, size_t len) { - USART_TypeDef *dev = 0; - - switch (uart) { -#if UART_0_EN - case UART_0: - dev = UART_0_DEV; - break; -#endif -#if UART_1_EN - case UART_1: - dev = UART_1_DEV; - break; -#endif -#if UART_2_EN - case UART_2: - dev = UART_2_DEV; - break; -#endif - default: - return; + /* in case we are inside an ISR, we need to send blocking */ + if (inISR()) { + /* send data by active waiting on the TXE flag */ + USART_TypeDef *dev = _dev(uart); + for (int i = 0; i < len; i++) { + while (!(dev->SR & USART_SR_TXE)); + dev->DR = data[i]; + } } - - for (size_t i = 0; i < len; i++) { - while (!(dev->SR & USART_SR_TXE)); - dev->DR = data[i]; + else { + DMA_Stream_TypeDef *stream = dma_stream(uart_config[uart].dma_stream); + /* configure and start DMA transfer */ + stream->M0AR = (uint32_t)data; + stream->NDTR = (uint16_t)len; + stream->CR |= DMA_SxCR_EN; + /* wait for transfer to complete */ + mutex_lock(&tx_sync[uart]); } } void uart_poweron(uart_t uart) { - switch (uart) { -#if UART_0_EN - case UART_0: - UART_0_CLKEN(); - break; -#endif -#if UART_1_EN - case UART_1: - UART_1_CLKEN(); - break; -#endif -#if UART_2_EN - case UART_2: - UART_2_CLKEN(); - break; -#endif + if (_bus(uart) == 1) { + RCC->APB1ENR |= uart_config[uart].rcc_mask; + } + else { + RCC->APB2ENR |= uart_config[uart].rcc_mask; } } void uart_poweroff(uart_t uart) { - switch (uart) { -#if UART_0_EN - case UART_0: - UART_0_CLKDIS(); - break; -#endif -#if UART_1_EN - case UART_1: - UART_1_CLKDIS(); - break; -#endif -#if UART_2_EN - case UART_2: - UART_2_CLKDIS(); - break; -#endif + if (_bus(uart) == 1) { + RCC->APB1ENR &= ~(uart_config[uart].rcc_mask); + } + else { + RCC->APB2ENR &= ~(uart_config[uart].rcc_mask); } } -static inline void irq_handler(uint8_t uartnum, USART_TypeDef *dev) +static inline void irq_handler(int uart, USART_TypeDef *dev) { if (dev->SR & USART_SR_RXNE) { char data = (char)dev->DR; - uart_config[uartnum].rx_cb(uart_config[uartnum].arg, data); + uart_ctx[uart].rx_cb(uart_ctx[uart].arg, data); } if (sched_context_switch_request) { thread_yield(); } } -#if UART_0_EN +static inline void dma_handler(int uart, int stream) +{ + /* clear DMA done flag */ + dma_base(stream)->IFCR[dma_hl(stream)] = dma_ifc(stream); + mutex_unlock(&tx_sync[uart]); + if (sched_context_switch_request) { + thread_yield(); + } +} + +#ifdef UART_0_ISR void UART_0_ISR(void) { - irq_handler(UART_0, UART_0_DEV); + irq_handler(0, uart_config[0].dev); +} + +void UART_0_DMA_ISR(void) +{ + dma_handler(0, uart_config[0].dma_stream); } #endif -#if UART_1_EN +#ifdef UART_1_ISR void UART_1_ISR(void) { - irq_handler(UART_1, UART_1_DEV); + irq_handler(1, uart_config[1].dev); +} + +void UART_1_DMA_ISR(void) +{ + dma_handler(1, uart_config[1].dma_stream); } #endif -#if UART_2_EN +#ifdef UART_2_ISR void UART_2_ISR(void) { - irq_handler(UART_2, UART_2_DEV); + irq_handler(2, uart_config[2].dev); +} +#endif + +#ifdef UART_3_ISR +void UART_3_ISR(void) +{ + irq_handler(3, uart_config[3].dev); +} +#endif + +#ifdef UART_4_ISR +void UART_4_ISR(void) +{ + irq_handler(4, uart_config[4].dev); +} +#endif + +#ifdef UART_5_ISR +void UART_5_ISR(void) +{ + irq_handler(5, uart_config[5].dev); } #endif