1
0
mirror of https://github.com/RIOT-OS/RIOT.git synced 2024-12-29 04:50:03 +01:00

cpu/stm32_common: unified UART driver

This commit is contained in:
Hauke Petersen 2016-12-07 16:17:12 +01:00
parent 5afb191027
commit 625d804fcb
11 changed files with 224 additions and 1329 deletions

View File

@ -132,6 +132,26 @@ typedef struct {
uint8_t bus; /**< APB bus */
} pwm_conf_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 */
#ifndef CPU_FAM_STM32F1
gpio_af_t rx_af; /**< alternate function for RX pin */
gpio_af_t tx_af; /**< alternate function for TX pin */
#endif
uint8_t bus; /**< APB bus */
uint8_t irqn; /**< IRQ channel */
#if 0 /* TODO */
uint8_t dma_stream; /**< DMA stream used for TX */
uint8_t dma_chan; /**< DMA channel used for TX */
#endif
} uart_conf_t;
/**
* @brief Get the actual bus clock frequency for the APB buses
*

View File

@ -0,0 +1,204 @@
/*
* Copyright (C) 2014-2016 Freie Universität Berlin
* Copyright (C) 2016 OTA keys
*
* 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.
*/
/**
* @ingroup cpu_stm32f2
* @{
*
* @file
* @brief Low-level UART driver implementation
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
* @author Fabian Nack <nack@inf.fu-berlin.de>
* @author Hermann Lelong <hermann@otakeys.com>
* @author Toon Stegen <toon.stegen@altran.com>
*
* @}
*/
#include "cpu.h"
#include "sched.h"
#include "thread.h"
#include "assert.h"
#include "periph/uart.h"
#include "periph/gpio.h"
#ifdef UART_NUMOF
#define RXENABLE (USART_CR1_RE | USART_CR1_RXNEIE)
/**
* @brief Allocate memory to store the callback functions
*/
static uart_isr_ctx_t isr_ctx[UART_NUMOF];
static inline USART_TypeDef *dev(uart_t uart)
{
return uart_config[uart].dev;
}
int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, void *arg)
{
uint16_t mantissa;
uint8_t fraction;
uint32_t clk;
assert(uart < UART_NUMOF);
/* save ISR context */
isr_ctx[uart].rx_cb = rx_cb;
isr_ctx[uart].arg = arg;
/* configure RX and TX pin */
gpio_init(uart_config[uart].rx_pin, GPIO_IN);
gpio_init(uart_config[uart].tx_pin, GPIO_OUT);
/* set TX pin high to avoid garbage during further initialization */
gpio_set(uart_config[uart].tx_pin);
#ifdef CPU_FAM_STM32F1
gpio_init_af(uart_config[uart].tx_pin, GPIO_AF_OUT_PP);
#else
gpio_init_af(uart_config[uart].tx_pin, uart_config[uart].tx_af);
gpio_init_af(uart_config[uart].rx_pin, uart_config[uart].rx_af);
#endif
/* enable the clock */
periph_clk_en(uart_config[uart].bus, uart_config[uart].rcc_mask);
/* reset UART configuration -> defaults to 8N1 mode */
dev(uart)->CR1 = 0;
dev(uart)->CR2 = 0;
dev(uart)->CR3 = 0;
/* calculate and apply baudrate */
clk = periph_apb_clk(uart_config[uart].bus) / baudrate;
mantissa = (uint16_t)(clk / 16);
fraction = (uint8_t)(clk - (mantissa * 16));
dev(uart)->BRR = ((mantissa & 0x0fff) << 4) | (fraction & 0x0f);
/* enable RX interrupt if applicable */
if (rx_cb) {
NVIC_EnableIRQ(uart_config[uart].irqn);
dev(uart)->CR1 = (USART_CR1_UE | USART_CR1_TE | RXENABLE);
}
else {
dev(uart)->CR1 = (USART_CR1_UE | USART_CR1_TE);
}
return UART_OK;
}
void uart_write(uart_t uart, const uint8_t *data, size_t len)
{
assert(uart < UART_NUMOF);
for (size_t i = 0; i < len; i++) {
#if defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32F3)
while (!(dev(uart)->ISR & USART_ISR_TXE)) {}
dev(uart)->TDR = data[i];
#else
while (!(dev(uart)->SR & USART_SR_TXE)) {}
dev(uart)->DR = data[i];
#endif
}
/* make sure the function is synchronous by waiting for the transfer to
* finish */
#if defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32F3)
while (!(dev(uart)->ISR & USART_ISR_TC)) {}
#else
while (!(dev(uart)->SR & USART_SR_TC)) {}
#endif
}
void uart_poweron(uart_t uart)
{
assert(uart < UART_NUMOF);
periph_clk_en(uart_config[uart].bus, uart_config[uart].rcc_mask);
}
void uart_poweroff(uart_t uart)
{
assert(uart < UART_NUMOF);
periph_clk_en(uart_config[uart].bus, uart_config[uart].rcc_mask);
}
static inline void irq_handler(uart_t uart)
{
#if defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32F3)
uint32_t status = dev(uart)->ISR;
if (status & USART_ISR_RXNE) {
isr_ctx[uart].rx_cb(isr_ctx[uart].arg, (uint8_t)dev(uart)->RDR);
}
if (status & USART_ISR_ORE) {
dev(uart)->ICR |= USART_ICR_ORECF; /* simply clear flag on overrun */
}
#else
uint32_t status = dev(uart)->SR;
if (status & USART_SR_RXNE) {
isr_ctx[uart].rx_cb(isr_ctx[uart].arg, (uint8_t)dev(uart)->DR);
}
if (status & USART_SR_ORE) {
/* ORE is cleared by reading SR and DR sequentially */
dev(uart)->DR;
}
#endif
cortexm_isr_end();
}
#ifdef UART_0_ISR
void UART_0_ISR(void)
{
irq_handler(UART_DEV(0));
}
#endif
#ifdef UART_1_ISR
void UART_1_ISR(void)
{
irq_handler(UART_DEV(1));
}
#endif
#ifdef UART_2_ISR
void UART_2_ISR(void)
{
irq_handler(UART_DEV(2));
}
#endif
#ifdef UART_3_ISR
void UART_3_ISR(void)
{
irq_handler(UART_DEV(3));
}
#endif
#ifdef UART_4_ISR
void UART_4_ISR(void)
{
irq_handler(UART_DEV(4));
}
#endif
#ifdef UART_5_ISR
void UART_5_ISR(void)
{
irq_handler(UART_DEV(5));
}
#endif
#endif /* UART_NUMOF */

