From 89c885ea402ed88559a32c5ca69c0bb7041cf9d1 Mon Sep 17 00:00:00 2001 From: dylad Date: Tue, 27 Jun 2017 21:13:41 +0200 Subject: [PATCH 1/3] sam0/uart: merge samd21 & saml21 uart driver Signed-off-by: dylad --- cpu/sam0_common/include/periph_cpu_common.h | 14 + cpu/sam0_common/periph/uart.c | 346 ++++++++++++++++++++ cpu/samd21/include/periph_cpu.h | 12 - cpu/samd21/periph/uart.c | 189 ----------- cpu/saml21/periph/uart.c | 187 ----------- 5 files changed, 360 insertions(+), 388 deletions(-) create mode 100644 cpu/sam0_common/periph/uart.c delete mode 100644 cpu/samd21/periph/uart.c delete mode 100644 cpu/saml21/periph/uart.c diff --git a/cpu/sam0_common/include/periph_cpu_common.h b/cpu/sam0_common/include/periph_cpu_common.h index fbf6c6adad..81e4f22a3e 100644 --- a/cpu/sam0_common/include/periph_cpu_common.h +++ b/cpu/sam0_common/include/periph_cpu_common.h @@ -117,6 +117,20 @@ typedef enum { * and CTS on pad 3 */ } uart_txpad_t; +/** + * @brief UART device configuration + */ +typedef struct { + SercomUsart *dev; /**< pointer to the used UART device */ + gpio_t rx_pin; /**< pin used for RX */ + gpio_t tx_pin; /**< pin used for TX */ + gpio_mux_t mux; /**< alternative function for pins */ + uart_rxpad_t rx_pad; /**< pad selection for RX line */ + uart_txpad_t tx_pad; /**< pad selection for TX line */ + uint8_t runstdby; /**< allow SERCOM to run in standby mode */ + uint8_t gclk_src; /**< GCLK source which supplys SERCOM */ +} uart_conf_t; + /** * @brief Available values for SERCOM SPI MISO pad selection */ diff --git a/cpu/sam0_common/periph/uart.c b/cpu/sam0_common/periph/uart.c new file mode 100644 index 0000000000..fafe2cac9d --- /dev/null +++ b/cpu/sam0_common/periph/uart.c @@ -0,0 +1,346 @@ +/* + * Copyright (C) 2015 Freie Universität Berlin + * 2015 FreshTemp, LLC. + * + * 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 driver_periph + * @{ + * + * @file + * @brief Low-level UART driver implementation + * + * @author Thomas Eichinger + * @author Troels Hoffmeyer + * @author Hauke Petersen + * @author Dylan Laduranty + * + * @} + */ + +#include "cpu.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 pointer to the base register of the given UART device + * + * @param[in] dev UART device identifier + * + * @return base register address + */ +static inline SercomUsart *_uart(uart_t dev) +{ + return uart_config[dev].dev; +} + +#ifdef CPU_FAM_SAML21 + +static uint64_t _long_division(uint64_t n, uint64_t d); + +/** + * @brief Get the sercom gclk id of the given UART device + * + * @param[in] dev UART device identifier + * + * @return sercom gclk id + */ + +static int _get_sercom_gclk_id(SercomUsart *dev) +{ + int id; + + switch(sercom_id(dev)) { + case 0: + id = SERCOM0_GCLK_ID_CORE; + break; + case 1: + id = SERCOM1_GCLK_ID_CORE; + break; + case 2: + id = SERCOM2_GCLK_ID_CORE; + break; + case 3: + id = SERCOM3_GCLK_ID_CORE; + break; + case 4: + id = SERCOM4_GCLK_ID_CORE; + break; + case 5: + id = SERCOM5_GCLK_ID_CORE; + break; + default: + id = -1; + DEBUG("[UART]: wrong SERCOM ID\n"); + break; + } + return id; +} +#endif + +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) +{ + /* initialize basic functionality */ + int res = init_base(uart, baudrate); + if (res != UART_OK) { + return res; + } + + /* register callbacks */ + uart_ctx[uart].rx_cb = rx_cb; + uart_ctx[uart].arg = arg; + /* configure interrupts and enable RX interrupt */ + NVIC_EnableIRQ(SERCOM0_IRQn + sercom_id(_uart(uart))); + _uart(uart)->INTENSET.reg |= SERCOM_USART_INTENSET_RXC; + + return UART_OK; +} + +static int init_base(uart_t uart, uint32_t baudrate) +{ + SercomUsart *dev; + + if ((unsigned int)uart >= UART_NUMOF) { + return UART_NODEV; + } + + /* get the devices base register */ + dev = _uart(uart); + + /* configure pins */ + gpio_init(uart_config[uart].rx_pin, GPIO_IN); + gpio_init_mux(uart_config[uart].rx_pin, uart_config[uart].mux); + gpio_init(uart_config[uart].tx_pin, GPIO_OUT); + gpio_init_mux(uart_config[uart].tx_pin, uart_config[uart].mux); + +#ifdef CPU_FAM_SAMD21 + /* calculate baudrate */ + uint32_t baud = ((((uint32_t)CLOCK_CORECLOCK * 10) / baudrate) / 16); + /* enable sync and async clocks */ + uart_poweron(uart); + /* reset the UART device */ + dev->CTRLA.reg = SERCOM_USART_CTRLA_SWRST; + while (dev->SYNCBUSY.reg & SERCOM_USART_SYNCBUSY_SWRST) {} + /* set asynchronous mode w/o parity, LSB first, TX and RX pad as specified + * by the board in the periph_conf.h, x16 sampling and use internal clock */ + dev->CTRLA.reg = (SERCOM_USART_CTRLA_DORD | + SERCOM_USART_CTRLA_SAMPR(0x1) | + SERCOM_USART_CTRLA_TXPO(uart_config[uart].tx_pad) | + SERCOM_USART_CTRLA_RXPO(uart_config[uart].rx_pad) | + SERCOM_USART_CTRLA_MODE_USART_INT_CLK | + (uart_config[uart].runstdby ? + SERCOM_USART_CTRLA_RUNSTDBY : 0)); + + /* set baudrate */ + dev->BAUD.FRAC.FP = (baud % 10); + dev->BAUD.FRAC.BAUD = (baud / 10); + /* enable receiver and transmitter, use 1 stop bit */ + dev->CTRLB.reg = (SERCOM_USART_CTRLB_RXEN | SERCOM_USART_CTRLB_TXEN); + while (dev->SYNCBUSY.reg & SERCOM_USART_SYNCBUSY_CTRLB) {} +#elif CPU_FAM_SAML21 + /* Calculate the BAUD value */ + uint64_t temp1 = ((16 * ((uint64_t)baudrate)) << 32); + uint64_t ratio = _long_division(temp1 , CLOCK_CORECLOCK); + uint64_t scale = ((uint64_t)1 << 32) - ratio; + uint64_t baud_calculated = (65536 * scale) >> 32; + + dev->CTRLA.bit.ENABLE = 0; /* Disable to write, need to sync tho */ + while(dev->SYNCBUSY.bit.ENABLE) {} + + /* set to LSB, asynchronous mode without parity, PAD0 Tx, PAD1 Rx, + * 16x over-sampling, internal clk */ + dev->CTRLA.reg = SERCOM_USART_CTRLA_DORD \ + | SERCOM_USART_CTRLA_FORM(0x0) \ + | SERCOM_USART_CTRLA_SAMPA(0x0) \ + | SERCOM_USART_CTRLA_TXPO(uart_config[uart].tx_pad) \ + | SERCOM_USART_CTRLA_RXPO(uart_config[uart].rx_pad) \ + | SERCOM_USART_CTRLA_SAMPR(0x0) \ + | SERCOM_USART_CTRLA_MODE(0x1) \ + | (uart_config[uart].runstdby ? + SERCOM_USART_CTRLA_RUNSTDBY : 0); + + /* Set baud rate */ + dev->BAUD.bit.BAUD = baud_calculated; + + /* enable receiver and transmitter, one stop bit*/ + dev->CTRLB.reg = (SERCOM_USART_CTRLB_RXEN | SERCOM_USART_CTRLB_TXEN); + while(dev->SYNCBUSY.bit.CTRLB) {} + uart_poweron(uart); +#endif + 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 (!(_uart(uart)->INTFLAG.reg & SERCOM_USART_INTFLAG_DRE)) {} + _uart(uart)->DATA.reg = data[i]; + while (_uart(uart)->INTFLAG.reg & SERCOM_USART_INTFLAG_TXC) {} + } +} + +void uart_poweron(uart_t uart) +{ + SercomUsart *dev; + + /* get the devices base register */ + dev = _uart(uart); + +#ifdef CPU_FAM_SAMD21 + PM->APBCMASK.reg |= (PM_APBCMASK_SERCOM0 << sercom_id(_uart(uart))); + GCLK->CLKCTRL.reg = (GCLK_CLKCTRL_CLKEN | + GCLK_CLKCTRL_GEN(uart_config[uart].gclk_src) | + (SERCOM0_GCLK_ID_CORE + sercom_id(_uart(uart))) << + GCLK_CLKCTRL_ID_Pos); + while (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY) {} +#elif CPU_FAM_SAML21 + /* Enable the peripheral channel */ + GCLK->PCHCTRL[_get_sercom_gclk_id(dev)].reg |= GCLK_PCHCTRL_CHEN | + GCLK_PCHCTRL_GEN(uart_config[uart].gclk_src); + + while (!(GCLK->PCHCTRL[_get_sercom_gclk_id(dev)].reg & GCLK_PCHCTRL_CHEN)) {} + if(_get_sercom_gclk_id(dev) < 5) { + MCLK->APBCMASK.reg |= MCLK_APBCMASK_SERCOM0 << sercom_id(dev); + } + else { + MCLK->APBDMASK.reg |= MCLK_APBDMASK_SERCOM5; + } + while (dev->SYNCBUSY.reg) {} +#endif + /* finally, enable the device */ + dev->CTRLA.reg |= SERCOM_USART_CTRLA_ENABLE; +} + +void uart_poweroff(uart_t uart) +{ + SercomUsart *dev; + + /* get the devices base register */ + dev = _uart(uart); + +#ifdef CPU_FAM_SAMD21 + PM->APBCMASK.reg &= ~(PM_APBCMASK_SERCOM0 << sercom_id(dev)); + GCLK->CLKCTRL.reg = ((SERCOM0_GCLK_ID_CORE + sercom_id(dev)) << + GCLK_CLKCTRL_ID_Pos); + while (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY) {} +#elif CPU_FAM_SAML21 + /* Enable the peripheral channel */ + GCLK->PCHCTRL[_get_sercom_gclk_id(dev)].reg &= ~GCLK_PCHCTRL_CHEN; + + if(_get_sercom_gclk_id(dev) < 5) { + MCLK->APBCMASK.reg &= ~(MCLK_APBCMASK_SERCOM0 << sercom_id(dev)); + } + else { + MCLK->APBDMASK.reg &= ~MCLK_APBDMASK_SERCOM5; + } + while (dev->SYNCBUSY.reg) {} + +#endif +} + +static inline void irq_handler(uint8_t uartnum) +{ + SercomUsart *uart = _uart(uartnum); +#ifdef CPU_FAM_SAMD21 + if (uart->INTFLAG.reg & SERCOM_USART_INTFLAG_RXC) { + /* interrupt flag is cleared by reading the data register */ + uart_ctx[uartnum].rx_cb(uart_ctx[uartnum].arg, (uint8_t)(uart->DATA.reg)); + } + else if (uart->INTFLAG.reg & SERCOM_USART_INTFLAG_ERROR) { + /* clear error flag */ + uart->INTFLAG.reg = SERCOM_USART_INTFLAG_ERROR; + } +#elif CPU_FAM_SAML21 + if (uart->INTFLAG.bit.RXC) { + /* cleared by reading DATA regiser */ + uint8_t data = (uint8_t)uart->DATA.reg; + uart_ctx[uartnum].rx_cb(uart_ctx[uartnum].arg, data); + } + else if (uart->INTFLAG.bit.ERROR) { + /* clear error flag */ + uart->INTFLAG.reg |= SERCOM_USART_INTFLAG_ERROR; + } +#endif + 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 + +#ifdef UART_3_ISR +void UART_3_ISR(void) +{ + irq_handler(3); +} +#endif + +#ifdef UART_4_ISR +void UART_4_ISR(void) +{ + irq_handler(4); +} +#endif + +#ifdef UART_5_ISR +void UART_5_ISR(void) +{ + irq_handler(5); +} +#endif + +#ifdef CPU_FAM_SAML21 +static uint64_t _long_division(uint64_t n, uint64_t d) +{ + int32_t i; + uint64_t q = 0, r = 0, bit_shift; + for (i = 63; i >= 0; i--) { + bit_shift = (uint64_t)1 << i; + + r = r << 1; + + if (n & bit_shift) { + r |= 0x01; + } + + if (r >= d) { + r = r - d; + q |= bit_shift; + } + } + + return q; +} +#endif diff --git a/cpu/samd21/include/periph_cpu.h b/cpu/samd21/include/periph_cpu.h index 459e41f254..94ab5cdd79 100644 --- a/cpu/samd21/include/periph_cpu.h +++ b/cpu/samd21/include/periph_cpu.h @@ -88,18 +88,6 @@ typedef struct { pwm_conf_chan_t chan[3]; /**< channel configuration */ } pwm_conf_t; -/** - * @brief UART device configuration - */ -typedef struct { - SercomUsart *dev; /**< pointer to the used UART device */ - gpio_t rx_pin; /**< pin used for RX */ - gpio_t tx_pin; /**< pin used for TX */ - gpio_mux_t mux; /**< alternative function for pins */ - uart_rxpad_t rx_pad; /**< pad selection for RX line */ - uart_txpad_t tx_pad; /**< pad selection for TX line */ -} uart_conf_t; - /** * @brief Return the numeric id of a SERCOM device derived from its address * diff --git a/cpu/samd21/periph/uart.c b/cpu/samd21/periph/uart.c deleted file mode 100644 index 24b8ef53da..0000000000 --- a/cpu/samd21/periph/uart.c +++ /dev/null @@ -1,189 +0,0 @@ -/* - * Copyright (C) 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_samd21 - * @ingroup drivers_periph_uart - * @{ - * - * @file - * @brief Low-level UART driver implementation - * - * @author Thomas Eichinger - * @author Troels Hoffmeyer - * @author Hauke Petersen - * - * @} - */ - -#include "cpu.h" - -#include "periph/uart.h" -#include "periph/gpio.h" - -#ifdef UART_NUMOF -/** - * @brief Allocate memory to store the callback functions - */ -static uart_isr_ctx_t uart_ctx[UART_NUMOF]; - -/** - * @brief Get the pointer to the base register of the given UART device - * - * @param[in] dev UART device identifier - * - * @return base register address - */ -static inline SercomUsart *_uart(uart_t dev) -{ - return uart_config[dev].dev; -} - -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) -{ - /* initialize basic functionality */ - int res = init_base(uart, baudrate); - if (res != UART_OK) { - return res; - } - - /* register callbacks */ - uart_ctx[uart].rx_cb = rx_cb; - uart_ctx[uart].arg = arg; - /* configure interrupts and enable RX interrupt */ - _uart(uart)->INTENSET.reg = SERCOM_USART_INTENSET_RXC; - NVIC_EnableIRQ(SERCOM0_IRQn + sercom_id(_uart(uart))); - return UART_OK; -} - -static int init_base(uart_t uart, uint32_t baudrate) -{ - uint32_t baud; - SercomUsart *dev; - - if ((unsigned int)uart >= UART_NUMOF) { - return UART_NODEV; - } - - /* get the devices base register */ - dev = _uart(uart); - /* calculate baudrate */ - baud = ((((uint32_t)CLOCK_CORECLOCK * 10) / baudrate) / 16); - /* enable sync and async clocks */ - uart_poweron(uart); - /* configure pins */ - gpio_init(uart_config[uart].rx_pin, GPIO_IN); - gpio_init_mux(uart_config[uart].rx_pin, uart_config[uart].mux); - gpio_init(uart_config[uart].tx_pin, GPIO_OUT); - gpio_init_mux(uart_config[uart].tx_pin, uart_config[uart].mux); - /* reset the UART device */ - dev->CTRLA.reg = SERCOM_USART_CTRLA_SWRST; - while (dev->SYNCBUSY.reg & SERCOM_USART_SYNCBUSY_SWRST) {} - /* set asynchronous mode w/o parity, LSB first, TX and RX pad as specified - * by the board in the periph_conf.h, x16 sampling and use internal clock */ - dev->CTRLA.reg = (SERCOM_USART_CTRLA_DORD | - SERCOM_USART_CTRLA_SAMPR(0x1) | - SERCOM_USART_CTRLA_TXPO(uart_config[uart].tx_pad) | - SERCOM_USART_CTRLA_RXPO(uart_config[uart].rx_pad) | - SERCOM_USART_CTRLA_MODE_USART_INT_CLK); - /* set baudrate */ - dev->BAUD.FRAC.FP = (baud % 10); - dev->BAUD.FRAC.BAUD = (baud / 10); - /* enable receiver and transmitter, use 1 stop bit */ - dev->CTRLB.reg = (SERCOM_USART_CTRLB_RXEN | SERCOM_USART_CTRLB_TXEN); - while (dev->SYNCBUSY.reg & SERCOM_USART_SYNCBUSY_CTRLB) {} - /* finally, enable the device */ - dev->CTRLA.reg |= SERCOM_USART_CTRLA_ENABLE; - 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 (!(_uart(uart)->INTFLAG.reg & SERCOM_USART_INTFLAG_DRE)) {} - _uart(uart)->DATA.reg = data[i]; - } -} - -void uart_poweron(uart_t uart) -{ - PM->APBCMASK.reg |= (PM_APBCMASK_SERCOM0 << sercom_id(_uart(uart))); - GCLK->CLKCTRL.reg = (GCLK_CLKCTRL_CLKEN | - GCLK_CLKCTRL_GEN_GCLK0 | - (SERCOM0_GCLK_ID_CORE + sercom_id(_uart(uart))) << - GCLK_CLKCTRL_ID_Pos); - while (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY) {} -} - -void uart_poweroff(uart_t uart) -{ - PM->APBCMASK.reg &= ~(PM_APBCMASK_SERCOM0 << sercom_id(_uart(uart))); - GCLK->CLKCTRL.reg = ((SERCOM0_GCLK_ID_CORE + sercom_id(_uart(uart))) << - GCLK_CLKCTRL_ID_Pos); - while (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY) {} -} - -static inline void irq_handler(int dev) -{ - SercomUsart *uart = _uart(dev); - - if (uart->INTFLAG.reg & SERCOM_USART_INTFLAG_RXC) { - /* interrupt flag is cleared by reading the data register */ - uart_ctx[dev].rx_cb(uart_ctx[dev].arg, (uint8_t)(uart->DATA.reg)); - } - else if (uart->INTFLAG.reg & SERCOM_USART_INTFLAG_ERROR) { - /* clear error flag */ - uart->INTFLAG.reg = SERCOM_USART_INTFLAG_ERROR; - } - 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 - -#ifdef UART_3_ISR -void UART_3_ISR(void) -{ - irq_handler(3); -} -#endif - -#ifdef UART_4_ISR -void UART_4_ISR(void) -{ - irq_handler(4); -} -#endif - -#ifdef UART_5_ISR -void UART_5_ISR(void) -{ - irq_handler(5); -} -#endif -#endif diff --git a/cpu/saml21/periph/uart.c b/cpu/saml21/periph/uart.c deleted file mode 100644 index 2fd462411d..0000000000 --- a/cpu/saml21/periph/uart.c +++ /dev/null @@ -1,187 +0,0 @@ -/* - * Copyright (C) 2014 Freie Universität Berlin - * 2015 Kaspar Schleiser - * 2015 FreshTemp, LLC. - * - * 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_saml21 - * @ingroup drivers_periph_uart - * @{ - * - * @file uart.c - * @brief Low-level UART driver implementation - * - * @author Thomas Eichinger - * @author Troels Hoffmeyer - * - * @} - */ - -#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 uint64_t _long_division(uint64_t n, uint64_t d); - -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) -{ - /* initialize basic functionality */ - int res = init_base(uart, baudrate); - if (res != UART_OK) { - return UART_NODEV; - } - - /* register callbacks */ - uart_config[uart].rx_cb = rx_cb; - uart_config[uart].arg = arg; - - /* configure interrupts and enable RX interrupt */ - switch (uart) { - case UART_0: - NVIC_SetPriority(UART_0_IRQ, UART_IRQ_PRIO); - NVIC_EnableIRQ(UART_0_IRQ); - UART_0_DEV.INTENSET.bit.RXC = 1; - break; - } - return UART_OK; -} - -static int init_base(uart_t uart, uint32_t baudrate) -{ - /* Calculate the BAUD value */ - uint64_t temp1 = ((16 * ((uint64_t)baudrate)) << 32); - uint64_t ratio = _long_division(temp1 , UART_0_REF_F); - uint64_t scale = ((uint64_t)1 << 32) - ratio; - uint64_t baud_calculated = (65536 * scale) >> 32; - - switch (uart) { -#if UART_0_EN - case UART_0: - /* Enable the peripheral channel */ - GCLK->PCHCTRL[SERCOM3_GCLK_ID_CORE].reg |= GCLK_PCHCTRL_CHEN | GCLK_PCHCTRL_GEN_GCLK0; - - while (!(GCLK->PCHCTRL[SERCOM3_GCLK_ID_CORE].reg & GCLK_PCHCTRL_CHEN)) { - /* Wait for clock synchronization */ - } - - MCLK->APBCMASK.reg |= MCLK_APBCMASK_SERCOM3; - /* configure PINS to input/output*/ - UART_0_PORT.DIRSET.reg = (1 << UART_0_TX_PIN); /* tx's direction is output */ - UART_0_PORT.PINCFG[UART_0_RX_PIN % 32].bit.INEN = true; /* buffer rx pin's value */ - - /* enable PMUX for pins and set to config C. */ - UART_0_PORT.WRCONFIG.reg = PORT_WRCONFIG_WRPINCFG \ - | PORT_WRCONFIG_WRPMUX \ - | PORT_WRCONFIG_PMUX(0x2) \ - | PORT_WRCONFIG_PMUXEN \ - | UART_0_PINS; - - UART_0_DEV.CTRLA.bit.ENABLE = 0; /* Disable to write, need to sync tho */ - while(UART_0_DEV.SYNCBUSY.bit.ENABLE) {} - - /* set to LSB, asynchronous mode without parity, PAD0 Tx, PAD1 Rx, - * 16x over-sampling, internal clk */ - UART_0_DEV.CTRLA.reg = SERCOM_USART_CTRLA_DORD \ - | SERCOM_USART_CTRLA_FORM(0x0) \ - | SERCOM_USART_CTRLA_SAMPA(0x0) \ - | SERCOM_USART_CTRLA_TXPO(0x0) \ - | SERCOM_USART_CTRLA_RXPO(0x1) \ - | SERCOM_USART_CTRLA_SAMPR(0x0) \ - | SERCOM_USART_CTRLA_MODE(0x1) \ - | (UART_0_RUNSTDBY ? SERCOM_USART_CTRLA_RUNSTDBY : 0); - - /* Set baud rate */ - UART_0_DEV.BAUD.bit.BAUD = baud_calculated; - - /* enable receiver and transmitter, one stop bit*/ - UART_0_DEV.CTRLB.reg = (SERCOM_USART_CTRLB_RXEN | SERCOM_USART_CTRLB_TXEN); - while(UART_0_DEV.SYNCBUSY.bit.CTRLB) {} - - break; -#endif - default: - (void)baud_calculated; - return UART_NODEV; - } - - uart_poweron(uart); - return UART_OK; -} - -void uart_write(uart_t uart, const uint8_t *data, size_t len) -{ - if (uart == UART_0) { - for (size_t i = 0; i < len; i++) { - while (UART_0_DEV.INTFLAG.bit.DRE == 0) {} - while(UART_0_DEV.SYNCBUSY.bit.ENABLE) {} - UART_0_DEV.DATA.reg = data[i]; - while (UART_0_DEV.INTFLAG.reg & SERCOM_USART_INTFLAG_TXC) {} - } - } -} - -static inline void irq_handler(uint8_t uartnum, SercomUsart *dev) -{ - if (dev->INTFLAG.bit.RXC) { - /* cleared by reading DATA regiser */ - uint8_t data = (uint8_t)dev->DATA.reg; - uart_config[uartnum].rx_cb(uart_config[uartnum].arg, data); - } - else if (dev->INTFLAG.bit.ERROR) { - /* clear error flag */ - dev->INTFLAG.reg |= SERCOM_USART_INTFLAG_ERROR; - } - cortexm_isr_end(); -} - -void uart_poweron(uart_t uart) -{ - while (UART_0_DEV.SYNCBUSY.reg) {} - UART_0_DEV.CTRLA.reg |= SERCOM_USART_CTRLA_ENABLE; -} - -void uart_poweroff(uart_t uart) -{ - while (UART_0_DEV.SYNCBUSY.reg) {} - UART_0_DEV.CTRLA.reg &= ~SERCOM_USART_CTRLA_ENABLE; -} - -#if UART_0_EN -void UART_0_ISR(void) -{ - irq_handler(UART_0, &UART_0_DEV); -} -#endif - -static uint64_t _long_division(uint64_t n, uint64_t d) -{ - int32_t i; - uint64_t q = 0, r = 0, bit_shift; - for (i = 63; i >= 0; i--) { - bit_shift = (uint64_t)1 << i; - - r = r << 1; - - if (n & bit_shift) { - r |= 0x01; - } - - if (r >= d) { - r = r - d; - q |= bit_shift; - } - } - - return q; -} From c81ae980687d746a863a864195b2e0faef812ad1 Mon Sep 17 00:00:00 2001 From: dylad Date: Tue, 27 Jun 2017 21:14:31 +0200 Subject: [PATCH 2/3] boards: update periph_conf of sam0 based board Signed-off-by: dylad --- .../arduino-mkr-common/include/periph_conf.h | 14 +++-- boards/arduino-zero/include/periph_conf.h | 28 +++++---- boards/samd21-xpro/include/periph_conf.h | 22 ++++--- boards/saml21-xpro/include/periph_conf.h | 38 +++++++---- boards/samr21-xpro/include/periph_conf.h | 8 ++- boards/sodaq-autonomo/include/periph_conf.h | 56 ++++++++++------- cpu/sam0_common/periph/uart.c | 63 ++++++------------- 7 files changed, 120 insertions(+), 109 deletions(-) diff --git a/boards/arduino-mkr-common/include/periph_conf.h b/boards/arduino-mkr-common/include/periph_conf.h index 6fc69bec0d..a538729ad6 100644 --- a/boards/arduino-mkr-common/include/periph_conf.h +++ b/boards/arduino-mkr-common/include/periph_conf.h @@ -104,12 +104,14 @@ extern "C" { */ static const uart_conf_t uart_config[] = { { - .dev = &SERCOM5->USART, - .rx_pin = GPIO_PIN(PB,23), /* ARDUINO_PIN_13, RX Pin */ - .tx_pin = GPIO_PIN(PB,22), /* ARDUINO_PIN_14, TX Pin */ - .mux = GPIO_MUX_D, - .rx_pad = UART_PAD_RX_3, - .tx_pad = UART_PAD_TX_2 + .dev = &SERCOM5->USART, + .rx_pin = GPIO_PIN(PB,23), /* ARDUINO_PIN_13, RX Pin */ + .tx_pin = GPIO_PIN(PB,22), /* ARDUINO_PIN_14, TX Pin */ + .mux = GPIO_MUX_D, + .rx_pad = UART_PAD_RX_3, + .tx_pad = UART_PAD_TX_2, + .runstdby = 0, + .gclk_src = GCLK_CLKCTRL_GEN_GCLK0 } }; diff --git a/boards/arduino-zero/include/periph_conf.h b/boards/arduino-zero/include/periph_conf.h index 773ada0dd2..a34cd81e83 100644 --- a/boards/arduino-zero/include/periph_conf.h +++ b/boards/arduino-zero/include/periph_conf.h @@ -107,20 +107,24 @@ extern "C" { */ static const uart_conf_t uart_config[] = { { - .dev = &SERCOM5->USART, - .rx_pin = GPIO_PIN(PB,23), - .tx_pin = GPIO_PIN(PB,22), - .mux = GPIO_MUX_D, - .rx_pad = UART_PAD_RX_3, - .tx_pad = UART_PAD_TX_2 + .dev = &SERCOM5->USART, + .rx_pin = GPIO_PIN(PB,23), + .tx_pin = GPIO_PIN(PB,22), + .mux = GPIO_MUX_D, + .rx_pad = UART_PAD_RX_3, + .tx_pad = UART_PAD_TX_2, + .runstdby = 0, + .gclk_src = GCLK_CLKCTRL_GEN_GCLK0 }, { - .dev = &SERCOM0->USART, - .rx_pin = GPIO_PIN(PA,11), - .tx_pin = GPIO_PIN(PA,10), - .mux = GPIO_MUX_C, - .rx_pad = UART_PAD_RX_3, - .tx_pad = UART_PAD_TX_2 + .dev = &SERCOM0->USART, + .rx_pin = GPIO_PIN(PA,11), + .tx_pin = GPIO_PIN(PA,10), + .mux = GPIO_MUX_C, + .rx_pad = UART_PAD_RX_3, + .tx_pad = UART_PAD_TX_2, + .runstdby = 0, + .gclk_src = GCLK_CLKCTRL_GEN_GCLK0 } }; diff --git a/boards/samd21-xpro/include/periph_conf.h b/boards/samd21-xpro/include/periph_conf.h index 33a080b404..02e138ae64 100644 --- a/boards/samd21-xpro/include/periph_conf.h +++ b/boards/samd21-xpro/include/periph_conf.h @@ -112,12 +112,14 @@ extern "C" { */ static const uart_conf_t uart_config[] = { { /* Virtual COM Port */ - .dev = &SERCOM3->USART, - .rx_pin = GPIO_PIN(PA,23), - .tx_pin = GPIO_PIN(PA,22), - .mux = GPIO_MUX_C, - .rx_pad = UART_PAD_RX_1, - .tx_pad = UART_PAD_TX_0 + .dev = &SERCOM3->USART, + .rx_pin = GPIO_PIN(PA,23), + .tx_pin = GPIO_PIN(PA,22), + .mux = GPIO_MUX_C, + .rx_pad = UART_PAD_RX_1, + .tx_pad = UART_PAD_TX_0, + .runstdby = 0, + .gclk_src = GCLK_CLKCTRL_GEN_GCLK0 }, { /* EXT1 */ .dev = &SERCOM4->USART, @@ -125,7 +127,9 @@ static const uart_conf_t uart_config[] = { .tx_pin = GPIO_PIN(PB,8), .mux = GPIO_MUX_D, .rx_pad = UART_PAD_RX_1, - .tx_pad = UART_PAD_TX_0 + .tx_pad = UART_PAD_TX_0, + .runstdby = 0, + .gclk_src = GCLK_CLKCTRL_GEN_GCLK0 }, { /* EXT2/3 */ .dev = &SERCOM4->USART, @@ -133,7 +137,9 @@ static const uart_conf_t uart_config[] = { .tx_pin = GPIO_PIN(PB,10), .mux = GPIO_MUX_D, .rx_pad = UART_PAD_RX_3, - .tx_pad = UART_PAD_TX_2 + .tx_pad = UART_PAD_TX_2, + .runstdby = 0, + .gclk_src = GCLK_CLKCTRL_GEN_GCLK0 } }; diff --git a/boards/saml21-xpro/include/periph_conf.h b/boards/saml21-xpro/include/periph_conf.h index 2a06a98398..d3b77a23b0 100644 --- a/boards/saml21-xpro/include/periph_conf.h +++ b/boards/saml21-xpro/include/periph_conf.h @@ -52,22 +52,34 @@ extern "C" { * @name UART configuration * @{ */ -#define UART_NUMOF (1U) -#define UART_0_EN 1 -#define UART_IRQ_PRIO 1 +static const uart_conf_t uart_config[] = { + { /* Virtual COM Port */ + .dev = &SERCOM3->USART, + .rx_pin = GPIO_PIN(PA,23), + .tx_pin = GPIO_PIN(PA,22), + .mux = GPIO_MUX_C, + .rx_pad = UART_PAD_RX_1, + .tx_pad = UART_PAD_TX_0, + .runstdby = 0, + .gclk_src = GCLK_PCHCTRL_GEN_GCLK0 + }, + { /* EXT1 header */ + .dev = &SERCOM4->USART, + .rx_pin = GPIO_PIN(PB, 9), + .tx_pin = GPIO_PIN(PB, 8), + .mux = GPIO_MUX_D, + .rx_pad = UART_PAD_RX_1, + .tx_pad = UART_PAD_TX_0, + .runstdby = 0, + .gclk_src = GCLK_PCHCTRL_GEN_GCLK0 + } +}; -/* UART 0 device configuration */ -#define UART_0_DEV SERCOM3->USART -#define UART_0_IRQ SERCOM3_IRQn +/* interrupt function name mapping */ #define UART_0_ISR isr_sercom3 -#define UART_0_REF_F (16000000UL) -#define UART_0_RUNSTDBY 1 +#define UART_1_ISR isr_sercom4 -/* UART 0 pin configuration */ -#define UART_0_PORT (PORT->Group[0]) -#define UART_0_TX_PIN (22) -#define UART_0_RX_PIN (23) -#define UART_0_PINS (((PORT_PA22 | PORT_PA23) >> 16) | PORT_WRCONFIG_HWSEL) +#define UART_NUMOF (sizeof(uart_config) / sizeof(uart_config[0])) /** @} */ /** diff --git a/boards/samr21-xpro/include/periph_conf.h b/boards/samr21-xpro/include/periph_conf.h index aae2a47786..18881a5b85 100644 --- a/boards/samr21-xpro/include/periph_conf.h +++ b/boards/samr21-xpro/include/periph_conf.h @@ -117,7 +117,9 @@ static const uart_conf_t uart_config[] = { .tx_pin = GPIO_PIN(PA,4), .mux = GPIO_MUX_D, .rx_pad = UART_PAD_RX_1, - .tx_pad = UART_PAD_TX_0 + .tx_pad = UART_PAD_TX_0, + .runstdby = 0, + .gclk_src = GCLK_CLKCTRL_GEN_GCLK0 }, { .dev = &SERCOM5->USART, @@ -125,7 +127,9 @@ static const uart_conf_t uart_config[] = { .tx_pin = GPIO_PIN(PA,22), .mux = GPIO_MUX_D, .rx_pad = UART_PAD_RX_1, - .tx_pad = UART_PAD_TX_0 + .tx_pad = UART_PAD_TX_0, + .runstdby = 0, + .gclk_src = GCLK_CLKCTRL_GEN_GCLK0 } }; diff --git a/boards/sodaq-autonomo/include/periph_conf.h b/boards/sodaq-autonomo/include/periph_conf.h index c4a272ef52..e8e77dbcaf 100644 --- a/boards/sodaq-autonomo/include/periph_conf.h +++ b/boards/sodaq-autonomo/include/periph_conf.h @@ -103,36 +103,44 @@ extern "C" { */ static const uart_conf_t uart_config[] = { { - .dev = &SERCOM0->USART, - .rx_pin = GPIO_PIN(PA,9), - .tx_pin = GPIO_PIN(PA,10), - .mux = GPIO_MUX_C, - .rx_pad = UART_PAD_RX_1, - .tx_pad = UART_PAD_TX_2, + .dev = &SERCOM0->USART, + .rx_pin = GPIO_PIN(PA,9), + .tx_pin = GPIO_PIN(PA,10), + .mux = GPIO_MUX_C, + .rx_pad = UART_PAD_RX_1, + .tx_pad = UART_PAD_TX_2, + .runstdby = 0, + .gclk_src = GCLK_CLKCTRL_GEN_GCLK0 }, { - .dev = &SERCOM5->USART, - .rx_pin = GPIO_PIN(PB,31), - .tx_pin = GPIO_PIN(PB,30), - .mux = GPIO_MUX_D, - .rx_pad = UART_PAD_RX_1, - .tx_pad = UART_PAD_TX_0_RTS_2_CTS_3, + .dev = &SERCOM5->USART, + .rx_pin = GPIO_PIN(PB,31), + .tx_pin = GPIO_PIN(PB,30), + .mux = GPIO_MUX_D, + .rx_pad = UART_PAD_RX_1, + .tx_pad = UART_PAD_TX_0_RTS_2_CTS_3, + .runstdby = 0, + .gclk_src = GCLK_CLKCTRL_GEN_GCLK0 }, { - .dev = &SERCOM4->USART, - .rx_pin = GPIO_PIN(PB,13), - .tx_pin = GPIO_PIN(PA,14), - .mux = GPIO_MUX_C, - .rx_pad = UART_PAD_RX_1, - .tx_pad = UART_PAD_TX_2, + .dev = &SERCOM4->USART, + .rx_pin = GPIO_PIN(PB,13), + .tx_pin = GPIO_PIN(PA,14), + .mux = GPIO_MUX_C, + .rx_pad = UART_PAD_RX_1, + .tx_pad = UART_PAD_TX_2, + .runstdby = 0, + .gclk_src = GCLK_CLKCTRL_GEN_GCLK0 }, { - .dev = &SERCOM1->USART, - .rx_pin = GPIO_PIN(PA,17), - .tx_pin = GPIO_PIN(PA,18), - .mux = GPIO_MUX_C, - .rx_pad = UART_PAD_RX_1, - .tx_pad = UART_PAD_TX_2, + .dev = &SERCOM1->USART, + .rx_pin = GPIO_PIN(PA,17), + .tx_pin = GPIO_PIN(PA,18), + .mux = GPIO_MUX_C, + .rx_pad = UART_PAD_RX_1, + .tx_pad = UART_PAD_TX_2, + .runstdby = 0, + .gclk_src = GCLK_CLKCTRL_GEN_GCLK0 } }; diff --git a/cpu/sam0_common/periph/uart.c b/cpu/sam0_common/periph/uart.c index fafe2cac9d..6e1c9fc219 100644 --- a/cpu/sam0_common/periph/uart.c +++ b/cpu/sam0_common/periph/uart.c @@ -51,44 +51,17 @@ static inline SercomUsart *_uart(uart_t dev) static uint64_t _long_division(uint64_t n, uint64_t d); -/** - * @brief Get the sercom gclk id of the given UART device - * - * @param[in] dev UART device identifier - * - * @return sercom gclk id - */ +static uint8_t sercom_gclk_id[] = + { + SERCOM0_GCLK_ID_CORE, + SERCOM1_GCLK_ID_CORE, + SERCOM2_GCLK_ID_CORE, + SERCOM3_GCLK_ID_CORE, + SERCOM4_GCLK_ID_CORE, + SERCOM5_GCLK_ID_CORE + }; -static int _get_sercom_gclk_id(SercomUsart *dev) -{ - int id; - switch(sercom_id(dev)) { - case 0: - id = SERCOM0_GCLK_ID_CORE; - break; - case 1: - id = SERCOM1_GCLK_ID_CORE; - break; - case 2: - id = SERCOM2_GCLK_ID_CORE; - break; - case 3: - id = SERCOM3_GCLK_ID_CORE; - break; - case 4: - id = SERCOM4_GCLK_ID_CORE; - break; - case 5: - id = SERCOM5_GCLK_ID_CORE; - break; - default: - id = -1; - DEBUG("[UART]: wrong SERCOM ID\n"); - break; - } - return id; -} #endif static int init_base(uart_t uart, uint32_t baudrate); @@ -130,7 +103,7 @@ static int init_base(uart_t uart, uint32_t baudrate) #ifdef CPU_FAM_SAMD21 /* calculate baudrate */ - uint32_t baud = ((((uint32_t)CLOCK_CORECLOCK * 10) / baudrate) / 16); + uint32_t baud = ((((uint32_t)CLOCK_CORECLOCK * 10) / baudrate) / 16); /* enable sync and async clocks */ uart_poweron(uart); /* reset the UART device */ @@ -210,11 +183,12 @@ void uart_poweron(uart_t uart) while (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY) {} #elif CPU_FAM_SAML21 /* Enable the peripheral channel */ - GCLK->PCHCTRL[_get_sercom_gclk_id(dev)].reg |= GCLK_PCHCTRL_CHEN | - GCLK_PCHCTRL_GEN(uart_config[uart].gclk_src); + GCLK->PCHCTRL[sercom_gclk_id[sercom_id(dev)]].reg |= + GCLK_PCHCTRL_CHEN | GCLK_PCHCTRL_GEN(uart_config[uart].gclk_src); - while (!(GCLK->PCHCTRL[_get_sercom_gclk_id(dev)].reg & GCLK_PCHCTRL_CHEN)) {} - if(_get_sercom_gclk_id(dev) < 5) { + while (!(GCLK->PCHCTRL[sercom_gclk_id[sercom_id(dev)]].reg & + GCLK_PCHCTRL_CHEN)) {} + if(sercom_gclk_id[sercom_id(dev)] < 5) { MCLK->APBCMASK.reg |= MCLK_APBCMASK_SERCOM0 << sercom_id(dev); } else { @@ -240,9 +214,9 @@ void uart_poweroff(uart_t uart) while (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY) {} #elif CPU_FAM_SAML21 /* Enable the peripheral channel */ - GCLK->PCHCTRL[_get_sercom_gclk_id(dev)].reg &= ~GCLK_PCHCTRL_CHEN; + GCLK->PCHCTRL[sercom_gclk_id[sercom_id(dev)]].reg &= ~GCLK_PCHCTRL_CHEN; - if(_get_sercom_gclk_id(dev) < 5) { + if(sercom_gclk_id[sercom_id(dev)] < 5) { MCLK->APBCMASK.reg &= ~(MCLK_APBCMASK_SERCOM0 << sercom_id(dev)); } else { @@ -259,7 +233,8 @@ static inline void irq_handler(uint8_t uartnum) #ifdef CPU_FAM_SAMD21 if (uart->INTFLAG.reg & SERCOM_USART_INTFLAG_RXC) { /* interrupt flag is cleared by reading the data register */ - uart_ctx[uartnum].rx_cb(uart_ctx[uartnum].arg, (uint8_t)(uart->DATA.reg)); + uart_ctx[uartnum].rx_cb(uart_ctx[uartnum].arg, + (uint8_t)(uart->DATA.reg)); } else if (uart->INTFLAG.reg & SERCOM_USART_INTFLAG_ERROR) { /* clear error flag */ From a3acd1d7417bf4c45e7e42f816eae8bc0e6ecb81 Mon Sep 17 00:00:00 2001 From: dylad Date: Tue, 29 Aug 2017 20:53:52 +0200 Subject: [PATCH 3/3] remove dev variable for cppcheck Signed-off-by: dylad --- cpu/sam0_common/periph/uart.c | 81 ++++++++++++++--------------------- 1 file changed, 33 insertions(+), 48 deletions(-) diff --git a/cpu/sam0_common/periph/uart.c b/cpu/sam0_common/periph/uart.c index 6e1c9fc219..f564af957f 100644 --- a/cpu/sam0_common/periph/uart.c +++ b/cpu/sam0_common/periph/uart.c @@ -86,15 +86,11 @@ int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, void *arg) static int init_base(uart_t uart, uint32_t baudrate) { - SercomUsart *dev; if ((unsigned int)uart >= UART_NUMOF) { return UART_NODEV; } - /* get the devices base register */ - dev = _uart(uart); - /* configure pins */ gpio_init(uart_config[uart].rx_pin, GPIO_IN); gpio_init_mux(uart_config[uart].rx_pin, uart_config[uart].mux); @@ -107,11 +103,11 @@ static int init_base(uart_t uart, uint32_t baudrate) /* enable sync and async clocks */ uart_poweron(uart); /* reset the UART device */ - dev->CTRLA.reg = SERCOM_USART_CTRLA_SWRST; - while (dev->SYNCBUSY.reg & SERCOM_USART_SYNCBUSY_SWRST) {} + _uart(uart)->CTRLA.reg = SERCOM_USART_CTRLA_SWRST; + while (_uart(uart)->SYNCBUSY.reg & SERCOM_USART_SYNCBUSY_SWRST) {} /* set asynchronous mode w/o parity, LSB first, TX and RX pad as specified * by the board in the periph_conf.h, x16 sampling and use internal clock */ - dev->CTRLA.reg = (SERCOM_USART_CTRLA_DORD | + _uart(uart)->CTRLA.reg = (SERCOM_USART_CTRLA_DORD | SERCOM_USART_CTRLA_SAMPR(0x1) | SERCOM_USART_CTRLA_TXPO(uart_config[uart].tx_pad) | SERCOM_USART_CTRLA_RXPO(uart_config[uart].rx_pad) | @@ -120,11 +116,11 @@ static int init_base(uart_t uart, uint32_t baudrate) SERCOM_USART_CTRLA_RUNSTDBY : 0)); /* set baudrate */ - dev->BAUD.FRAC.FP = (baud % 10); - dev->BAUD.FRAC.BAUD = (baud / 10); + _uart(uart)->BAUD.FRAC.FP = (baud % 10); + _uart(uart)->BAUD.FRAC.BAUD = (baud / 10); /* enable receiver and transmitter, use 1 stop bit */ - dev->CTRLB.reg = (SERCOM_USART_CTRLB_RXEN | SERCOM_USART_CTRLB_TXEN); - while (dev->SYNCBUSY.reg & SERCOM_USART_SYNCBUSY_CTRLB) {} + _uart(uart)->CTRLB.reg = (SERCOM_USART_CTRLB_RXEN | SERCOM_USART_CTRLB_TXEN); + while (_uart(uart)->SYNCBUSY.reg & SERCOM_USART_SYNCBUSY_CTRLB) {} #elif CPU_FAM_SAML21 /* Calculate the BAUD value */ uint64_t temp1 = ((16 * ((uint64_t)baudrate)) << 32); @@ -132,12 +128,12 @@ static int init_base(uart_t uart, uint32_t baudrate) uint64_t scale = ((uint64_t)1 << 32) - ratio; uint64_t baud_calculated = (65536 * scale) >> 32; - dev->CTRLA.bit.ENABLE = 0; /* Disable to write, need to sync tho */ - while(dev->SYNCBUSY.bit.ENABLE) {} + _uart(uart)->CTRLA.bit.ENABLE = 0; /* Disable to write, need to sync tho */ + while(_uart(uart)->SYNCBUSY.bit.ENABLE) {} /* set to LSB, asynchronous mode without parity, PAD0 Tx, PAD1 Rx, * 16x over-sampling, internal clk */ - dev->CTRLA.reg = SERCOM_USART_CTRLA_DORD \ + _uart(uart)->CTRLA.reg = SERCOM_USART_CTRLA_DORD \ | SERCOM_USART_CTRLA_FORM(0x0) \ | SERCOM_USART_CTRLA_SAMPA(0x0) \ | SERCOM_USART_CTRLA_TXPO(uart_config[uart].tx_pad) \ @@ -148,11 +144,11 @@ static int init_base(uart_t uart, uint32_t baudrate) SERCOM_USART_CTRLA_RUNSTDBY : 0); /* Set baud rate */ - dev->BAUD.bit.BAUD = baud_calculated; + _uart(uart)->BAUD.bit.BAUD = baud_calculated; /* enable receiver and transmitter, one stop bit*/ - dev->CTRLB.reg = (SERCOM_USART_CTRLB_RXEN | SERCOM_USART_CTRLB_TXEN); - while(dev->SYNCBUSY.bit.CTRLB) {} + _uart(uart)->CTRLB.reg = (SERCOM_USART_CTRLB_RXEN | SERCOM_USART_CTRLB_TXEN); + while(_uart(uart)->SYNCBUSY.bit.CTRLB) {} uart_poweron(uart); #endif return UART_OK; @@ -169,11 +165,6 @@ void uart_write(uart_t uart, const uint8_t *data, size_t len) void uart_poweron(uart_t uart) { - SercomUsart *dev; - - /* get the devices base register */ - dev = _uart(uart); - #ifdef CPU_FAM_SAMD21 PM->APBCMASK.reg |= (PM_APBCMASK_SERCOM0 << sercom_id(_uart(uart))); GCLK->CLKCTRL.reg = (GCLK_CLKCTRL_CLKEN | @@ -183,72 +174,66 @@ void uart_poweron(uart_t uart) while (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY) {} #elif CPU_FAM_SAML21 /* Enable the peripheral channel */ - GCLK->PCHCTRL[sercom_gclk_id[sercom_id(dev)]].reg |= + GCLK->PCHCTRL[sercom_gclk_id[sercom_id(_uart(uart))]].reg |= GCLK_PCHCTRL_CHEN | GCLK_PCHCTRL_GEN(uart_config[uart].gclk_src); - while (!(GCLK->PCHCTRL[sercom_gclk_id[sercom_id(dev)]].reg & + while (!(GCLK->PCHCTRL[sercom_gclk_id[sercom_id(_uart(uart))]].reg & GCLK_PCHCTRL_CHEN)) {} - if(sercom_gclk_id[sercom_id(dev)] < 5) { - MCLK->APBCMASK.reg |= MCLK_APBCMASK_SERCOM0 << sercom_id(dev); + if(sercom_gclk_id[sercom_id(_uart(uart))] < 5) { + MCLK->APBCMASK.reg |= MCLK_APBCMASK_SERCOM0 << sercom_id(_uart(uart)); } else { MCLK->APBDMASK.reg |= MCLK_APBDMASK_SERCOM5; } - while (dev->SYNCBUSY.reg) {} + while (_uart(uart)->SYNCBUSY.reg) {} #endif /* finally, enable the device */ - dev->CTRLA.reg |= SERCOM_USART_CTRLA_ENABLE; + _uart(uart)->CTRLA.reg |= SERCOM_USART_CTRLA_ENABLE; } void uart_poweroff(uart_t uart) { - SercomUsart *dev; - - /* get the devices base register */ - dev = _uart(uart); - #ifdef CPU_FAM_SAMD21 - PM->APBCMASK.reg &= ~(PM_APBCMASK_SERCOM0 << sercom_id(dev)); - GCLK->CLKCTRL.reg = ((SERCOM0_GCLK_ID_CORE + sercom_id(dev)) << + PM->APBCMASK.reg &= ~(PM_APBCMASK_SERCOM0 << sercom_id(_uart(uart))); + GCLK->CLKCTRL.reg = ((SERCOM0_GCLK_ID_CORE + sercom_id(_uart(uart))) << GCLK_CLKCTRL_ID_Pos); while (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY) {} #elif CPU_FAM_SAML21 /* Enable the peripheral channel */ - GCLK->PCHCTRL[sercom_gclk_id[sercom_id(dev)]].reg &= ~GCLK_PCHCTRL_CHEN; + GCLK->PCHCTRL[sercom_gclk_id[sercom_id(_uart(uart))]].reg &= ~GCLK_PCHCTRL_CHEN; - if(sercom_gclk_id[sercom_id(dev)] < 5) { - MCLK->APBCMASK.reg &= ~(MCLK_APBCMASK_SERCOM0 << sercom_id(dev)); + if(sercom_gclk_id[sercom_id(_uart(uart))] < 5) { + MCLK->APBCMASK.reg &= ~(MCLK_APBCMASK_SERCOM0 << sercom_id(_uart(uart))); } else { MCLK->APBDMASK.reg &= ~MCLK_APBDMASK_SERCOM5; } - while (dev->SYNCBUSY.reg) {} + while (_uart(uart)->SYNCBUSY.reg) {} #endif } static inline void irq_handler(uint8_t uartnum) { - SercomUsart *uart = _uart(uartnum); #ifdef CPU_FAM_SAMD21 - if (uart->INTFLAG.reg & SERCOM_USART_INTFLAG_RXC) { + if (_uart(uartnum)->INTFLAG.reg & SERCOM_USART_INTFLAG_RXC) { /* interrupt flag is cleared by reading the data register */ uart_ctx[uartnum].rx_cb(uart_ctx[uartnum].arg, - (uint8_t)(uart->DATA.reg)); + (uint8_t)(_uart(uartnum)->DATA.reg)); } - else if (uart->INTFLAG.reg & SERCOM_USART_INTFLAG_ERROR) { + else if (_uart(uartnum)->INTFLAG.reg & SERCOM_USART_INTFLAG_ERROR) { /* clear error flag */ - uart->INTFLAG.reg = SERCOM_USART_INTFLAG_ERROR; + _uart(uartnum)->INTFLAG.reg = SERCOM_USART_INTFLAG_ERROR; } #elif CPU_FAM_SAML21 - if (uart->INTFLAG.bit.RXC) { + if (_uart(uartnum)->INTFLAG.bit.RXC) { /* cleared by reading DATA regiser */ - uint8_t data = (uint8_t)uart->DATA.reg; + uint8_t data = (uint8_t)_uart(uartnum)->DATA.reg; uart_ctx[uartnum].rx_cb(uart_ctx[uartnum].arg, data); } - else if (uart->INTFLAG.bit.ERROR) { + else if (_uart(uartnum)->INTFLAG.bit.ERROR) { /* clear error flag */ - uart->INTFLAG.reg |= SERCOM_USART_INTFLAG_ERROR; + _uart(uartnum)->INTFLAG.reg |= SERCOM_USART_INTFLAG_ERROR; } #endif cortexm_isr_end();