diff --git a/cpu/cc2538/include/cc2538_uart.h b/cpu/cc2538/include/cc2538_uart.h index 0fd671a983..43fdb3beb9 100644 --- a/cpu/cc2538/include/cc2538_uart.h +++ b/cpu/cc2538/include/cc2538_uart.h @@ -180,8 +180,8 @@ typedef struct { cc2538_reg_t RESERVED7[13]; /**< Reserved addresses */ } cc2538_uart_t; -extern cc2538_uart_t * const UART0; /**< UART0 Instance */ -extern cc2538_uart_t * const UART1; /**< UART1 Instance */ +#define UART0_BASEADDR (cc2538_uart_t *)(&UART0_DR) /**< UART0 Instance */ +#define UART1_BASEADDR (cc2538_uart_t *)(&UART1_DR) /**< UART1 Instance */ #ifdef __cplusplus } /* end extern "C" */ diff --git a/cpu/cc2538/include/periph_cpu.h b/cpu/cc2538/include/periph_cpu.h index 8ce2e13f64..4511dd8ea4 100644 --- a/cpu/cc2538/include/periph_cpu.h +++ b/cpu/cc2538/include/periph_cpu.h @@ -112,6 +112,20 @@ typedef enum { } gpio_mode_t; /** @} */ + +/** + * @name UART device configuration + * @{ + */ +typedef struct { + cc2538_uart_t *dev; /**< pointer to the used UART device */ + gpio_t rx_pin; /**< pin used for RX */ + gpio_t tx_pin; /**< pin used for TX */ + gpio_t cts_pin; /**< CTS pin - set to GPIO_UNDEF when not using */ + gpio_t rts_pin; /**< RTS pin - set to GPIO_UNDEF when not using */ +} uart_conf_t; +/** @} */ + /** * @name Override SPI mode settings * @{ @@ -240,7 +254,5 @@ typedef gpio_t adc_conf_t; } #endif -#include "periph/dev_enums.h" - #endif /* PERIPH_CPU_H */ /** @} */ diff --git a/cpu/cc2538/periph/uart.c b/cpu/cc2538/periph/uart.c index c08e8fca88..3baacd4064 100644 --- a/cpu/cc2538/periph/uart.c +++ b/cpu/cc2538/periph/uart.c @@ -27,8 +27,24 @@ #include "periph/uart.h" #include "periph_conf.h" -#undef BIT -#define BIT(n) ( 1 << (n) ) +/* Pin functions and interrupt definitions for the two UARTs */ +#define UART_RXD(X) (cc2538_ioc_pin_t)(2 * (X)) +#define UART_TXD(X) (cc2538_ioc_sel_t)(2 * (X)) +#define UART_IRQ(X) (IRQn_Type)(5 + (X)) + +/* Bit field definitions for the UART Line Control Register: */ +#define FEN (1 << 4) /**< Enable FIFOs */ + +/* Bit masks for the UART Masked Interrupt Status (MIS) Register: */ +#define OEMIS (1 << 10) /**< UART overrun errors */ +#define BEMIS (1 << 9) /**< UART break error */ +#define FEMIS (1 << 7) /**< UART framing error */ +#define RTMIS (1 << 6) /**< UART RX time-out */ +#define RXMIS (1 << 4) /**< UART RX masked interrupt */ + +#define UART_CTL_HSE_VALUE (0) +#define DIVFRAC_NUM_BITS (6) +#define DIVFRAC_MASK ((1 << DIVFRAC_NUM_BITS) - 1) enum { FIFO_LEVEL_1_8TH = 0, @@ -46,173 +62,32 @@ enum { WLEN_8_BITS = 3, }; -/* Bit field definitions for the UART Line Control Register: */ -#define FEN BIT( 4) /**< Enable FIFOs */ - -/* Bit masks for the UART Masked Interrupt Status (MIS) Register: */ -#define OEMIS BIT(10) /**< UART overrun error masked status */ -#define BEMIS BIT( 9) /**< UART break error masked status */ -#define FEMIS BIT( 7) /**< UART framing error masked status */ -#define RTMIS BIT( 6) /**< UART RX time-out masked status */ -#define RXMIS BIT( 4) /**< UART RX masked interrupt status */ - -#define UART_CTL_HSE_VALUE 0 -#define DIVFRAC_NUM_BITS 6 -#define DIVFRAC_MASK ( (1 << DIVFRAC_NUM_BITS) - 1 ) - -/** @brief Indicates if there are bytes available in the UART0 receive FIFO */ -#define uart0_rx_avail() ( UART0->cc2538_uart_fr.FRbits.RXFE == 0 ) - -/** @brief Indicates if there are bytes available in the UART1 receive FIFO */ -#define uart1_rx_avail() ( UART1->cc2538_uart_fr.FRbits.RXFE == 0 ) - -/** @brief Read one byte from the UART0 receive FIFO */ -#define uart0_read() ( UART0->DR ) - -/** @brief Read one byte from the UART1 receive FIFO */ -#define uart1_read() ( UART1->DR ) - -/*---------------------------------------------------------------------------*/ - /** * @brief Allocate memory to store the callback functions. */ -static uart_isr_ctx_t uart_config[UART_NUMOF]; - -cc2538_uart_t * const UART0 = (cc2538_uart_t *)0x4000c000; -cc2538_uart_t * const UART1 = (cc2538_uart_t *)0x4000d000; - -/*---------------------------------------------------------------------------*/ -static void reset(cc2538_uart_t *u) -{ - /* Make sure the UART is disabled before trying to configure it */ - u->cc2538_uart_ctl.CTLbits.UARTEN = 0; - - u->cc2538_uart_ctl.CTLbits.RXE = 1; - u->cc2538_uart_ctl.CTLbits.TXE = 1; - u->cc2538_uart_ctl.CTLbits.HSE = UART_CTL_HSE_VALUE; - - /* Clear error status */ - u->cc2538_uart_dr.ECR = 0xFF; - - /* Flush FIFOs by clearing LCHR.FEN */ - u->cc2538_uart_lcrh.LCRH &= ~FEN; - - /* Restore LCHR configuration */ - u->cc2538_uart_lcrh.LCRH |= FEN; - - /* UART Enable */ - u->cc2538_uart_ctl.CTLbits.UARTEN = 1; -} -/*---------------------------------------------------------------------------*/ - -#if UART_0_EN -void UART_0_ISR(void) -{ - uint_fast16_t mis; - - /* Latch the Masked Interrupt Status and clear any active flags */ - mis = UART_0_DEV->cc2538_uart_mis.MIS; - UART_0_DEV->ICR = mis; - - while (UART_0_DEV->cc2538_uart_fr.FRbits.RXFE == 0) { - uart_config[0].rx_cb(uart_config[0].arg, UART_0_DEV->DR); - } - - if (mis & (OEMIS | BEMIS | FEMIS)) { - /* ISR triggered due to some error condition */ - reset(UART_0_DEV); - } - - cortexm_isr_end(); -} -#endif /* UART_0_EN */ - -#if UART_1_EN -void UART_1_ISR(void) -{ - uint_fast16_t mis; - - /* Latch the Masked Interrupt Status and clear any active flags */ - mis = UART_1_DEV->cc2538_uart_mis.MIS; - UART_1_DEV->ICR = mis; - - while (UART_1_DEV->cc2538_uart_fr.FRbits.RXFE == 0) { - uart_config[1].rx_cb(uart_config[1].arg, UART_1_DEV->DR); - } - - if (mis & (OEMIS | BEMIS | FEMIS)) { - /* ISR triggered due to some error condition */ - reset(UART_1_DEV); - } - - cortexm_isr_end(); -} -#endif /* UART_1_EN */ - -static int init_base(uart_t uart, uint32_t baudrate); +static uart_isr_ctx_t uart_ctx[UART_NUMOF]; 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; + assert(uart < UART_NUMOF); + + cc2538_uart_t *u = uart_config[uart].dev; + + /* uart_num refers to the CPU UART peripheral number, which may be + * different from the value of the uart variable, depending on the board + * configuration. + */ + unsigned int uart_num = ((uintptr_t)u - (uintptr_t)UART0_BASEADDR) / 0x1000; + + /* Configure the Rx and Tx pins. If no callback function is defined, + * the UART should be initialised in Tx only mode. + */ + if (rx_cb) { + gpio_init_af(uart_config[uart].rx_pin, UART_RXD(uart_num), GPIO_IN); } + gpio_init_af(uart_config[uart].tx_pin, UART_TXD(uart_num), GPIO_OUT); - /* register callbacks */ - uart_config[uart].rx_cb = rx_cb; - uart_config[uart].arg = arg; - - /* configure interrupts and enable RX interrupt */ - switch (uart) { -#if UART_0_EN - case UART_0: - NVIC_SetPriority(UART0_IRQn, UART_IRQ_PRIO); - NVIC_EnableIRQ(UART0_IRQn); - break; -#endif -#if UART_1_EN - case UART_1: - NVIC_SetPriority(UART1_IRQn, UART_IRQ_PRIO); - NVIC_EnableIRQ(UART1_IRQn); - break; -#endif - default: - return UART_NODEV; - } - - return UART_OK; -} - -static int init_base(uart_t uart, uint32_t baudrate) -{ - cc2538_uart_t *u = NULL; - - switch (uart) { -#if UART_0_EN - case UART_0: - u = UART_0_DEV; - gpio_init_af(UART_0_RX_PIN, UART0_RXD, GPIO_IN); - gpio_init_af(UART_0_TX_PIN, UART0_TXD, GPIO_OUT); - break; -#endif -#if UART_1_EN - case UART_1: - u = UART_1_DEV; - gpio_init_af(UART_1_RX_PIN, UART1_RXD, GPIO_IN); - gpio_init_af(UART_1_TX_PIN, UART1_TXD, GPIO_OUT); - break; -#endif - - default: - (void)u; - return UART_NODEV; - } - -#if UART_0_EN || UART_1_EN /* Enable clock for the UART while Running, in Sleep and Deep Sleep */ - unsigned int uart_num = ( (uintptr_t)u - (uintptr_t)UART0 ) / 0x1000; SYS_CTRL_RCGCUART |= (1 << uart_num); SYS_CTRL_SCGCUART |= (1 << uart_num); SYS_CTRL_DCGCUART |= (1 << uart_num); @@ -224,42 +99,36 @@ static int init_base(uart_t uart, uint32_t baudrate) u->CC = 0; /* On the CC2538, hardware flow control is supported only on UART1 */ - if (u == UART1) { -#ifdef UART_1_RTS_PIN - gpio_init_af(UART_1_RTS_PIN, UART1_RTS, GPIO_OUT); + if (uart_config[uart].rts_pin != GPIO_UNDEF) { + assert(u != UART0_BASEADDR); + gpio_init_af(uart_config[uart].rts_pin, UART1_RTS, GPIO_OUT); u->cc2538_uart_ctl.CTLbits.RTSEN = 1; -#endif - -#ifdef UART_1_CTS_PIN - gpio_init_af(UART_1_CTS_PIN, UART1_CTS, GPIO_IN); - u->cc2538_uart_ctl.CTLbits.CTSEN = 1; -#endif } - /* Enable clock for the UART while Running, in Sleep and Deep Sleep */ - uart_num = ( (uintptr_t)u - (uintptr_t)UART0 ) / 0x1000; - SYS_CTRL_RCGCUART |= (1 << uart_num); - SYS_CTRL_SCGCUART |= (1 << uart_num); - SYS_CTRL_DCGCUART |= (1 << uart_num); + if (uart_config[uart].cts_pin != GPIO_UNDEF) { + assert(u != UART0_BASEADDR); + gpio_init_af(uart_config[uart].cts_pin, UART1_CTS, GPIO_IN); + u->cc2538_uart_ctl.CTLbits.CTSEN = 1; + } /* - * UART Interrupt Masks: - * Acknowledge RX and RX Timeout - * Acknowledge Framing, Overrun and Break Errors + * UART Interrupt Setup: + * Acknowledge Overrun, Break and Framing Errors + * Acknowledge RX Timeout and Rx */ - u->cc2538_uart_im.IM = 0; - u->cc2538_uart_im.IMbits.RXIM = 1; /**< UART receive interrupt mask */ - u->cc2538_uart_im.IMbits.RTIM = 1; /**< UART receive time-out interrupt mask */ - u->cc2538_uart_im.IMbits.OEIM = 1; /**< UART overrun error interrupt mask */ - u->cc2538_uart_im.IMbits.BEIM = 1; /**< UART break error interrupt mask */ - u->cc2538_uart_im.IMbits.FEIM = 1; /**< UART framing error interrupt mask */ + u->cc2538_uart_im.IM = (OEMIS | BEMIS | FEMIS | RTMIS | RXMIS); - /* Set FIFO interrupt levels: */ - u->cc2538_uart_ifls.IFLSbits.RXIFLSEL = FIFO_LEVEL_4_8TH; /**< MCU default */ - u->cc2538_uart_ifls.IFLSbits.TXIFLSEL = FIFO_LEVEL_4_8TH; /**< MCU default */ - - u->cc2538_uart_ctl.CTLbits.RXE = 1; + /* Set FIFO interrupt levels and enable Rx and/or Tx: */ + if (rx_cb) { + u->cc2538_uart_ifls.IFLSbits.RXIFLSEL = FIFO_LEVEL_4_8TH; /**< MCU default */ + u->cc2538_uart_ctl.CTLbits.RXE = 1; + } + u->cc2538_uart_ifls.IFLSbits.TXIFLSEL = FIFO_LEVEL_4_8TH; /**< MCU default */ u->cc2538_uart_ctl.CTLbits.TXE = 1; + + /* Enable high speed (UART is clocked using system clock divided by 8 + * rather than 16) + */ u->cc2538_uart_ctl.CTLbits.HSE = UART_CTL_HSE_VALUE; /* Set the divisor for the baud rate generator */ @@ -273,31 +142,26 @@ static int init_base(uart_t uart, uint32_t baudrate) /* Configure line control for 8-bit, no parity, 1 stop bit and enable */ u->cc2538_uart_lcrh.LCRH = (WLEN_8_BITS << 5) | FEN; + /* register callbacks */ + if (rx_cb) { + uart_ctx[uart].rx_cb = rx_cb; + uart_ctx[uart].arg = arg; + } + + /* enable UART interrupt */ + NVIC_EnableIRQ(UART_IRQ(uart_num)); + /* UART Enable */ u->cc2538_uart_ctl.CTLbits.UARTEN = 1; return UART_OK; -#endif /* UART_0_EN || UART_1_EN */ } void uart_write(uart_t uart, const uint8_t *data, size_t len) { - cc2538_uart_t *u; + assert(uart < UART_NUMOF); - switch (uart) { -#if UART_0_EN - case UART_0: - u = UART_0_DEV; - break; -#endif -#if UART_1_EN - case UART_1: - u = UART_1_DEV; - break; -#endif - default: - return; - } + cc2538_uart_t *u = uart_config[uart].dev; /* Block if the TX FIFO is full */ for (size_t i = 0; i < len; i++) { @@ -308,11 +172,59 @@ void uart_write(uart_t uart, const uint8_t *data, size_t len) void uart_poweron(uart_t uart) { - (void) uart; + assert(uart < UART_NUMOF); + /* Turn the clock on first, in case it has been turned off */ + SYS_CTRL->cc2538_sys_ctrl_unnamed1.RCGCUART |= (1 << uart); + + uart_config[uart].dev->cc2538_uart_ctl.CTLbits.UARTEN = 1; } void uart_poweroff(uart_t uart) { - (void) uart; + assert(uart < UART_NUMOF); + + /* Wait for the TX FIFO to clear */ + while (uart_config[uart].dev->cc2538_uart_fr.FRbits.TXFF) {} + + uart_config[uart].dev->cc2538_uart_ctl.CTLbits.UARTEN = 0; + + /* Turn the clock off afterwards to save power */ + SYS_CTRL->cc2538_sys_ctrl_unnamed1.RCGCUART &= ~(1 << uart); } + +static inline void irq_handler(uart_t uart) +{ + assert(uart < UART_NUMOF); + + cc2538_uart_t *u = uart_config[uart].dev; + + /* Latch the Masked Interrupt Status and clear any active flags */ + uint16_t mis = uart_config[uart].dev->cc2538_uart_mis.MIS; + uart_config[uart].dev->ICR = mis; + + while (uart_config[uart].dev->cc2538_uart_fr.FRbits.RXFE == 0) { + uart_ctx[uart].rx_cb(uart_ctx[uart].arg, uart_config[uart].dev->DR); + } + + if (mis & (OEMIS | BEMIS | FEMIS)) { + /* Clear error status */ + u->cc2538_uart_dr.ECR = 0xFF; + } + + cortexm_isr_end(); +} + +#ifdef UART_0_ISR +void UART_0_ISR(void) +{ + irq_handler((uart_t)0); +} +#endif + +#ifdef UART_1_ISR +void UART_1_ISR(void) +{ + irq_handler((uart_t)1); +} +#endif