View File

@ -1,220 +0,0 @@
/*
* Copyright (C) 2014 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.
*/
/**
* @ingroup cpu_stm32f0
* @{
*
* @file
* @brief Low-level UART driver implementation
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*
* @}
*/
#include "cpu.h"
#include "periph/uart.h"
/**
* @brief Allocate memory to store the callback functions.
*/
static uart_isr_ctx_t uart_config[UART_NUMOF];
static USART_TypeDef *const uart_port[UART_NUMOF] = {
#if UART_0_EN
[UART_0] = UART_0_DEV,
#endif
#if UART_1_EN
[UART_1] = UART_1_DEV,
#endif
};
int init_base(uart_t uart, uint32_t baudrate);
int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, void *arg)
{
int res;
/* initialize UART in blocking mode first */
res = init_base(uart, baudrate);
if (res != UART_OK) {
return res;
}
/* enable global interrupt and configure the interrupts priority */
switch (uart) {
#if UART_0_EN
case UART_0:
NVIC_EnableIRQ(UART_0_IRQ);
UART_0_DEV->CR1 |= USART_CR1_RXNEIE;
break;
#endif
#if UART_1_EN
case UART_1:
NVIC_EnableIRQ(UART_1_IRQ);
UART_1_DEV->CR1 |= USART_CR1_RXNEIE;
break;
#endif
}
/* register callbacks */
uart_config[uart].rx_cb = rx_cb;
uart_config[uart].arg = arg;
return UART_OK;
}
int init_base(uart_t uart, uint32_t baudrate)
{
USART_TypeDef *dev = 0;
GPIO_TypeDef *port = 0;
uint32_t rx_pin = 0;
uint32_t tx_pin = 0;
uint8_t af = 0;
uint32_t mid;
uint16_t mantissa;
uint8_t fraction;
/* enable UART and port clocks and select devices */
switch (uart) {
#if UART_0_EN
case UART_0:
dev = UART_0_DEV;
port = UART_0_PORT;
rx_pin = UART_0_RX_PIN;
tx_pin = UART_0_TX_PIN;
af = UART_0_AF;
/* enable clocks */
UART_0_CLKEN();
UART_0_PORT_CLKEN();
break;
#endif
#if UART_1_EN
case UART_1:
dev = UART_1_DEV;
port = UART_1_PORT;
tx_pin = UART_1_TX_PIN;
rx_pin = UART_1_RX_PIN;
af = UART_1_AF;
/* enable clocks */
UART_1_CLKEN();
UART_1_PORT_CLKEN();
break;
#endif
default:
return UART_NODEV;
}
/* Make sure port and dev are != NULL here, i.e. that the variables are
* assigned in all non-returning branches of the switch at the top of this
* function. */
assert(port != NULL);
assert(dev != NULL);
/* 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);
}
else {
port->AFR[1] &= ~(0xf << ((rx_pin - 8) * 4));
port->AFR[1] |= af << ((rx_pin - 8) * 4);
}
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 */
mid = (CLOCK_CORECLOCK / baudrate);
mantissa = (uint16_t)(mid / 16);
fraction = (uint8_t)(mid - (mantissa * 16));
dev->BRR = ((mantissa & 0x0fff) << 4) | (0x0f & fraction);
/* enable receive and transmit mode */
dev->CR1 |= USART_CR1_UE | USART_CR1_TE | USART_CR1_RE;
return UART_OK;
}
void uart_write(uart_t uart, const uint8_t *data, size_t len)
{
USART_TypeDef *dev = uart_port[uart];
for (size_t i = 0; i < len; i++) {
while (!(dev->ISR & USART_ISR_TXE)) {}
dev->TDR = data[i];
}
}
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
}
}
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
}
}
static inline void irq_handler(uint8_t uartnum, USART_TypeDef *dev)
{
if (dev->ISR & USART_ISR_RXNE) {
uint8_t data = (uint8_t)dev->RDR;
uart_config[uartnum].rx_cb(uart_config[uartnum].arg, data);
}
else if (dev->ISR & USART_ISR_ORE) {
/* do nothing on overrun */
dev->ICR |= USART_ICR_ORECF;
}
cortexm_isr_end();
}
#if UART_0_EN
void UART_0_ISR(void)
{
irq_handler(UART_0, UART_0_DEV);
}
#endif
#if UART_1_EN
void UART_1_ISR(void)
{
irq_handler(UART_1, UART_1_DEV);
}
#endif

