From 05ed0f8871551de1217756d66bbfb7b820bbcf6a Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 28 Dec 2009 16:03:26 +0000 Subject: [PATCH] 1st cut at serial driver git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2445 42af7a65-404d-4744-a932-0658087f49c3 --- arch/arm/src/lpc313x/lpc313x_serial.c | 870 ++++++++++++++++++++++++++ arch/arm/src/lpc313x/lpc313x_uart.h | 29 +- 2 files changed, 885 insertions(+), 14 deletions(-) create mode 100755 arch/arm/src/lpc313x/lpc313x_serial.c diff --git a/arch/arm/src/lpc313x/lpc313x_serial.c b/arch/arm/src/lpc313x/lpc313x_serial.c new file mode 100755 index 0000000000..3a3b539cbf --- /dev/null +++ b/arch/arm/src/lpc313x/lpc313x_serial.c @@ -0,0 +1,870 @@ +/**************************************************************************** + * arch/arm/src/lpc313x/lpc313x_serial.c + * + * Copyright (C) 2009 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include "up_arch.h" +#include "os_internal.h" +#include "up_internal.h" + +#include "lpc313x_cgudriver.h" +#include "lpc313x_uart.h" + +#ifdef CONFIG_USE_SERIALDRIVER + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct up_dev_s +{ + uint8_t ier; /* Saved IER value */ +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static int up_setup(struct uart_dev_s *dev); +static void up_shutdown(struct uart_dev_s *dev); +static int up_attach(struct uart_dev_s *dev); +static void up_detach(struct uart_dev_s *dev); +static int up_interrupt(int irq, void *context); +static int up_ioctl(struct file *filep, int cmd, unsigned long arg); +static int up_receive(struct uart_dev_s *dev, uint32_t *status); +static void up_rxint(struct uart_dev_s *dev, bool enable); +static bool up_rxavailable(struct uart_dev_s *dev); +static void up_send(struct uart_dev_s *dev, int ch); +static void up_txint(struct uart_dev_s *dev, bool enable); +static bool up_txready(struct uart_dev_s *dev); +static bool up_txempty(struct uart_dev_s *dev); + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +struct uart_ops_s g_uart_ops = +{ + .setup = up_setup, + .shutdown = up_shutdown, + .attach = up_attach, + .detach = up_detach, + .ioctl = up_ioctl, + .receive = up_receive, + .rxint = up_rxint, + .rxavailable = up_rxavailable, + .send = up_send, + .txint = up_txint, + .txready = up_txready, + .txempty = up_txempty, +}; + +/* I/O buffers */ + +static char g_rxbuffer[CONFIG_UART_RXBUFSIZE]; +static char g_txbuffer[CONFIG_UART_TXBUFSIZE]; + +/* This describes the state of the single LPC313X uart port. */ + +static struct up_dev_s g_uartpriv; +static uart_dev_t g_uartport = +{ + .recv = + { + .size = CONFIG_UART_RXBUFSIZE, + .buffer = g_rxbuffer, + }, + .xmit = + { + .size = CONFIG_UART_TXBUFSIZE, + .buffer = g_txbuffer, + }, + .ops = &g_uart_ops, + .priv = &g_uartpriv, +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_disableuartint + ****************************************************************************/ + +static inline void up_disableuartint(struct up_dev_s *priv, uint8_t *ier) +{ + if (ier) + { + *ier = priv->ier & UART_IER_ALLINTS; + } + + priv->ier &= ~UART_IER_ALLINTS; + putreg32((uint32_t)priv->ier, LPC313X_UART_IER); +} + +/**************************************************************************** + * Name: up_restoreuartint + ****************************************************************************/ + +static inline void up_restoreuartint(struct up_dev_s *priv, uint8_t ier) +{ + priv->ier |= ier & UART_IER_ALLINTS; + putreg32((uint32_t)priv->ier, LPC313X_UART_IER); +} + +/**************************************************************************** + * Name: up_waittxready + ****************************************************************************/ + +static inline void up_waittxready(struct up_dev_s *priv) +{ + int tmp; + + /* Limit how long we will wait for the TX available condition */ + + for (tmp = 1000 ; tmp > 0 ; tmp--) + { + /* Check if the tranmitter holding register (THR) is empty */ + + if ((getreg32(LPC313X_UART_LSR) & UART_LSR_THRE) != 0) + { + /* The THR is empty, return */ + + break; + } + } +} + +/**************************************************************************** + * Name: up_enablebreaks + ****************************************************************************/ + +static inline void up_enablebreaks(struct up_dev_s *priv, bool enable) +{ + uint32_t_t lcr = getreg32(LPC313X_UART_LCR); + if (enable) + { + lcr |= UART_LCR_BRKCTRL; + } + else + { + lcr &= ~UART_LCR_BRKCTRL; + } + putreg32(lcr, LPC313X_UART_LCR); +} + +/**************************************************************************** + * Name: up_configbaud + ****************************************************************************/ + +static inline void up_configbaud(void) +{ + /* In a buckled-up, embedded system, there is no reason to constantly + * calculate the following. The calculation can be skipped if the + * MULVAL, DIVADDVAL, and DIVISOR values are provided in the configuration + * file. + */ + +#ifndef CONFIG_LPC313X_UART_MULVAL + uint32_t qtrclk; + uint32_t regval; + + /* Test values calculated for every multiplier/divisor combination */ + + uint32_t tdiv; + uint32_t terr; + int tmulval; + int tdivaddval; + + /* Optimal multiplier/divider values */ + + uint32_t div = 0; + uint32_t err = 100000; + int mulval = 1; + int divaddval = 0; + + /* Baud is generated using FDR and DLL-DLM registers + * + * baud = clock * (mulval/(mulval+divaddval) / (16 * div) + * + * Or + * + * div = (clock/16) * (mulval/(mulval+divaddval) / baud + * + * Where mulval = Fractional divider multiplier + * divaddval = Fractional divider pre-scale div + * div = DLL-DLM divisor + */ + + /* Get UART block clock divided by 16 */ + + qtrclk = lpc313x_clkfreq(CLKID_UARTUCLK, DOMAINID_UART) >> 4; + + /* Try every valid multiplier, tmulval (or until a perfect + * match is found). + */ + + for (tmulval = 1 ; tmulval <= 15 && err > 0; tmulval++) + { + /* Try every valid pre-scale div, tdivaddval (or until a perfect + * match is found). + */ + + for (tdivaddval = 0 ; tdivaddval <= 15 && err > 0; tdivaddval++) + { + /* Calculate the divisor with these fractional divider settings */ + + uint32_t tmp = (tmulval * qtrclk) / ((tmulval + tdivaddval)); + tdiv = (tmp + (CONFIG_UART_BAUD>>1)) / CONFIG_UART_BAUD; + + /* Check if this candidate divisor is within a valid range */ + + if (tdiv > 2 && tdiv < 0x10000) + { + /* Calculate the actual baud and the error */ + + uint32_t actualbaud = tmp / tdiv; + + if (actualbaud <= CONFIG_UART_BAUD) + { + terr = CONFIG_UART_BAUD - actualbaud; + } + else + { + terr = actualbaud - CONFIG_UART_BAUD; + } + + /* Is this the smallest error we have encountered? */ + + if (terr < err) + { + /* Yes, save these settings as the new, candidate optimal settings */ + + mulval = tmulval ; + divaddval = tdivaddval; + div = tdiv; + err = terr; + } + } + } + } + + /* Set the Divisor Latch Access Bit (DLAB) to enable DLL/DLM access */ + + regval = getreg32(LPV313X_UART_LCR); + regval |= UART_LCR_DLAB + putreg32(regval, LPV313X_UART_LCR); + + /* Configure the MS and LS DLAB registers */ + + putreg32(div & UART_DLL_MASK, LPC313X_UART_DLL); + putreg32((div >> 8) & UART_DLL_MASK, LPC313X_UART_DLM);\ + + regval &~= UART_LCR_DLAB + putreg32(regval, LPV313X_UART_LCR); + + /* Configure the Fractional Divider Register (FDR) */ + + putreg32((mulval << UART_FDR_MULVAL_SHIFT) | + (divaddval << UART_FDR_DIVADDVAL_SHIFT), + LPC313X_UART_FRD); +#else + /* Set the Divisor Latch Access Bit (DLAB) to enable DLL/DLM access */ + + regval = getreg32(LPV313X_UART_LCR); + regval |= UART_LCR_DLAB + putreg32(regval, LPV313X_UART_LCR); + + /* Configure the MS and LS DLAB registers */ + + putreg32(CONFIG_LPC313X_UART_DIVISOR & UART_DLL_MASK, LPC313X_UART_DLL); + putreg32((CONFIG_LPC313X_UART_DIVISOR >> 8) & UART_DLL_MASK, LPC313X_UART_DLM);\ + + regval &~= UART_LCR_DLAB + putreg32(regval, LPV313X_UART_LCR); + + /* Configure the Fractional Divider Register (FDR) */ + + putreg32((CONFIG_LPC313X_UART_MULVAL << UART_FDR_MULVAL_SHIFT) | + (CONFIG_LPC313X_UART_DIVADDVAL << UART_FDR_DIVADDVAL_SHIFT), + LPC313X_UART_FRD); +#endif +} + +/**************************************************************************** + * Name: up_setup + * + * Description: + * Configure the UART baud, bits, parity, fifos, etc. This method is called + * the first time that the serial port is opened. + * + ****************************************************************************/ + +static int up_setup(struct uart_dev_s *dev) +{ +#ifndef CONFIG_SUPPRESS_LPC313X_UART_CONFIG + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + uint32_t regval; + + /* Clear fifos */ + + putreg32((UART_FCR_RXFIFORST|UART_FCR_TXFIFORST), LPC313X_UART_FCR); + + /* Set trigger */ + + putreg32((UART_FCR_FIFOENABLE|UART_FCR_RXTRIGLEVEL_16), LPC313X_UART_FCR); + + /* Set up the IER */ + + priv->ier = getreg32(LPC313X_UART_IER); + + /* Set up the LCR */ + + regval = 0; + +#if CONFIG_UART_BITS == 5 + regval |= UART_LCR_WDLENSEL_5BITS; +#elif CONFIG_UART_BITS == 6 + regval |= UART_LCR_WDLENSEL_6BITS; +#elif CONFIG_UART_BITS == 7 + regval |= UART_LCR_WDLENSEL_7BITS; +#else + regval |= UART_LCR_WDLENSEL_8BITS; +#endif + +#if CONFIG_UART_2STOP > 0 + regval |= UART_LCR_NSTOPBITS; +#endif + +#if CONFIG_UART_PARITY == 1 + regval |= UART_LCR_PAREN; +#elif CONFIG_UART_PARITY == 2) + regval |= (UART_LCR_PAREVEN|UART_LCR_PAREN); +#endif + putreg32(regval, LPV313X_UART_LCR); + + /* Set the BAUD divisor */ + + up_configbaud(); + + /* Configure the FIFOs */ + + putreg32((UART_FCR_RXTRIGLEVEL_16|UART_FCR_TXFIFORST|\ + UART_FCR_RXFIFORST|UART_FCR_FIFOENABLE), + LPC313X_UART_FCR); + + /* The NuttX serial driver waits for the first THRE interrrupt before + * sending serial data... However, it appears that the lpc313x hardware + * does not generate that interrupt until a transition from not-empty + * to empty. So, the current kludge here is to send one NULL at + * startup to kick things off. + */ + + putreg32('\0', LPC313X_UART_THR); +#endif + return OK; +} + +/**************************************************************************** + * Name: up_shutdown + * + * Description: + * Disable the UART. This method is called when the serial port is closed + * + ****************************************************************************/ + +static void up_shutdown(struct uart_dev_s *dev) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + up_disableuartint(priv, NULL); +} + +/**************************************************************************** + * Name: up_attach + * + * Description: + * Configure the UART to operation in interrupt driven mode. This method + * is called when the serial port is opened. Normally, this is just after + * he the setup() method is called, however, the serial console may operate in + * in a non-interrupt driven mode during the boot phase. + * + * RX and TX interrupts are not enabled when by the attach method (unless + * the hardware supports multiple levels of interrupt enabling). The RX and TX + * and TX interrupts are not enabled until the txint() and rxint() methods + * are called. + * + ****************************************************************************/ + +static int up_attach(struct uart_dev_s *dev) +{ + int ret; + + /* Attach and enable the IRQ */ + + ret = irq_attach(LPC313X_IRQ_UART, up_interrupt); + if (ret == OK) + { + /* Enable the interrupt (RX and TX interrupts are still disabled + * in the UART + */ + + up_enable_irq(LPC313X_IRQ_UART); + } + return ret; +} + +/**************************************************************************** + * Name: up_detach + * + * Description: + * Detach UART interrupts. This method is called when the serial port is + * closed normally just before the shutdown method is called. The + * exception is the serial console which is never shutdown. + * + ****************************************************************************/ + +static void up_detach(struct uart_dev_s *dev) +{ + up_disable_irq(LPC313X_IRQ_UART); + irq_detach(LPC313X_IRQ_UART); +} + +/**************************************************************************** + * Name: up_interrupt + * + * Description: + * This is the UART interrupt handler. It will be invoked when an + * interrupt received on the UART irq. It should call uart_transmitchars + * or uart_receivechar to perform the appropriate data transfers. + * + ****************************************************************************/ + +static int up_interrupt(int irq, void *context) +{ + struct uart_dev_s *dev = &g_uartport; + struct up_dev_s *priv = &g_uartpriv; + uint8_t status; + int passes; + + /* Loop until there are no characters to be transferred or, + * until we have been looping for a long time. + */ + + for (passes = 0; passes < 256; passes++) + { + /* Get the current UART status and check for loop + * termination conditions + */ + + status = getreg32(LPC313X_UART_IIR); + + /* The NO INTERRUPT should be zero if there are pending + * interrupts + */ + + if ((status & UART_IIR_NOINT) != 0) + { + /* Break out of the loop when there is no longer a pending + * interrupt + */ + + break; + } + + /* Handle the interrupt by its interrupt ID field */ + + switch (status & UART_IIR_INTID_MASK) + { + /* Handle incoming, receive bytes (with or without timeout) */ + + case UART_IIR_INTID_RDA: /* Received Data Available */ + case UART_IIR_INTID_TIMEOUT: /* Character time-out */ + { + uart_recvchars(dev); + break; + } + + /* Handle outgoing, transmit bytes */ + + case UART_IIR_INTID_THRE: /* Transmitter Holding Register empty */ + { + uart_xmitchars(dev); + break; + } + + /* Just clear modem status interrupts */ + + case UART_IIR_INTID_MS: /* Modem status */ + { + /* Read the modem status register (MSR) to clear */ + + status = getreg32(LPC313X_UART_MSR); + fvdbg("MSR: %02x\n", status); + break; + } + + /* Just clear any line status interrupts */ + + case UART_IIR_INTID_RLS: /* Receiver Line Status */ + { + /* Read the line status register (LSR) to clear */ + + status = getreg32(LPC313X_UART_LSR); + fvdbg("LSR: %02x\n", status); + break; + } + + /* There should be no other values */ + + default: + { + dbg("Unexpected IIR: %02x\n", status); + break; + } + } + } + return OK; +} + +/**************************************************************************** + * Name: up_ioctl + * + * Description: + * All ioctl calls will be routed through this method + * + ****************************************************************************/ + +static int up_ioctl(struct file *filep, int cmd, unsigned long arg) +{ + struct inode *inode = filep->f_inode; + struct uart_dev_s *dev = inode->i_private; + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + int ret = OK; + + switch (cmd) + { + case TIOCSERGSTRUCT: + { + struct up_dev_s *user = (struct up_dev_s*)arg; + if (!user) + { + ret = -EINVAL; + } + else + { + memcpy(user, dev, sizeof(struct up_dev_s)); + } + } + break; + + case TIOCSBRK: /* BSD compatibility: Turn break on, unconditionally */ + { + irqstate_t flags = irqsave(); + up_enablebreaks(priv, true); + irqrestore(flags); + } + break; + + case TIOCCBRK: /* BSD compatibility: Turn break off, unconditionally */ + { + irqstate_t flags; + flags = irqsave(); + up_enablebreaks(priv, false); + irqrestore(flags); + } + break; + + default: + errno = ENOTTY; + ret = ERROR; + break; + } + + return ret; +} + +/**************************************************************************** + * Name: up_receive + * + * Description: + * Called (usually) from the interrupt level to receive one character from + * the UART. Error bits associated with the receipt are provided in the + * return 'status'. + * + ****************************************************************************/ + +static int up_receive(struct uart_dev_s *dev, uint32_t *status) +{ + uint32_t rbr; + + *status = getreg32(LPC313X_UART_LSR); + rbr = getreg32(LPC313X_UART_RBR); + return rbr & 0xff; +} + +/**************************************************************************** + * Name: up_rxint + * + * Description: + * Call to enable or disable RX interrupts + * + ****************************************************************************/ + +static void up_rxint(struct uart_dev_s *dev, bool enable) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + if (enable) + { +#ifndef CONFIG_SUPPRESS_SERIAL_INTS + priv->ier |= UART_IER_RDAINTEN; +#endif + } + else + { + priv->ier &= ~UART_IER_RDAINTEN; + } + putreg32(priv->ier, LPC313X_UART_IER); +} + +/**************************************************************************** + * Name: up_rxavailable + * + * Description: + * Return true if the receive fifo is not empty + * + ****************************************************************************/ + +static bool up_rxavailable(struct uart_dev_s *dev) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + return ((getreg32(LPC313X_UART_LSR) & UART_LSR_RDR) != 0); +} + +/**************************************************************************** + * Name: up_send + * + * Description: + * This method will send one byte on the UART + * + ****************************************************************************/ + +static void up_send(struct uart_dev_s *dev, int ch) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + putreg32((uint32_t)ch, LPC313X_UART_THR); +} + +/**************************************************************************** + * Name: up_txint + * + * Description: + * Call to enable or disable TX interrupts + * + ****************************************************************************/ + +static void up_txint(struct uart_dev_s *dev, bool enable) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + if (enable) + { +#ifndef CONFIG_SUPPRESS_SERIAL_INTS + priv->ier |= UART_IER_THREINTEN; +#endif + } + else + { + priv->ier &= ~UART_IER_THREINTEN; + } + putreg32(priv->ier, LPC313X_UART_IER); +} + +/**************************************************************************** + * Name: up_txready + * + * Description: + * Return true if the tranmsit fifo is not full + * + ****************************************************************************/ + +static bool up_txready(struct uart_dev_s *dev) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + return ((getreg32(LPC313X_UART_LSR) & UART_LSR_THRE) != 0); +} + +/**************************************************************************** + * Name: up_txempty + * + * Description: + * Return true if the transmit fifo is empty + * + ****************************************************************************/ + +static bool up_txempty(struct uart_dev_s *dev) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + return ((getreg32(LPC313X_UART_LSR) & UART_LSR_TEMT) != 0); +} + +/**************************************************************************** + * Public Funtions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_earlyserialinit + * + * Description: + * Performs the low level UART initialization early in debug so that the + * serial console will be available during bootup (via up_putc). This must + * be called before up_serialinit. + * + ****************************************************************************/ + +void up_earlyserialinit(void) +{ + /* Enable UART system clock */ + + lpc313x_enableclock(CLKID_UARTAPBCLK); + lpc313x_enableclock(CLKID_UARTUCLK); + + /* Disable UART interrupts */ + + up_disableuartint(g_uartport.priv, NULL); + + /* Configuration the serial console */ + +#if defined(CONFIG_UART_SERIAL_CONSOLE) + g_uartport.isconsole = true; + up_setup(&g_uartport); +#endif +} + +/**************************************************************************** + * Name: up_serialinit + * + * Description: + * Register serial console and serial ports. This assumes that + * up_earlyserialinit was called previously. + * + ****************************************************************************/ + +void up_serialinit(void) +{ +#if defined(CONFIG_UART_SERIAL_CONSOLE) + (void)uart_register("/dev/console", &g_uartport); +#endif + (void)uart_register("/dev/ttyS0", &g_uartport); +} + +/**************************************************************************** + * Name: up_putc + * + * Description: + * Provide priority, low-level access to support OS debug writes + * + ****************************************************************************/ + +int up_putc(int ch) +{ + struct up_dev_s *priv = g_uartpriv; + uint8_t ier; + + up_disableuartint(priv, &ier); + up_waittxready(priv); + putreg32((uint32_t)ch, LPC313X_UART_THR); + + /* Check for LF */ + + if (ch == '\n') + { + /* Add CR */ + + up_waittxready(priv); + putreg32('\r', LPC313X_UART_THR); + } + + up_waittxready(priv); + up_restoreuartint(priv, ier); + return ch; +} + +#else /* CONFIG_USE_SERIALDRIVER */ + +/**************************************************************************** + * Name: up_putc + * + * Description: + * Provide priority, low-level access to support OS debug writes + * + ****************************************************************************/ + +int up_putc(int ch) +{ + /* Check for LF */ + + if (ch == '\n') + { + /* Add CR */ + + up_lowputc('\r'); + } + + up_lowputc(ch); + return ch; +} + +#endif /* CONFIG_USE_SERIALDRIVER */ diff --git a/arch/arm/src/lpc313x/lpc313x_uart.h b/arch/arm/src/lpc313x/lpc313x_uart.h index 73c982f1bd..f0c7aee2ad 100755 --- a/arch/arm/src/lpc313x/lpc313x_uart.h +++ b/arch/arm/src/lpc313x/lpc313x_uart.h @@ -134,6 +134,7 @@ #define UART_IER_RLSINTEN (1 << 2) /* Bit 2: Receiver Line Status interrupt enable */ #define UART_IER_THREINTEN (1 << 1) /* Bit 1: Transmitter Holding Register Empty interrupt enable */ #define UART_IER_RDAINTEN (1 << 0) /* Bit 0: Receive Data Available interrupt enable */ +#define UART_IER_ALLINTS (0x1f) /* Interrupt Identification Register IIR, address 0x15001008 */ @@ -141,21 +142,21 @@ #define UART_IIR_FIFOEN_MASK (3 << UART_IIR_FIFOEN_SHIFT) #define UART_IIR_INTID_SHIFT (1) /* Bits 1-3: Interrupt identification */ #define UART_IIR_INTID_MASK (7 << UART_IIR_INTID_SHIFT) -# define UART_IIR_INTID_MODEMSTATUS (0 << UART_IIR_INTID_SHIFT) /* Modem status */ -# define UART_IIR_INTID_THREMPTY (1 << UART_IIR_INTID_SHIFT) /* Transmitter Holding Register empty */ -# define UART_IIR_INTID_REVCDATA (2 << UART_IIR_INTID_SHIFT) /* Received Data Available */ -# define UART_IIR_INTID_LINESTATUS (3 << UART_IIR_INTID_SHIFT) /* Receiver Line Status */ +# define UART_IIR_INTID_MS (0 << UART_IIR_INTID_SHIFT) /* Modem status */ +# define UART_IIR_INTID_THRE (1 << UART_IIR_INTID_SHIFT) /* Transmitter Holding Register empty */ +# define UART_IIR_INTID_RDA (2 << UART_IIR_INTID_SHIFT) /* Received Data Available */ +# define UART_IIR_INTID_RLS (3 << UART_IIR_INTID_SHIFT) /* Receiver Line Status */ # define UART_IIR_INTID_TIMEOUT (6 << UART_IIR_INTID_SHIFT) /* Character time-out */ -#define UART_IIR_INTSTATUS (1 << 0) /* Bit 0: 0 Interrupt status */ +#define UART_IIR_NOINT (1 << 0) /* Bit 0: Interrupt status, 1=no interrupt */ /* FIFO Control Register FCR, address 0x15001008 */ #define UART_FCR_RXTRIGLEVEL_SHIFT (6) /* Bits 6-7: 7:6 Receiver trigger level selection */ #define UART_FCR_RXTRIGLEVEL_MASK (3 << UART_FCR_RXTRIGLEVEL_SHIFT) -#define UART_FCR_RXTRIGLEVEL (0 << UART_FCR_RXTRIGLEVEL_SHIFT) /* Rx trigger at character 1 */ -#define UART_FCR_RXTRIGLEVEL (1 << UART_FCR_RXTRIGLEVEL_SHIFT) /* Rx trigger at character 16 */ -#define UART_FCR_RXTRIGLEVEL (2 << UART_FCR_RXTRIGLEVEL_SHIFT) /* Rx trigger at character 32 */ -#define UART_FCR_RXTRIGLEVEL (3 << UART_FCR_RXTRIGLEVEL_SHIFT) /* Rx trigger at character 56 */ +# define UART_FCR_RXTRIGLEVEL_1 (0 << UART_FCR_RXTRIGLEVEL_SHIFT) /* Rx trigger at character 1 */ +# define UART_FCR_RXTRIGLEVEL_16 (1 << UART_FCR_RXTRIGLEVEL_SHIFT) /* Rx trigger at character 16 */ +# define UART_FCR_RXTRIGLEVEL_32 (2 << UART_FCR_RXTRIGLEVEL_SHIFT) /* Rx trigger at character 32 */ +# define UART_FCR_RXTRIGLEVEL_56 (3 << UART_FCR_RXTRIGLEVEL_SHIFT) /* Rx trigger at character 56 */ #define UART_FCR_DMAMODE (1 << 3) /* Bit 3: DMA mode select */ #define UART_FCR_TXFIFORST (1 << 2) /* Bit 2: Transmitter FIFO reset */ #define UART_FCR_RXFIFORST (1 << 1) /* Bit 1: Receiver FIFO reset */ @@ -171,10 +172,10 @@ #define UART_LCR_NSTOPBITS (1 << 2) /* Bit 2: Number of stop bits selector */ #define UART_LCR_WDLENSEL_SHIFT (0) /* Bits 0-1: Word length selector */ #define UART_LCR_WDLENSEL_MASK (3 << UART_LCR_WDLENSEL_SHIFT) -#define UART_LCR_WDLENSEL_5BITS (0 << UART_LCR_WDLENSEL_SHIFT) /* Char length=5 stopbits=1 or 1.5*/ -#define UART_LCR_WDLENSEL_6BITS (1 << UART_LCR_WDLENSEL_SHIFT) /* Char length=6 stopbits=1 or 2 */ -#define UART_LCR_WDLENSEL_7BITS (2 << UART_LCR_WDLENSEL_SHIFT) /* Char length=7 stopbits=1 or 2 */ -#define UART_LCR_WDLENSEL_8BITS (3 << UART_LCR_WDLENSEL_SHIFT) /* Char length=8 stopbits=1 or 2 */ +# define UART_LCR_WDLENSEL_5BITS (0 << UART_LCR_WDLENSEL_SHIFT) /* Char length=5 stopbits=1 or 1.5*/ +# define UART_LCR_WDLENSEL_6BITS (1 << UART_LCR_WDLENSEL_SHIFT) /* Char length=6 stopbits=1 or 2 */ +# define UART_LCR_WDLENSEL_7BITS (2 << UART_LCR_WDLENSEL_SHIFT) /* Char length=7 stopbits=1 or 2 */ +# define UART_LCR_WDLENSEL_8BITS (3 << UART_LCR_WDLENSEL_SHIFT) /* Char length=8 stopbits=1 or 2 */ /* Modem Control Register MCR, address 0x15001010 */ @@ -192,7 +193,7 @@ #define UART_LSR_FE (1 << 3) /* Bit 3: Framing error */ #define UART_LSR_PE (1 << 2) /* Bit 2: Parity error */ #define UART_LSR_OE (1 << 1) /* Bit 1: Overrun error */ -#define UART_LSR_DR (1 << 0) /* Bit 0: Data ready */ +#define UART_LSR_RDR (1 << 0) /* Bit 0: Read Data ready */ /* Modem Status Register MSR, address 0x15001018 */