From 5d5fc5f3d4f24c903e4638099ebb1abc0a1c55f4 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 27 Feb 2013 20:34:57 +0000 Subject: The NuTiny-SDK-NUC120 basic port is complete and functional git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5682 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/nuc1xx/chip/nuc_uart.h | 23 +-- nuttx/arch/arm/src/nuc1xx/nuc_irq.c | 31 ++++ nuttx/arch/arm/src/nuc1xx/nuc_irq.h | 65 ++++++++ nuttx/arch/arm/src/nuc1xx/nuc_lowputc.c | 4 +- nuttx/arch/arm/src/nuc1xx/nuc_serial.c | 262 ++++++++++++++++++++++++------ 5 files changed, 321 insertions(+), 64 deletions(-) create mode 100644 nuttx/arch/arm/src/nuc1xx/nuc_irq.h (limited to 'nuttx/arch') diff --git a/nuttx/arch/arm/src/nuc1xx/chip/nuc_uart.h b/nuttx/arch/arm/src/nuc1xx/chip/nuc_uart.h index 455821264..18b0122b1 100644 --- a/nuttx/arch/arm/src/nuc1xx/chip/nuc_uart.h +++ b/nuttx/arch/arm/src/nuc1xx/chip/nuc_uart.h @@ -129,28 +129,29 @@ #define UART_IER_MODEM_IEN (1 << 3) /* Bit 3: Modem status interrupt enable (UART0/1) */ #define UART_IER_RTO_IEN (1 << 4) /* Bit 4: RX timeout interrupt enable */ #define UART_IER_BUF_ERR_IEN (1 << 5) /* Bit 5: Buffer error interrupt enable */ -#define UART_IER_WAKE_EN (1 << 6) /* Bit 6: UART wake-up function enabled (UART0/1) */ +#define UART_IER_WAKE_EN (1 << 6) /* Bit 6: UART wake-up function enable (UART0/1) */ #define UART_IER_TIME_OUT_EN (1 << 11) /* Bit 11: Time out counter enable */ #define UART_IER_AUTO_RTS_EN (1 << 12) /* Bit 12: RTS auto flow control enable (UART0/1) */ #define UART_IER_AUTO_CTS_EN (1 << 13) /* Bit 13: CTS auto flow control enable (UART0/1) */ #define UART_IER_DMA_TX_EN (1 << 14) /* Bit 14: TX DMA enable (UART0/1) */ #define UART_IER_DMA_RX_EN (1 << 15) /* Bit 15: RX DMA enable (UART0/1) */ -#define UART_IER_ALLIE (0x0000f87f) +#define UART_IER_ALLIE (0x0000003f) +#define UART_IER_ALLBITS (0x0000f87f) /* UART FIFO control register */ #define UART_FCR_RFR (1 << 1) /* Bit 1: RX FIFO software reset */ #define UART_FCR_TFR (1 << 2) /* Bit 2: TX FIFO software reset */ -#define UART_FCR_FRITL_SHIFT (4) /* Bits 4-7: RX FIFO interrupt trigger level */ -#define UART_FCR_FRITL_MASK (15 << UART_FCR_FRITL_SHIFT) -# define UART_FCR_FRITL_1 (0 << UART_FCR_FRITL_SHIFT) -# define UART_FCR_FRITL_4 (1 << UART_FCR_FRITL_SHIFT) -# define UART_FCR_FRITL_8 (2 << UART_FCR_FRITL_SHIFT) -# define UART_FCR_FRITL_14 (3 << UART_FCR_FRITL_SHIFT) -# define UART_FCR_FRITL_30 (4 << UART_FCR_FRITL_SHIFT) /* High speed */ -# define UART_FCR_FRITL_46 (5 << UART_FCR_FRITL_SHIFT) /* High speed */ -# define UART_FCR_FRITL_62 (6 << UART_FCR_FRITL_SHIFT) /* High speed */ +#define UART_FCR_RFITL_SHIFT (4) /* Bits 4-7: RX FIFO interrupt trigger level */ +#define UART_FCR_RFITL_MASK (15 << UART_FCR_RFITL_SHIFT) +# define UART_FCR_RFITL_1 (0 << UART_FCR_RFITL_SHIFT) +# define UART_FCR_RFITL_4 (1 << UART_FCR_RFITL_SHIFT) +# define UART_FCR_RFITL_8 (2 << UART_FCR_RFITL_SHIFT) +# define UART_FCR_RFITL_14 (3 << UART_FCR_RFITL_SHIFT) +# define UART_FCR_RFITL_30 (4 << UART_FCR_RFITL_SHIFT) /* High speed */ +# define UART_FCR_RFITL_46 (5 << UART_FCR_RFITL_SHIFT) /* High speed */ +# define UART_FCR_RFITL_62 (6 << UART_FCR_RFITL_SHIFT) /* High speed */ #define UART_FCR_RX_DIS (1 << 8) /* Bit 8: Recive disable register */ #define UART_FCR_RTS_TRI_LEV_SHIFT (16) /* Bits 16-19: RTS trigger level for auto flow control */ #define UART_FCR_RTS_TRI_LEV_MASK (15 << UART_FCR_RTS_TRI_LEV_SHIFT) diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_irq.c b/nuttx/arch/arm/src/nuc1xx/nuc_irq.c index 423e40031..fc3bd4d7e 100644 --- a/nuttx/arch/arm/src/nuc1xx/nuc_irq.c +++ b/nuttx/arch/arm/src/nuc1xx/nuc_irq.c @@ -52,6 +52,8 @@ #include "os_internal.h" #include "up_internal.h" +#include "nuc_irq.h" + /**************************************************************************** * Definitions ****************************************************************************/ @@ -178,6 +180,34 @@ static inline void nuc_prioritize_syscall(int priority) putreg32(regval, ARMV6M_SYSCON_SHPR2); } +/**************************************************************************** + * Name: nuc_clrpend + * + * Description: + * Clear a pending interrupt at the NVIC. + * + ****************************************************************************/ + +static inline void nuc_clrpend(int irq) +{ + /* This will be called on each interrupt exit whether the interrupt can be + * enambled or not. So this assertion is necessarily lame. + */ + + DEBUGASSERT((unsigned)irq < NR_IRQS); + + /* Check for an external interrupt */ + + if (irq >= NUC_IRQ_INTERRUPT && irq < NUC_IRQ_INTERRUPT + 32) + { + /* Set the appropriate bit in the ISER register to enable the + * interrupt + */ + + putreg32((1 << (irq - NUC_IRQ_INTERRUPT)), ARMV6M_NVIC_ICPR); + } +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -332,6 +362,7 @@ void up_enable_irq(int irq) void up_maskack_irq(int irq) { up_disable_irq(irq); + nuc_clrpend(irq); } /**************************************************************************** diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_irq.h b/nuttx/arch/arm/src/nuc1xx/nuc_irq.h new file mode 100644 index 000000000..f475753bb --- /dev/null +++ b/nuttx/arch/arm/src/nuc1xx/nuc_irq.h @@ -0,0 +1,65 @@ +/************************************************************************************ + * arch/arm/src/nuc1xx/nuc_irq.h + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_NUC1XX_NUC_IRQ_H +#define __ARCH_ARM_SRC_NUC1XX_NUC_IRQ_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Inline Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_NUC1XX_NUC_IRQ_H */ diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_lowputc.c b/nuttx/arch/arm/src/nuc1xx/nuc_lowputc.c index b9fdb0ef6..7e8766a73 100644 --- a/nuttx/arch/arm/src/nuc1xx/nuc_lowputc.c +++ b/nuttx/arch/arm/src/nuc1xx/nuc_lowputc.c @@ -273,8 +273,8 @@ void nuc_lowsetup(void) /* Set Rx Trigger Level */ - regval &= ~UART_FCR_FRITL_MASK; - regval |= UART_FCR_FRITL_4; + regval &= ~UART_FCR_RFITL_MASK; + regval |= UART_FCR_RFITL_4; putreg32(regval, NUC_CONSOLE_BASE + NUC_UART_FCR_OFFSET); /* Set Parity & Data bits and Stop bits */ diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_serial.c b/nuttx/arch/arm/src/nuc1xx/nuc_serial.c index fce9ea967..529f5c61b 100644 --- a/nuttx/arch/arm/src/nuc1xx/nuc_serial.c +++ b/nuttx/arch/arm/src/nuc1xx/nuc_serial.c @@ -324,18 +324,42 @@ static inline void up_serialout(struct nuc_dev_s *priv, int offset, uint32_t val } /**************************************************************************** - * Name: up_disableuartint + * Name: up_setier ****************************************************************************/ -static inline void up_disableuartint(struct nuc_dev_s *priv, uint32_t *ier) +static uint32_t up_setier(struct nuc_dev_s *priv, + uint32_t clrbits, uint32_t setbits) { - if (ier) - { - *ier = priv->ier & UART_IER_ALLIE; - } + irqstate_t flags; + uint32_t retval; + + /* Make sure that this is atomic */ - priv->ier &= ~UART_IER_ALLIE; + flags = irqsave(); + + /* Get the current IER setting */ + + retval = priv->ier; + + /* Modify and write the IER according to the inputs */ + + priv->ier &= ~clrbits; + priv->ier |= setbits; up_serialout(priv, NUC_UART_IER_OFFSET, priv->ier); + irqrestore(flags); + + /* Return the value of the IER before modification */ + + return retval; +} + +/**************************************************************************** + * Name: up_disableuartint + ****************************************************************************/ + +static inline void up_disableuartint(struct nuc_dev_s *priv, uint32_t *ier) +{ + *ier = up_setier(priv, UART_IER_ALLIE, 0); } /**************************************************************************** @@ -344,8 +368,67 @@ static inline void up_disableuartint(struct nuc_dev_s *priv, uint32_t *ier) static inline void up_restoreuartint(struct nuc_dev_s *priv, uint32_t ier) { - priv->ier |= ier & UART_IER_ALLIE; - up_serialout(priv, NUC_UART_IER_OFFSET, priv->ier); + uint32_t setbits = ier & UART_IER_ALLIE; + uint32_t clrbits = (~ier) & UART_IER_ALLIE; + (void)up_setier(priv, clrbits, setbits); +} + +/**************************************************************************** + * Name: up_rxto_disable + ****************************************************************************/ + +static void up_rxto_disable(struct nuc_dev_s *priv) +{ + uint32_t regval; + + /* This function is called at initialization time and also when a timeout + * interrupt is received when the RX FIFO is empty. + * + * Set Rx Trigger Level so that an interrupt will be generated when the + * very next byte is received. + */ + + regval = up_serialin(priv, NUC_UART_FCR_OFFSET); + regval &= ~UART_FCR_RFITL_MASK; + regval |= UART_FCR_RFITL_1; + up_serialout(priv, NUC_UART_FCR_OFFSET, regval); + + /* Disable the RX timeout interrupt and disable the timeout */ + + (void)up_setier(priv, (UART_IER_RTO_IEN | UART_IER_TIME_OUT_EN), 0); +} + +/**************************************************************************** + * Name: up_rxto_enable + ****************************************************************************/ + +static void up_rxto_enable(struct nuc_dev_s *priv) +{ + uint32_t regval; + + /* This function is called after each RX interrupt. Data has been received + * and more may or may not be received. + * + * Set the RX FIFO level so that interrupts are only received when there + * are 8 or 14 bytes in the FIFO (depending on the UART FIFO depth). + */ + + regval = up_serialin(priv, NUC_UART_FCR_OFFSET); + regval &= ~UART_FCR_RFITL_MASK; +#if defined(CONFIG_NUC_UART0) +# if defined(CONFIG_NUC_UART0) || defined(CONFIG_NUC_UART0) + regval |= priv->depth > 16 ? UART_FCR_RFITL_14 : UART_FCR_RFITL_8; +# else + regval |= UART_FCR_RFITL_14; +# endif +#else + regval |= UART_FCR_RFITL_8; +#endif + up_serialout(priv, NUC_UART_FCR_OFFSET, regval); + + /* Enable the RX timeout interrupt and enable the timeout */ + + (void)up_setier(priv, 0, (UART_IER_RTO_IEN | UART_IER_TIME_OUT_EN)); } /**************************************************************************** @@ -378,8 +461,8 @@ static int up_setup(struct uart_dev_s *dev) /* Set Rx Trigger Level */ - regval &= ~(UART_FCR_FRITL_MASK | UART_FCR_TFR | UART_FCR_RFR); - regval |= UART_FCR_FRITL_4; + regval &= ~(UART_FCR_RFITL_MASK | UART_FCR_TFR | UART_FCR_RFR); + regval |= UART_FCR_RFITL_1; up_serialout(priv, NUC_UART_FCR_OFFSET, regval); /* Set Parity & Data bits and Stop bits */ @@ -427,9 +510,9 @@ static int up_setup(struct uart_dev_s *dev) up_serialout(priv, NUC_UART_LCR_OFFSET, regval); - /* Set Time-Out values */ + /* Configure the RX timeout, but do not enable the interrupt yet */ - regval = UART_TOR_TOIC(40) | UART_TOR_DLY(0); + regval = UART_TOR_TOIC(60) | UART_TOR_DLY(0); up_serialout(priv, NUC_UART_TOR_OFFSET, regval); /* Set the baud */ @@ -529,8 +612,11 @@ static int up_interrupt(int irq, void *context) { struct uart_dev_s *dev = NULL; struct nuc_dev_s *priv; - uint32_t status; + uint32_t isr; + uint32_t regval; int passes; + bool rxto; + bool rxfe; #ifdef CONFIG_NUC_UART0 if (g_uart0priv.irq == irq) @@ -564,52 +650,94 @@ static int up_interrupt(int irq, void *context) for (passes = 0; passes < 256; passes++) { - /* Get the current UART interrupt status */ + /* Get the current UART interrupt status register (ISR) contents */ + + isr = up_serialin(priv, NUC_UART_ISR_OFFSET); + + /* Check if the RX FIFO is empty. Check if an RX timeout occur. These affect + * some later decisions. + */ - status = up_serialin(priv, NUC_UART_ISR_OFFSET); + rxfe = ((up_serialin(priv, NUC_UART_FSR_OFFSET) & UART_FSR_RX_EMPTY) != 0); + rxto = ((isr & UART_ISR_TOUT_INT) != 0); - /* Check if the RX FIFO is filled to the threshold value (OR if the RX - * timeout occurred without the FIFO being filled) + /* Check if the RX FIFO is filled to the threshold value OR if the RX + * timeout occurred with the FIFO non-empty. Both are cleared + * by reading from the RBR register. */ - if ((status & UART_ISR_RDA_INT) != 0 || (status & UART_ISR_TOUT_INT) != 0) + if ((isr & UART_ISR_RDA_INT) != 0 || (rxto && !rxfe)) { uart_recvchars(dev); } - /* Check if the transmit holding register is empty */ + /* Enable or disable RX timeouts based on the state of RX FIFO: + * + * DISABLE: If the timeout occurred and the RX FIFO was empty. + * ENABLE: Data was in RX FIFO (may have been removed), RX interrupts + * are enabled, and the timeout is not already enabled. + */ - if ((status & UART_ISR_THRE_INT) != 0) + if (rxto && rxfe) { - uart_xmitchars(dev); - } + /* A timeout interrupt occurred while the RX FIFO is empty. + * We need to read from the RBR to clear the interrupt. + */ - /* Check for modem status */ + (void)up_serialin(priv, NUC_UART_RBR_OFFSET); - if ((status & UART_ISR_MODEM_INT) != 0) - { - /* REVISIT: Do we clear this be reading the modem status register? */ + /* Disable, further RX timeout interrupts and set the RX FIFO + * threshold so that an interrupt will be generated when the + * very next byte is recieved. + */ - (void)up_serialin(priv, NUC_UART_MSR_OFFSET); + up_rxto_disable(priv); } - - /* Check for line status */ - if ((status & UART_ISR_RLS_INT) != 0) + /* Is the timeout enabled? Are RX interrupts enabled? Was there + * data in the RX FIFO when we entered the interrupt handler? + */ + + else if ((priv->ier & (UART_IER_RTO_IEN|UART_IER_RDA_IEN)) == UART_IER_RDA_IEN && !rxfe) { - /* REVISIT: Do we clear this be reading the FIFO status register? */ + /* We are receiving data and the RX timeout is not enabled. + * Set the RX FIFO threshold so that RX interrupts will only be + * generated after several bytes have been recevied and enable + * the RX timout. + */ + + up_rxto_enable(priv); + } - (void)up_serialin(priv, NUC_UART_FSR_OFFSET); + /* Check if the transmit holding register is empty. Cleared by writing + * to the THR register. + */ + + if ((isr & UART_ISR_THRE_INT) != 0) + { + uart_xmitchars(dev); } - /* Check for buffer errors */ + /* Check for modem status. */ - if ((status & UART_ISR_BUF_ERR_INT) != 0) + if ((isr & UART_ISR_MODEM_INT) != 0) { - /* REVISIT: Do we clear this by reading the FIFO status register? */ + /* Cleared by setting the DCTSF bit in the modem control register (MCR) */ - (void)up_serialin(priv, NUC_UART_FSR_OFFSET); + regval = up_serialin(priv, NUC_UART_MCR_OFFSET); + up_serialout(priv, NUC_UART_MCR_OFFSET, regval | UART_MSR_DCTSF); } + + /* Check for line status or buffer errors*/ + + if ((isr & UART_ISR_RLS_INT) != 0 || + (isr & UART_ISR_BUF_ERR_INT) != 0) + { + /* Both errors are cleared by reseting the RX FIFO */ + + regval = up_serialin(priv, NUC_UART_FCR_OFFSET); + up_serialout(priv, NUC_UART_FCR_OFFSET, regval | UART_FCR_RFR); + } } return OK; @@ -740,19 +868,51 @@ static int up_receive(struct uart_dev_s *dev, uint32_t *status) static void up_rxint(struct uart_dev_s *dev, bool enable) { struct nuc_dev_s *priv = (struct nuc_dev_s*)dev->priv; + if (enable) { #ifndef CONFIG_SUPPRESS_SERIAL_INTS - priv->ier |= (UART_IER_RDA_IEN | UART_IER_RLS_IEN | UART_IER_RTO_IEN | - UART_IER_BUF_ERR_IEN | UART_IER_TIME_OUT_EN); + /* Enable receive data, line status and buffer error interrupts */ + + irqstate_t flags = irqsave(); + (void)up_setier(priv, 0, + (UART_IER_RDA_IEN | UART_IER_RLS_IEN | + UART_IER_BUF_ERR_IEN)); + + /* Enable or disable timeouts based on the state of RX FIFO */ + + if ((up_serialin(priv, NUC_UART_FSR_OFFSET) & UART_FSR_RX_EMPTY) != 0) + { + /* The FIFO is empty. Disable RX timeout interrupts and set the + * RX FIFO threshold so that an interrupt will be generated when + * the very next byte is recieved. + */ + + up_rxto_disable(priv); + } + else + { + /* Otherwise, set the RX FIFO threshold so that RX interrupts will + * only be generated after several bytes have been recevied and + * enable* the RX timout. + */ + + up_rxto_enable(priv); + } + + irqrestore(flags); #endif } else { - priv->ier &= ~(UART_IER_RDA_IEN | UART_IER_RLS_IEN | UART_IER_RTO_IEN); - } + /* Enable receive data, line status, buffer error, and RX timeout + * interrupts. Also disables the RX timer. + */ - up_serialout(priv, NUC_UART_IER_OFFSET, priv->ier); + (void)up_setier(priv, 0, + (UART_IER_RDA_IEN | UART_IER_RLS_IEN | UART_IER_RTO_IEN | + UART_IER_BUF_ERR_IEN | UART_IER_TIME_OUT_EN)); + } } /**************************************************************************** @@ -766,7 +926,7 @@ static void up_rxint(struct uart_dev_s *dev, bool enable) static bool up_rxavailable(struct uart_dev_s *dev) { struct nuc_dev_s *priv = (struct nuc_dev_s*)dev->priv; - return ((up_serialin(priv, NUC_UART_FSR_OFFSET) & UART_FSR_RX_EMPTY) != 0); + return ((up_serialin(priv, NUC_UART_FSR_OFFSET) & UART_FSR_RX_EMPTY) == 0); } /**************************************************************************** @@ -794,29 +954,29 @@ static void up_send(struct uart_dev_s *dev, int ch) static void up_txint(struct uart_dev_s *dev, bool enable) { struct nuc_dev_s *priv = (struct nuc_dev_s*)dev->priv; - irqstate_t flags; - flags = irqsave(); if (enable) { #ifndef CONFIG_SUPPRESS_SERIAL_INTS - priv->ier |= (UART_IER_THRE_IEN | UART_IER_BUF_ERR_IEN); - up_serialout(priv, NUC_UART_IER_OFFSET, priv->ier); + /* Enable the THR empty interrupt */ + + irqstate_t flags = irqsave(); + (void)up_setier(priv, 0, UART_IER_THRE_IEN); /* Fake a TX interrupt here by just calling uart_xmitchars() with * interrupts disabled (note this may recurse). */ uart_xmitchars(dev); + irqrestore(flags); #endif } else { - priv->ier &= ~UART_IER_THRE_IEN; - up_serialout(priv, NUC_UART_IER_OFFSET, priv->ier); - } + /* Disable the THR empty interrupt */ - irqrestore(flags); + (void)up_setier(priv, UART_IER_THRE_IEN, 0); + } } /**************************************************************************** -- cgit v1.2.3