View File

@ -115,18 +115,6 @@ typedef struct {
uint8_t chan; /**< CPU ADC channel connected to the pin */
} adc_conf_t;
/**
* @brief UART configuration options
*/
typedef struct {
USART_TypeDef *dev; /**< UART device */
gpio_t rx_pin; /**< TX pin */
gpio_t tx_pin; /**< RX pin */
uint32_t rcc_pin; /**< bit in the RCC register */
uint8_t bus; /**< peripheral bus */
uint8_t irqn; /**< interrupt number */
} uart_conf_t;
/**
* @brief DAC line configuration data
*/

View File

@ -1,134 +0,0 @@
/*
* Copyright (C) 2014-2016 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.
*/
/**
* @ingroup cpu_stm32f1
* @{
*
* @file
* @brief Low-level UART driver implementation
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
*
* @}
*/
#include <math.h>
#include "cpu.h"
#include "board.h"
#include "periph_conf.h"
#include "periph/uart.h"
#include "periph/gpio.h"
/**
* @brief Allocate memory to store the callback functions.
*/
static uart_isr_ctx_t isr_ctx[UART_NUMOF];
static inline USART_TypeDef *dev(uart_t uart)
{
return uart_config[uart].dev;
}
static void clk_en(uart_t uart)
{
if (uart_config[uart].bus == APB1) {
periph_clk_en(APB1, uart_config[uart].rcc_pin);
}
else {
periph_clk_en(APB2, uart_config[uart].rcc_pin);
}
}
int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, void *arg)
{
uint32_t bus_clk;
uint16_t mantissa;
uint8_t fraction;
/* make sure the given device is valid */
if (uart >= UART_NUMOF) {
return UART_NODEV;
}
/* save ISR context */
isr_ctx[uart].rx_cb = rx_cb;
isr_ctx[uart].arg = arg;
/* configure RX and TX pin */
gpio_init(uart_config[uart].rx_pin, GPIO_IN);
gpio_init_af(uart_config[uart].tx_pin, GPIO_AF_OUT_PP);
/* enable the clock */
clk_en(uart);
/* reset UART configuration -> defaults to 8N1 mode */
dev(uart)->CR1 = 0;
dev(uart)->CR2 = 0;
dev(uart)->CR3 = 0;
/* calculate and apply baudrate */
bus_clk = (uart_config[uart].bus == APB1) ? CLOCK_APB1 : CLOCK_APB2;
bus_clk /= baudrate;
mantissa = (uint16_t)(bus_clk / 16);
fraction = (uint8_t)(bus_clk - (mantissa * 16));
dev(uart)->BRR = ((mantissa & 0x0fff) << 4) | (fraction & 0x0f);
/* enable the UART's global interrupt and activate it */
NVIC_EnableIRQ(uart_config[uart].irqn);
dev(uart)->CR1 = (USART_CR1_UE | USART_CR1_TE |
USART_CR1_RE | USART_CR1_RXNEIE);
return UART_OK;
}
void uart_write(uart_t uart, const uint8_t *data, size_t len)
{
for (size_t i = 0; i < len; i++) {
while(!(dev(uart)->SR & USART_SR_TXE)) {}
dev(uart)->DR = data[i];
}
}
static inline void irq_handler(uart_t uart)
{
uint32_t status = dev(uart)->SR;
if (status & USART_SR_RXNE) {
char data = (char)dev(uart)->DR;
isr_ctx[uart].rx_cb(isr_ctx[uart].arg, data);
}
if (status & USART_SR_ORE) {
/* ORE is cleared by reading SR and DR sequentially */
dev(uart)->DR;
}
cortexm_isr_end();
}
#ifdef UART_0_ISR
void UART_0_ISR(void)
{
irq_handler(0);
}
#endif
#ifdef UART_1_ISR
void UART_1_ISR(void)
{
irq_handler(1);
}
#endif
#ifdef UART_2_ISR
void UART_2_ISR(void)
{
irq_handler(2);
}
#endif

