1
0
mirror of https://github.com/RIOT-OS/RIOT.git synced 2025-12-24 22:13:52 +01:00

Merge pull request #7260 from dylad/sam0_uart

sam0/uart: merge samd21 & saml21 uart driver
This commit is contained in:
Hauke Petersen 2017-08-29 22:45:43 +02:00 committed by GitHub
commit 8acaab6ee2
11 changed files with 421 additions and 453 deletions

View File

@ -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
}
};

View File

@ -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
}
};

View File

@ -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
}
};

View File

@ -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]))
/** @} */
/**

View File

@ -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
}
};

View File

@ -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
}
};

View File

@ -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
*/

View File

@ -0,0 +1,306 @@
/*
* 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 <thomas.eichinger@fu-berlin.de>
* @author Troels Hoffmeyer <troels.d.hoffmeyer@gmail.com>
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Dylan Laduranty <dylanladuranty@gmail.com>
*
* @}
*/
#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);
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
};
#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)
{
if ((unsigned int)uart >= UART_NUMOF) {
return UART_NODEV;
}
/* 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 */
_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 */
_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) |
SERCOM_USART_CTRLA_MODE_USART_INT_CLK |
(uart_config[uart].runstdby ?
SERCOM_USART_CTRLA_RUNSTDBY : 0));
/* set baudrate */
_uart(uart)->BAUD.FRAC.FP = (baud % 10);
_uart(uart)->BAUD.FRAC.BAUD = (baud / 10);
/* enable receiver and transmitter, use 1 stop bit */
_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);
uint64_t ratio = _long_division(temp1 , CLOCK_CORECLOCK);
uint64_t scale = ((uint64_t)1 << 32) - ratio;
uint64_t baud_calculated = (65536 * scale) >> 32;
_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 */
_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) \
| 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 */
_uart(uart)->BAUD.bit.BAUD = baud_calculated;
/* enable receiver and transmitter, one stop bit*/
_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;
}
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)
{
#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[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(_uart(uart))]].reg &
GCLK_PCHCTRL_CHEN)) {}
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 (_uart(uart)->SYNCBUSY.reg) {}
#endif
/* finally, enable the device */
_uart(uart)->CTRLA.reg |= SERCOM_USART_CTRLA_ENABLE;
}
void uart_poweroff(uart_t uart)
{
#ifdef CPU_FAM_SAMD21
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(_uart(uart))]].reg &= ~GCLK_PCHCTRL_CHEN;
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 (_uart(uart)->SYNCBUSY.reg) {}
#endif
}
static inline void irq_handler(uint8_t uartnum)
{
#ifdef CPU_FAM_SAMD21
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(uartnum)->DATA.reg));
}
else if (_uart(uartnum)->INTFLAG.reg & SERCOM_USART_INTFLAG_ERROR) {
/* clear error flag */
_uart(uartnum)->INTFLAG.reg = SERCOM_USART_INTFLAG_ERROR;
}
#elif CPU_FAM_SAML21
if (_uart(uartnum)->INTFLAG.bit.RXC) {
/* cleared by reading DATA regiser */
uint8_t data = (uint8_t)_uart(uartnum)->DATA.reg;
uart_ctx[uartnum].rx_cb(uart_ctx[uartnum].arg, data);
}
else if (_uart(uartnum)->INTFLAG.bit.ERROR) {
/* clear error flag */
_uart(uartnum)->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

View File

@ -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
*

View File

@ -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 <thomas.eichinger@fu-berlin.de>
* @author Troels Hoffmeyer <troels.d.hoffmeyer@gmail.com>
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*
* @}
*/
#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

View File

@ -1,187 +0,0 @@
/*
* Copyright (C) 2014 Freie Universität Berlin
* 2015 Kaspar Schleiser <kaspar@schleiser.de>
* 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 <thomas.eichinger@fu-berlin.de>
* @author Troels Hoffmeyer <troels.d.hoffmeyer@gmail.com>
*
* @}
*/
#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;
}