View File

@ -67,29 +67,6 @@ enum {
PORT_I = 8 /**< port I */
};
/**
* @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_mode_t rx_mode; /**< RX pin mode */
gpio_mode_t tx_mode; /**< TX pin mode */
gpio_t rts_pin; /**< RTS pin */
gpio_t cts_pin; /**< CTS pin */
gpio_mode_t rts_mode; /**< RTS pin mode */
gpio_mode_t cts_mode; /**< CTS pin mode */
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 */
uint8_t hw_flow_ctrl; /**< Support for hardware flow control */
} uart_conf_t;
/** @} */
/**
* @brief Available number of ADC devices
*/

View File

@ -1,287 +0,0 @@
/*
* Copyright (C) 2014-2015 Freie Universität Berlin
* Copyright (C) 2016 OTA keys
*
* 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.
*/
/**
* @ingroup cpu_stm32f2
* @{
*
* @file
* @brief Low-level UART driver implementation
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Fabian Nack <nack@inf.fu-berlin.de>
* @author Hermann Lelong <hermann@otakeys.com>
* @author Toon Stegen <toon.stegen@altran.com>
*
* @}
*/
#include "cpu.h"
#include "mutex.h"
#include "periph/uart.h"
#include "periph/gpio.h"
#define ENABLE_DEBUG (0)
#include "debug.h"
/**
* @brief Allocate memory to store the callback functions
*/
static uart_isr_ctx_t uart_ctx[UART_NUMOF];
/**
* @brief Get the base register for the given UART device
*/
static inline USART_TypeDef *_dev(uart_t uart)
{
return uart_config[uart].dev;
}
/**
* @brief Transmission locks
*/
static mutex_t tx_sync[UART_NUMOF];
static mutex_t tx_lock[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)
{
USART_TypeDef *dev;
DMA_Stream_TypeDef *stream;
float divider;
uint16_t mantissa;
uint8_t fraction;
uint32_t max_clock;
uint8_t over8;
/* check if given UART device does exist */
if (uart < 0 || uart >= UART_NUMOF) {
return UART_NODEV;
}
/* check if baudrate is reachable and choose the right oversampling method*/
max_clock = (_bus(uart) == 1) ? CLOCK_APB1 : CLOCK_APB2;
if (baudrate < (max_clock / 16)) {
over8 = 0;
}
else if (baudrate < (max_clock / 8)) {
over8 = 1;
}
else {
return UART_NOBAUD;
}
/* 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]);
mutex_init(&tx_lock[uart]);
/* configure pins */
gpio_init(uart_config[uart].rx_pin, uart_config[uart].rx_mode);
gpio_init(uart_config[uart].tx_pin, uart_config[uart].tx_mode);
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 */
divider = max_clock / (8 * (2 - over8) * baudrate);
mantissa = (uint16_t)divider;
fraction = (uint8_t)((divider - mantissa) * (8 * (2 - over8)));
dev->BRR = ((mantissa & 0x0fff) << 4) | (0x07 & fraction);
/* configure UART to 8N1 and enable receive and transmit mode*/
dev->CR1 = USART_CR1_UE | USART_CR1_TE | USART_CR1_RE;
if (over8) {
dev->CR1 |= USART_CR1_OVER8;
}
dev->CR3 = USART_CR3_DMAT;
dev->CR2 = 0;
if(uart_config[uart].hw_flow_ctrl) {
gpio_init(uart_config[uart].cts_pin, uart_config[uart].cts_mode);
gpio_init(uart_config[uart].rts_pin, uart_config[uart].rts_mode);
gpio_init_af(uart_config[uart].cts_pin, uart_config[uart].af);
gpio_init_af(uart_config[uart].rts_pin, uart_config[uart].af);
DEBUG("Init flow control on uart %u\n", uart);
/* configure hardware flow control */
dev->CR3 |= USART_CR3_RTSE | USART_CR3_CTSE;
}
/* 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 UART_OK;
}
void uart_write(uart_t uart, const uint8_t *data, size_t len)
{
/* in case we are inside an ISR, we need to send blocking */
if (irq_is_in()) {
/* 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];
}
}
else {
mutex_lock(&tx_lock[uart]);
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]);
mutex_unlock(&tx_lock[uart]);
}
}
void uart_poweron(uart_t uart)
{
if (_bus(uart) == 1) {
periph_clk_en(APB1, uart_config[uart].rcc_mask);
}
else {
periph_clk_en(APB2, uart_config[uart].rcc_mask);
}
}
void uart_poweroff(uart_t uart)
{
if (_bus(uart) == 1) {
periph_clk_dis(APB1, uart_config[uart].rcc_mask);
}
else {
periph_clk_dis(APB2, uart_config[uart].rcc_mask);
}
}
static inline void irq_handler(int uart, USART_TypeDef *dev)
{
if (dev->SR & USART_SR_RXNE) {
char data = (char)dev->DR;
uart_ctx[uart].rx_cb(uart_ctx[uart].arg, data);
}
cortexm_isr_end();
}
static inline void dma_handler(int uart, int stream)
{
/* clear DMA done flag */
if (stream < 4) {
dma_base(stream)->LIFCR = dma_ifc(stream);
}
else {
dma_base(stream)->HIFCR = dma_ifc(stream);
}
mutex_unlock(&tx_sync[uart]);
cortexm_isr_end();
}
#ifdef UART_0_ISR
void UART_0_ISR(void)
{
irq_handler(0, uart_config[0].dev);
}
void UART_0_DMA_ISR(void)
{
dma_handler(0, uart_config[0].dma_stream);
}
#endif
#ifdef UART_1_ISR
void UART_1_ISR(void)
{
irq_handler(1, uart_config[1].dev);
}
void UART_1_DMA_ISR(void)
{
dma_handler(1, uart_config[1].dma_stream);
}
#endif
#ifdef UART_2_ISR
void UART_2_ISR(void)
{
irq_handler(2, uart_config[2].dev);
}
void UART_2_DMA_ISR(void)
{
dma_handler(2, uart_config[2].dma_stream);
}
#endif
#ifdef UART_3_ISR
void UART_3_ISR(void)
{
irq_handler(3, uart_config[3].dev);
}
void UART_3_DMA_ISR(void)
{
dma_handler(3, uart_config[3].dma_stream);
}
#endif
#ifdef UART_4_ISR
void UART_4_ISR(void)
{
irq_handler(4, uart_config[4].dev);
}
void UART_4_DMA_ISR(void)
{
dma_handler(4, uart_config[4].dma_stream);
}
#endif
#ifdef UART_5_ISR
void UART_5_ISR(void)
{
irq_handler(5, uart_config[5].dev);
}
void UART_5_DMA_ISR(void)
{
dma_handler(5, uart_config[5].dma_stream);
}
#endif

View File

@ -1,227 +0,0 @@
/*
* Copyright (C) 2014 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.
*/
/**
* @ingroup cpu_stm32f3
* @{
*
* @file
* @brief Low-level UART driver implementation
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*
* @}
*/
#include "cpu.h"
#include "periph/uart.h"
/**
* @brief Allocate memory to store the callback functions.
*/
static uart_isr_ctx_t uart_config[UART_NUMOF];
static int init_base(uart_t uart, uint32_t baudrate);
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 != UART_OK) {
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_EnableIRQ(UART_0_IRQ_CHAN);
UART_0_DEV->CR1 |= USART_CR1_RXNEIE;
break;
#endif
#if UART_1_EN
case UART_1:
NVIC_EnableIRQ(UART_1_IRQ_CHAN);
UART_1_DEV->CR1 |= USART_CR1_RXNEIE;
break;
#endif
#if UART_2_EN
case UART_2:
NVIC_EnableIRQ(UART_2_IRQ_CHAN);
UART_2_DEV->CR1 |= USART_CR1_RXNEIE;
break;
#endif
}
return UART_OK;
}
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;
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 UART_NODEV;
}
/* Make sure port and dev are != NULL here, i.e. that the variables are
* assigned in all non-returning branches of the switch at the top of this
* function. */
assert(port != NULL);
assert(dev != NULL);
/* 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);
}
else {
port->AFR[1] &= ~(0xf << ((rx_pin - 8) * 4));
port->AFR[1] |= af << ((rx_pin - 8) * 4);
}
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);
}
/* uart_configure UART to mode 8N1 with given baudrate */
clk /= baudrate;
mantissa = (uint16_t)(clk / 16);
fraction = (uint8_t)(clk - (mantissa * 16));
dev->BRR = ((mantissa & 0x0fff) << 4) | (0x0f & fraction);
/* enable receive and transmit mode */
dev->CR3 = 0;
dev->CR2 = 0;
dev->CR1 |= USART_CR1_UE | USART_CR1_TE | USART_CR1_RE;
return UART_OK;
}
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;
}
/* Make sure dev is != NULL here, i.e. that the variable is assigned in
* all non-returning branches of the switch at the top of this function. */
assert(dev != NULL);
for (size_t i = 0; i < len; i++) {
while (!(dev->ISR & USART_ISR_TXE)) {}
dev->TDR = data[i];
}
}
static inline void irq_handler(uint8_t uartnum, USART_TypeDef *dev)
{
if (dev->ISR & USART_ISR_RXNE) {
uint8_t data = (uint8_t)dev->RDR;
uart_config[uartnum].rx_cb(uart_config[uartnum].arg, data);
}
else if (dev->ISR & USART_ISR_ORE) {
/* do nothing on overrun */
dev->ICR |= USART_ICR_ORECF;
}
cortexm_isr_end();
}
#if UART_0_EN
void UART_0_ISR(void)
{
irq_handler(UART_0, UART_0_DEV);
}
#endif
#if UART_1_EN
void UART_1_ISR(void)
{
irq_handler(UART_1, UART_1_DEV);
}
#endif
#if UART_2_EN
void UART_2_ISR(void)
{
irq_handler(UART_2, UART_2_DEV);
}
#endif

View File

@ -102,23 +102,6 @@ enum {
PORT_I = 8 /**< port I */
};
/**
* @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 bus; /**< APB bus */
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 ADC channel configuration data
*/

View File

@ -1,209 +0,0 @@
/*
* 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.
*/
/**
* @ingroup cpu_stm32f4
* @{
*
* @file
* @brief Low-level UART driver implementation
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Fabian Nack <nack@inf.fu-berlin.de>
*
* @}
*/
#include "cpu.h"
#include "mutex.h"
#include "periph/uart.h"
#include "periph/gpio.h"
/**
* @brief Allocate memory to store the callback functions
*/
static uart_isr_ctx_t uart_ctx[UART_NUMOF];
/**
* @brief Get the base register for the given UART device
*/
static inline USART_TypeDef *_dev(uart_t uart)
{
return uart_config[uart].dev;
}
/**
* @brief Transmission locks
*/
static mutex_t _tx_dma_sync[UART_NUMOF];
static mutex_t _tx_lock[UART_NUMOF];
int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, void *arg)
{
USART_TypeDef *dev;
DMA_Stream_TypeDef *stream;
float divider;
uint16_t mantissa;
uint8_t fraction;
/* check if given UART device does exist */
if ((unsigned int)uart >= UART_NUMOF) {
return UART_NODEV;
}
/* 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 and DMA synchronization mutex */
mutex_init(&_tx_lock[uart]);
mutex_init(&_tx_dma_sync[uart]);
mutex_lock(&_tx_dma_sync[uart]);
/* configure pins */
gpio_init(uart_config[uart].rx_pin, GPIO_IN);
gpio_init(uart_config[uart].tx_pin, GPIO_OUT);
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 (uart_config[uart].bus == APB1) {
divider = CLOCK_APB1 / (16 * baudrate);
}
else {
divider = CLOCK_APB2 / (16 * baudrate);
}
mantissa = (uint16_t)divider;
fraction = (uint8_t)((divider - mantissa) * 16);
dev->BRR = ((mantissa & 0x0fff) << 4) | (0x0f & fraction);
/* 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 UART_OK;
}
void uart_write(uart_t uart, const uint8_t *data, size_t len)
{
/* in case we are inside an ISR, we need to send blocking */
if (irq_is_in()) {
/* 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];
}
}
else {
mutex_lock(&_tx_lock[uart]);
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_dma_sync[uart]);
mutex_unlock(&_tx_lock[uart]);
}
}
void uart_poweron(uart_t uart)
{
periph_clk_en(uart_config[uart].bus, uart_config[uart].rcc_mask);
}
void uart_poweroff(uart_t uart)
{
periph_clk_dis(uart_config[uart].bus, uart_config[uart].rcc_mask);
}
static inline void irq_handler(int uart, USART_TypeDef *dev)
{
if (dev->SR & USART_SR_RXNE) {
uint8_t data = (uint8_t)dev->DR;
uart_ctx[uart].rx_cb(uart_ctx[uart].arg, data);
}
cortexm_isr_end();
}
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_dma_sync[uart]);
cortexm_isr_end();
}
#ifdef UART_0_ISR
void UART_0_ISR(void)
{
irq_handler(0, uart_config[0].dev);
}
void UART_0_DMA_ISR(void)
{
dma_handler(0, uart_config[0].dma_stream);
}
#endif
#ifdef UART_1_ISR
void UART_1_ISR(void)
{
irq_handler(1, uart_config[1].dev);
}
void UART_1_DMA_ISR(void)
{
dma_handler(1, uart_config[1].dma_stream);
}
#endif
#ifdef UART_2_ISR
void UART_2_ISR(void)
{
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

View File

@ -1,200 +0,0 @@
/*
* Copyright (C) 2014 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.
*/
/**
* @addtogroup driver_periph
* @{
*
* @file
* @brief Low-level UART driver implementation
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*
* @}
*/
#include "cpu.h"
#include "periph/uart.h"
#include "periph/gpio.h"
/**
* @brief Allocate memory to store the callback functions.
*/
static uart_isr_ctx_t uart_config[UART_NUMOF];
static int init_base(uart_t uart, uint32_t baudrate);
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 != UART_OK) {
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_EnableIRQ(UART_0_IRQ);
UART_0_DEV->CR1 |= USART_CR1_RXNEIE;
break;
#endif
#if UART_1_EN
case UART_1:
NVIC_EnableIRQ(UART_1_IRQ);
UART_1_DEV->CR1 |= USART_CR1_RXNEIE;
break;
#endif
#if UART_2_EN
case UART_2:
NVIC_EnableIRQ(UART_2_IRQ);
UART_2_DEV->CR1 |= USART_CR1_RXNEIE;
break;
#endif
}
return UART_OK;
}
static int init_base(uart_t uart, uint32_t baudrate)
{
USART_TypeDef *dev = 0;
gpio_t tx_pin = 0;
gpio_t rx_pin = 0;
gpio_af_t af = 0;
float clk = 0;
uint16_t mantissa;
uint8_t fraction;
switch (uart) {
#if UART_0_EN
case UART_0:
dev = UART_0_DEV;
clk = UART_0_CLK;
tx_pin = UART_0_TX_PIN;
rx_pin = UART_0_RX_PIN;
af = UART_0_AF;
UART_0_CLKEN();
break;
#endif
#if UART_1_EN
case UART_1:
dev = UART_1_DEV;
clk = UART_1_CLK;
tx_pin = UART_1_TX_PIN;
rx_pin = UART_1_RX_PIN;
af = UART_1_AF;
UART_1_CLKEN();
break;
#endif
#if UART_2_EN
case UART_2:
dev = UART_2_DEV;
clk = UART_2_CLK;
tx_pin = UART_2_TX_PIN;
rx_pin = UART_2_RX_PIN;
af = UART_2_AF;
UART_2_CLKEN();
break;
#endif
default:
return UART_NODEV;
}
/* Make sure dev is != NULL here, i.e. that the variable is assigned in
* all non-returning branches of the switch at the top of this function. */
assert(dev != NULL);
/* uart_configure RX and TX pins, set pin to use alternative function mode */
gpio_init(tx_pin, GPIO_OUT);
gpio_init_af(tx_pin, af);
gpio_init(rx_pin, GPIO_IN);
gpio_init_af(rx_pin, af);
/* uart_configure UART to mode 8N1 with given baudrate */
clk /= baudrate;
mantissa = (uint16_t)(clk / 16);
fraction = (uint8_t)(clk - (mantissa * 16));
dev->BRR = ((mantissa & 0x0fff) << 4) | (0x0f & fraction);
/* enable receive and transmit mode */
dev->CR3 = 0;
dev->CR2 = 0;
dev->CR1 |= USART_CR1_UE | USART_CR1_TE | USART_CR1_RE;
return UART_OK;
}
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;
}
/* Make sure dev is != NULL here, i.e. that the variable is assigned in
* all non-returning branches of the switch at the top of this function. */
assert(dev != NULL);
for (size_t i = 0; i < len; i++) {
while (!(dev->SR & USART_SR_TXE)) {}
dev->DR = data[i];
}
}
static inline void irq_handler(uint8_t uartnum, USART_TypeDef *dev)
{
if (dev->SR & USART_SR_RXNE) {
uint8_t data = (uint8_t)dev->DR;
uart_config[uartnum].rx_cb(uart_config[uartnum].arg, data);
}
cortexm_isr_end();
}
#if UART_0_EN
void UART_0_ISR(void)
{
irq_handler(UART_0, UART_0_DEV);
}
#endif
#if UART_1_EN
void UART_1_ISR(void)
{
irq_handler(UART_1, UART_1_DEV);
}
#endif
#if UART_2_EN
void UART_2_ISR(void)
{
irq_handler(UART_2, UART_2_DEV);
}
#endif