summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-01-26 23:46:09 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-01-26 23:46:09 +0000
commit53cb9f23346c4969c5d9cc30de45840391ce5d78 (patch)
treeadeb2273c442b722fe34e31fc48fe7779f9df0f1 /nuttx/arch
parent7e229d14b101765bf25eea8e5661ed2e47900065 (diff)
downloadpx4-nuttx-53cb9f23346c4969c5d9cc30de45840391ce5d78.tar.gz
px4-nuttx-53cb9f23346c4969c5d9cc30de45840391ce5d78.tar.bz2
px4-nuttx-53cb9f23346c4969c5d9cc30de45840391ce5d78.zip
Structure serial driver interface to support different interrupt architectures
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@571 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/arm/src/c5471/c5471_serial.c228
-rw-r--r--nuttx/arch/arm/src/dm320/dm320_serial.c240
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_serial.c102
-rw-r--r--nuttx/arch/c5471/src/up_serial.c228
-rw-r--r--nuttx/arch/dm320/src/up_serial.c220
-rwxr-xr-xnuttx/arch/z16/src/z16f/z16f_lowuart.S106
-rw-r--r--nuttx/arch/z16/src/z16f/z16f_serial.c120
7 files changed, 783 insertions, 461 deletions
diff --git a/nuttx/arch/arm/src/c5471/c5471_serial.c b/nuttx/arch/arm/src/c5471/c5471_serial.c
index ceeba8a36..22ce3c063 100644
--- a/nuttx/arch/arm/src/c5471/c5471_serial.c
+++ b/nuttx/arch/arm/src/c5471/c5471_serial.c
@@ -1,7 +1,7 @@
-/************************************************************
+/****************************************************************************
* c5471/c5471_serial.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
@@ -31,11 +31,11 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Included Files
- ************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
@@ -55,9 +55,9 @@
#include "os_internal.h"
#include "up_internal.h"
-/************************************************************
+/****************************************************************************
* Definitions
- ************************************************************/
+ ****************************************************************************/
#define BASE_BAUD 115200
@@ -65,9 +65,9 @@
# define CONFIG_UART_HWFLOWCONTROL
#endif
-/************************************************************
+/****************************************************************************
* Private Types
- ************************************************************/
+ ****************************************************************************/
struct uart_regs_s
{
@@ -82,13 +82,11 @@ struct uart_regs_s
struct up_dev_s
{
- unsigned int uartbase; /* Base address of UART
- * registers */
+ unsigned int uartbase; /* Base address of UART registers */
unsigned int baud_base; /* Base baud for conversions */
unsigned int baud; /* Configured baud */
ubyte xmit_fifo_size; /* Size of transmit FIFO */
- ubyte irq; /* IRQ associated with
- * this UART */
+ ubyte irq; /* IRQ associated with this UART */
ubyte parity; /* 0=none, 1=odd, 2=even */
ubyte bits; /* Number of bits (7 or 8) */
#ifdef CONFIG_UART_HWFLOWCONTROL
@@ -100,39 +98,42 @@ struct up_dev_s
struct uart_regs_s regs; /* Shadow copy of readonly regs */
};
-/************************************************************
+/****************************************************************************
* 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, unsigned int *status);
static void up_rxint(struct uart_dev_s *dev, boolean enable);
-static boolean up_rxfifonotempty(struct uart_dev_s *dev);
+static boolean 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, boolean enable);
-static boolean up_txfifonotfull(struct uart_dev_s *dev);
-static boolean up_txfifoempty(struct uart_dev_s *dev);
+static boolean up_txready(struct uart_dev_s *dev);
+static boolean up_txempty(struct uart_dev_s *dev);
-/************************************************************
+/****************************************************************************
* Private Variables
- ************************************************************/
+ ****************************************************************************/
struct uart_ops_s g_uart_ops =
{
.setup = up_setup,
.shutdown = up_shutdown,
- .handler = up_interrupt,
+ .attach = up_attach,
+ .detach = up_detach,
.ioctl = up_ioctl,
.receive = up_receive,
.rxint = up_rxint,
- .rxfifonotempty = up_rxfifonotempty,
+ .rxavailable = up_rxavailable,
.send = up_send,
.txint = up_txint,
- .txfifonotfull = up_txfifonotfull,
- .txfifoempty = up_txfifoempty,
+ .txready = up_txready,
+ .txempty = up_txempty,
};
/* I/O buffers */
@@ -150,6 +151,7 @@ static struct up_dev_s g_irdapriv =
.baud_base = BASE_BAUD,
.uartbase = UART_IRDA_BASE,
.baud = CONFIG_UART_IRDA_BAUD,
+ .irq = C5471_IRQ_UART_IRDA,
.parity = CONFIG_UART_IRDA_PARITY,
.bits = CONFIG_UART_IRDA_BITS,
#ifdef CONFIG_UART_IRDA_HWFLOWCONTROL
@@ -160,7 +162,6 @@ static struct up_dev_s g_irdapriv =
static uart_dev_t g_irdaport =
{
- .irq = C5471_IRQ_UART_IRDA,
.recv =
{
.size = CONFIG_UART_IRDA_RXBUFSIZE,
@@ -183,6 +184,7 @@ static struct up_dev_s g_modempriv =
.baud_base = BASE_BAUD,
.uartbase = UART_MODEM_BASE,
.baud = CONFIG_UART_MODEM_BAUD,
+ .irq = C5471_IRQ_UART,
.parity = CONFIG_UART_MODEM_PARITY,
.bits = CONFIG_UART_MODEM_BITS,
#ifdef CONFIG_UART_MODEM_HWFLOWCONTROL
@@ -193,7 +195,6 @@ static struct up_dev_s g_modempriv =
static uart_dev_t g_modemport =
{
- .irq = C5471_IRQ_UART,
.recv =
{
.size = CONFIG_UART_MODEM_RXBUFSIZE,
@@ -220,31 +221,31 @@ static uart_dev_t g_modemport =
# define TTYS1_DEV g_irdaport
#endif
-/************************************************************
+/****************************************************************************
* Private Functions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Name: up_inserial
- ************************************************************/
+ ****************************************************************************/
static inline uint32 up_inserial(struct up_dev_s *priv, uint32 offset)
{
return getreg32(priv->uartbase + offset);
}
-/************************************************************
+/****************************************************************************
* Name: up_serialout
- ************************************************************/
+ ****************************************************************************/
static inline void up_serialout(struct up_dev_s *priv, uint32 offset, uint32 value)
{
putreg32(value, priv->uartbase + offset);
}
-/************************************************************
+/****************************************************************************
* Name: up_disableuartint
- ************************************************************/
+ ****************************************************************************/
static inline void up_disableuartint(struct up_dev_s *priv, uint16 *ier)
{
@@ -256,9 +257,9 @@ static inline void up_disableuartint(struct up_dev_s *priv, uint16 *ier)
up_serialout(priv, UART_IER_OFFS, priv->regs.ier);
}
-/************************************************************
+/****************************************************************************
* Name: up_restoreuartint
- ************************************************************/
+ ****************************************************************************/
static inline void up_restoreuartint(struct up_dev_s *priv, uint16 ier)
{
@@ -266,11 +267,11 @@ static inline void up_restoreuartint(struct up_dev_s *priv, uint16 ier)
up_serialout(priv, UART_IER_OFFS, priv->regs.ier);
}
-/************************************************************
- * Name: up_waittxfifonotfull
- ************************************************************/
+/****************************************************************************
+ * Name: up_waittxready
+ ****************************************************************************/
-static inline void up_waittxfifonotfull(struct up_dev_s *priv)
+static inline void up_waittxready(struct up_dev_s *priv)
{
int tmp;
@@ -282,9 +283,9 @@ static inline void up_waittxfifonotfull(struct up_dev_s *priv)
}
}
}
-/************************************************************
+/****************************************************************************
* Name: up_disablebreaks
- ************************************************************/
+ ****************************************************************************/
static inline void up_disablebreaks(struct up_dev_s *priv)
{
@@ -292,9 +293,9 @@ static inline void up_disablebreaks(struct up_dev_s *priv)
up_serialout(priv, UART_LCR_OFFS, priv->regs.lcr);
}
-/************************************************************
+/****************************************************************************
* Name: up_enablebreaks
- ************************************************************/
+ ****************************************************************************/
static inline void up_enablebreaks(struct up_dev_s *priv)
{
@@ -302,9 +303,9 @@ static inline void up_enablebreaks(struct up_dev_s *priv)
up_serialout(priv, UART_LCR_OFFS, priv->regs.lcr);
}
-/************************************************************
+/****************************************************************************
* Name: up_setrate
- ************************************************************/
+ ****************************************************************************/
static inline void up_setrate(struct up_dev_s *priv, unsigned int rate)
{
@@ -342,7 +343,7 @@ static inline void up_setrate(struct up_dev_s *priv, unsigned int rate)
up_serialout(priv, UART_DIV_BIT_RATE_OFFS, div_bit_rate);
}
-/************************************************************
+/****************************************************************************
* Name: up_setup
*
* Description:
@@ -350,7 +351,7 @@ static inline void up_setrate(struct up_dev_s *priv, unsigned int rate)
* method is called the first time that the serial port is
* opened.
*
- ************************************************************/
+ ****************************************************************************/
static int up_setup(struct uart_dev_s *dev)
{
@@ -447,13 +448,13 @@ static int up_setup(struct uart_dev_s *dev)
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)
{
@@ -461,7 +462,58 @@ static void up_shutdown(struct uart_dev_s *dev)
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 the
+ * the setup() method is called, however, the serial console may operate 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
+ * interrupts are not enabled until the txint() and rxint() methods are called.
+ *
+ ****************************************************************************/
+
+static int up_attach(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ int ret;
+
+ /* Attach and enable the IRQ */
+
+ ret = irq_attach(priv->irq, up_interrupt);
+ if (ret == OK)
+ {
+ /* Enable the interrupt (RX and TX interrupts are still disabled
+ * in the UART
+ */
+
+ up_enable_irq(priv->irq);
+ }
+ 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)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ up_disable_irq(priv->irq);
+ irq_detach(priv->irq);
+}
+
+/****************************************************************************
* Name: up_interrupt
*
* Description:
@@ -472,7 +524,7 @@ static void up_shutdown(struct uart_dev_s *dev)
* must be able to map the 'irq' number into the approprite
* uart_dev_s structure in order to call these functions.
*
- ************************************************************/
+ ****************************************************************************/
static int up_interrupt(int irq, void *context)
{
@@ -480,11 +532,11 @@ static int up_interrupt(int irq, void *context)
struct up_dev_s *priv;
volatile uint32 cause;
- if (g_irdaport.irq == irq)
+ if (g_irdapriv.irq == irq)
{
dev = &g_irdaport;
}
- else if (g_modemport.irq == irq)
+ else if (g_modempriv.irq == irq)
{
dev = &g_modemport;
}
@@ -546,13 +598,13 @@ static int up_interrupt(int irq, void *context)
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)
{
@@ -604,7 +656,7 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
return ret;
}
-/************************************************************
+/****************************************************************************
* Name: up_receive
*
* Description:
@@ -612,7 +664,7 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
* the UART. Error bits associated with the receipt are provided in the
* the return 'status'.
*
- ************************************************************/
+ ****************************************************************************/
static int up_receive(struct uart_dev_s *dev, unsigned int *status)
{
@@ -634,13 +686,13 @@ static int up_receive(struct uart_dev_s *dev, unsigned int *status)
return rhr & 0x000000ff;
}
-/************************************************************
+/****************************************************************************
* Name: up_rxint
*
* Description:
* Call to enable or disable RX interrupts
*
- ************************************************************/
+ ****************************************************************************/
static void up_rxint(struct uart_dev_s *dev, boolean enable)
{
@@ -659,27 +711,27 @@ static void up_rxint(struct uart_dev_s *dev, boolean enable)
}
}
-/************************************************************
- * Name: up_rxfifonotempty
+/****************************************************************************
+ * Name: up_rxavailable
*
* Description:
* Return TRUE if the receive fifo is not empty
*
- ************************************************************/
+ ****************************************************************************/
-static boolean up_rxfifonotempty(struct uart_dev_s *dev)
+static boolean up_rxavailable(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
return up_inserial(priv, UART_LSR_OFFS) & UART_RX_FIFO_NOEMPTY;
}
-/************************************************************
+/****************************************************************************
* Name: up_send
*
* Description:
* This method will send one byte on the UART
*
- ************************************************************/
+ ****************************************************************************/
static void up_send(struct uart_dev_s *dev, int ch)
{
@@ -687,13 +739,13 @@ static void up_send(struct uart_dev_s *dev, int ch)
up_serialout(priv, UART_THR_OFFS, (ubyte)ch);
}
-/************************************************************
+/****************************************************************************
* Name: up_txint
*
* Description:
* Call to enable or disable TX interrupts
*
- ************************************************************/
+ ****************************************************************************/
static void up_txint(struct uart_dev_s *dev, boolean enable)
{
@@ -712,39 +764,39 @@ static void up_txint(struct uart_dev_s *dev, boolean enable)
}
}
-/************************************************************
- * Name: up_txfifonotfull
+/****************************************************************************
+ * Name: up_txready
*
* Description:
* Return TRUE if the tranmsit fifo is not full
*
- ************************************************************/
+ ****************************************************************************/
-static boolean up_txfifonotfull(struct uart_dev_s *dev)
+static boolean up_txready(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
return (up_inserial(priv, UART_SSR_OFFS) & UART_SSR_TXFULL) == 0;
}
-/************************************************************
- * Name: up_txfifoempty
+/****************************************************************************
+ * Name: up_txempty
*
* Description:
* Return TRUE if the transmit fifo is empty
*
- ************************************************************/
+ ****************************************************************************/
-static boolean up_txfifoempty(struct uart_dev_s *dev)
+static boolean up_txempty(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
return (up_inserial(priv, UART_LSR_OFFS) & UART_LSR_TREF) != 0;
}
-/************************************************************
+/****************************************************************************
* Public Funtions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Name: up_serialinit
*
* Description:
@@ -752,7 +804,7 @@ static boolean up_txfifoempty(struct uart_dev_s *dev)
* debug so that the serial console will be available
* during bootup. This must be called before up_serialinit.
*
- ************************************************************/
+ ****************************************************************************/
void up_earlyserialinit(void)
{
@@ -763,14 +815,14 @@ void up_earlyserialinit(void)
up_setup(&CONSOLE_DEV);
}
-/************************************************************
+/****************************************************************************
* Name: up_serialinit
*
* Description:
* Register serial console and serial ports. This assumes
* that up_earlyserialinit was called previously.
*
- ************************************************************/
+ ****************************************************************************/
void up_serialinit(void)
{
@@ -779,14 +831,14 @@ void up_serialinit(void)
(void)uart_register("/dev/ttyS1", &TTYS1_DEV);
}
-/************************************************************
+/****************************************************************************
* Name: up_putc
*
* Description:
* Provide priority, low-level access to support OS debug
* writes
*
- ************************************************************/
+ ****************************************************************************/
int up_putc(int ch)
{
@@ -794,7 +846,7 @@ int up_putc(int ch)
uint16 ier;
up_disableuartint(priv, &ier);
- up_waittxfifonotfull(priv);
+ up_waittxready(priv);
up_serialout(priv, UART_THR_OFFS, (ubyte)ch);
/* Check for LF */
@@ -803,11 +855,11 @@ int up_putc(int ch)
{
/* Add CR */
- up_waittxfifonotfull(priv);
+ up_waittxready(priv);
up_serialout(priv, UART_THR_OFFS, '\r');
}
- up_waittxfifonotfull(priv);
+ up_waittxready(priv);
up_restoreuartint(priv, ier);
return ch;
}
diff --git a/nuttx/arch/arm/src/dm320/dm320_serial.c b/nuttx/arch/arm/src/dm320/dm320_serial.c
index c74264b8d..2eea71dd0 100644
--- a/nuttx/arch/arm/src/dm320/dm320_serial.c
+++ b/nuttx/arch/arm/src/dm320/dm320_serial.c
@@ -1,7 +1,7 @@
-/************************************************************
+/****************************************************************************
* dm320/dm320_serial.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
@@ -31,11 +31,11 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Included Files
- ************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
@@ -57,63 +57,64 @@
#if CONFIG_NFILE_DESCRIPTORS > 0
-/************************************************************
+/****************************************************************************
* Definitions
- ************************************************************/
+ ****************************************************************************/
#define BASE_BAUD 115200
-/************************************************************
+/****************************************************************************
* Private Types
- ************************************************************/
+ ****************************************************************************/
struct up_dev_s
{
- uint32 uartbase; /* Base address of UART
- * registers */
+ uint32 uartbase; /* Base address of UART registers */
uint32 baud; /* Configured baud */
uint16 msr; /* Saved MSR value */
- ubyte irq; /* IRQ associated with
- * this UART */
+ ubyte irq; /* IRQ associated with this UART */
ubyte parity; /* 0=none, 1=odd, 2=even */
ubyte bits; /* Number of bits (7 or 8) */
boolean stopbits2; /* TRUE: Configure with 2
* stop bits instead of 1 */
};
-/************************************************************
+/****************************************************************************
* 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 *status);
static void up_rxint(struct uart_dev_s *dev, boolean enable);
-static boolean up_rxfifonotempty(struct uart_dev_s *dev);
+static boolean 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, boolean enable);
-static boolean up_txfifonotfull(struct uart_dev_s *dev);
-static boolean up_txfifoempty(struct uart_dev_s *dev);
+static boolean up_txready(struct uart_dev_s *dev);
+static boolean up_txempty(struct uart_dev_s *dev);
-/************************************************************
+/****************************************************************************
* Private Variables
- ************************************************************/
+ ****************************************************************************/
struct uart_ops_s g_uart_ops =
{
.setup = up_setup,
.shutdown = up_shutdown,
- .handler = up_interrupt,
+ .attach = up_attach,
+ .detach = up_detach,
.ioctl = up_ioctl,
.receive = up_receive,
.rxint = up_rxint,
- .rxfifonotempty = up_rxfifonotempty,
+ .rxavailable = up_rxavailable,
.send = up_send,
.txint = up_txint,
- .txfifonotfull = up_txfifonotfull,
- .txfifoempty = up_txfifoempty,
+ .txready = up_txready,
+ .txempty = up_txempty,
};
/* I/O buffers */
@@ -129,6 +130,7 @@ static struct up_dev_s g_uart0priv =
{
.uartbase = DM320_UART0_REGISTER_BASE,
.baud = CONFIG_UART0_BAUD,
+ .irq = DM320_IRQ_UART0,
.parity = CONFIG_UART0_PARITY,
.bits = CONFIG_UART0_BITS,
.stopbits2 = CONFIG_UART0_2STOP,
@@ -136,7 +138,6 @@ static struct up_dev_s g_uart0priv =
static uart_dev_t g_uart0port =
{
- .irq = DM320_IRQ_UART0,
.recv =
{
.size = CONFIG_UART0_RXBUFSIZE,
@@ -157,6 +158,7 @@ static struct up_dev_s g_uart1priv =
{
.uartbase = DM320_UART1_REGISTER_BASE,
.baud = CONFIG_UART1_BAUD,
+ .irq = DM320_IRQ_UART1,
.parity = CONFIG_UART1_PARITY,
.bits = CONFIG_UART1_BITS,
.stopbits2 = CONFIG_UART1_2STOP,
@@ -164,7 +166,6 @@ static struct up_dev_s g_uart1priv =
static uart_dev_t g_uart1port =
{
- .irq = DM320_IRQ_UART1,
.recv =
{
.size = CONFIG_UART1_RXBUFSIZE,
@@ -191,31 +192,31 @@ static uart_dev_t g_uart1port =
# define TTYS1_DEV g_uart1port
#endif
-/************************************************************
+/****************************************************************************
* Private Functions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Name: up_serialin
- ************************************************************/
+ ****************************************************************************/
static inline uint16 up_serialin(struct up_dev_s *priv, uint32 offset)
{
return getreg16(priv->uartbase + offset);
}
-/************************************************************
+/****************************************************************************
* Name: up_serialout
- ************************************************************/
+ ****************************************************************************/
static inline void up_serialout(struct up_dev_s *priv, uint32 offset, uint16 value)
{
putreg16(value, priv->uartbase + offset);
}
-/************************************************************
+/****************************************************************************
* Name: up_disableuartint
- ************************************************************/
+ ****************************************************************************/
static inline void up_disableuartint(struct up_dev_s *priv, uint16 *msr)
{
@@ -228,9 +229,9 @@ static inline void up_disableuartint(struct up_dev_s *priv, uint16 *msr)
up_serialout(priv, UART_MSR, priv->msr);
}
-/************************************************************
+/****************************************************************************
* Name: up_restoreuartint
- ************************************************************/
+ ****************************************************************************/
static inline void up_restoreuartint(struct up_dev_s *priv, uint16 msr)
{
@@ -238,11 +239,11 @@ static inline void up_restoreuartint(struct up_dev_s *priv, uint16 msr)
up_serialout(priv, UART_MSR, priv->msr);
}
-/************************************************************
- * Name: up_waittxfifonotfull
- ************************************************************/
+/****************************************************************************
+ * Name: up_waittxready
+ ****************************************************************************/
-static inline void up_waittxfifonotfull(struct up_dev_s *priv)
+static inline void up_waittxready(struct up_dev_s *priv)
{
int tmp;
@@ -255,9 +256,9 @@ static inline void up_waittxfifonotfull(struct up_dev_s *priv)
}
}
-/************************************************************
+/****************************************************************************
* Name: up_enablebreaks
- ************************************************************/
+ ****************************************************************************/
static inline void up_enablebreaks(struct up_dev_s *priv, boolean enable)
{
@@ -273,7 +274,7 @@ static inline void up_enablebreaks(struct up_dev_s *priv, boolean enable)
up_serialout(priv, UART_LCR, lcr);
}
-/************************************************************
+/****************************************************************************
* Name: up_setup
*
* Description:
@@ -281,7 +282,7 @@ static inline void up_enablebreaks(struct up_dev_s *priv, boolean enable)
* method is called the first time that the serial port is
* opened.
*
- ************************************************************/
+ ****************************************************************************/
static int up_setup(struct uart_dev_s *dev)
{
@@ -385,14 +386,14 @@ static int up_setup(struct uart_dev_s *dev)
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)
{
@@ -400,7 +401,58 @@ static void up_shutdown(struct uart_dev_s *dev)
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 the
+ * the setup() method is called, however, the serial console may operate 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
+ * interrupts are not enabled until the txint() and rxint() methods are called.
+ *
+ ****************************************************************************/
+
+static int up_attach(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ int ret;
+
+ /* Attach and enable the IRQ */
+
+ ret = irq_attach(priv->irq, up_interrupt);
+ if (ret == OK)
+ {
+ /* Enable the interrupt (RX and TX interrupts are still disabled
+ * in the UART
+ */
+
+ up_enable_irq(priv->irq);
+ }
+ 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)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ up_disable_irq(priv->irq);
+ irq_detach(priv->irq);
+}
+
+/****************************************************************************
* Name: up_interrupt
*
* Description:
@@ -411,7 +463,7 @@ static void up_shutdown(struct uart_dev_s *dev)
* must be able to map the 'irq' number into the approprite
* uart_dev_s structure in order to call these functions.
*
- ************************************************************/
+ ****************************************************************************/
static int up_interrupt(int irq, void *context)
{
@@ -420,11 +472,11 @@ static int up_interrupt(int irq, void *context)
uint16 status;
int passes = 0;
- if (g_uart1port.irq == irq)
+ if (g_uart1priv.irq == irq)
{
dev = &g_uart1port;
}
- else if (g_uart0port.irq == irq)
+ else if (g_uart0priv.irq == irq)
{
dev = &g_uart0port;
}
@@ -474,13 +526,13 @@ static int up_interrupt(int irq, void *context)
}
}
-/************************************************************
+/****************************************************************************
* 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)
{
@@ -532,7 +584,7 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
return ret;
}
-/************************************************************
+/****************************************************************************
* Name: up_receive
*
* Description:
@@ -540,7 +592,7 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
* character from the UART. Error bits associated with the
* receipt are provided in the the return 'status'.
*
- ************************************************************/
+ ****************************************************************************/
static int up_receive(struct uart_dev_s *dev, uint32 *status)
{
@@ -552,13 +604,13 @@ static int up_receive(struct uart_dev_s *dev, uint32 *status)
return dtrr & UART_DTRR_DTR_MASK;
}
-/************************************************************
+/****************************************************************************
* Name: up_rxint
*
* Description:
* Call to enable or disable RX interrupts
*
- ************************************************************/
+ ****************************************************************************/
static void up_rxint(struct uart_dev_s *dev, boolean enable)
{
@@ -576,27 +628,27 @@ static void up_rxint(struct uart_dev_s *dev, boolean enable)
up_serialout(priv, UART_MSR, priv->msr);
}
-/************************************************************
- * Name: up_rxfifonotempty
+/****************************************************************************
+ * Name: up_rxavailable
*
* Description:
* Return TRUE if the receive fifo is not empty
*
- ************************************************************/
+ ****************************************************************************/
-static boolean up_rxfifonotempty(struct uart_dev_s *dev)
+static boolean up_rxavailable(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
return ((up_serialin(priv, UART_SR) & UART_SR_RFNEF) != 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)
{
@@ -604,13 +656,13 @@ static void up_send(struct uart_dev_s *dev, int ch)
up_serialout(priv, UART_DTRR, (uint16)ch);
}
-/************************************************************
+/****************************************************************************
* Name: up_txint
*
* Description:
* Call to enable or disable TX interrupts
*
- ************************************************************/
+ ****************************************************************************/
static void up_txint(struct uart_dev_s *dev, boolean enable)
{
@@ -628,39 +680,39 @@ static void up_txint(struct uart_dev_s *dev, boolean enable)
up_serialout(priv, UART_MSR, priv->msr);
}
-/************************************************************
- * Name: up_txfifonotfull
+/****************************************************************************
+ * Name: up_txready
*
* Description:
* Return TRUE if the tranmsit fifo is not full
*
- ************************************************************/
+ ****************************************************************************/
-static boolean up_txfifonotfull(struct uart_dev_s *dev)
+static boolean up_txready(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
return ((up_serialin(priv, UART_SR) & UART_SR_TFTI) != 0);
}
-/************************************************************
- * Name: up_txfifoempty
+/****************************************************************************
+ * Name: up_txempty
*
* Description:
* Return TRUE if the transmit fifo is empty
*
- ************************************************************/
+ ****************************************************************************/
-static boolean up_txfifoempty(struct uart_dev_s *dev)
+static boolean up_txempty(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
return ((up_serialin(priv, UART_SR) & UART_SR_TREF) == 0);
}
-/************************************************************
+/****************************************************************************
* Public Funtions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Name: up_serialinit
*
* Description:
@@ -668,7 +720,7 @@ static boolean up_txfifoempty(struct uart_dev_s *dev)
* debug so that the serial console will be available
* during bootup. This must be called before up_serialinit.
*
- ************************************************************/
+ ****************************************************************************/
void up_earlyserialinit(void)
{
@@ -679,14 +731,14 @@ void up_earlyserialinit(void)
up_setup(&CONSOLE_DEV);
}
-/************************************************************
+/****************************************************************************
* Name: up_serialinit
*
* Description:
* Register serial console and serial ports. This assumes
* that up_earlyserialinit was called previously.
*
- ************************************************************/
+ ****************************************************************************/
void up_serialinit(void)
{
@@ -695,14 +747,14 @@ void up_serialinit(void)
(void)uart_register("/dev/ttyS1", &TTYS1_DEV);
}
-/************************************************************
+/****************************************************************************
* Name: up_putc
*
* Description:
* Provide priority, low-level access to support OS debug
* writes
*
- ************************************************************/
+ ****************************************************************************/
int up_putc(int ch)
{
@@ -710,7 +762,7 @@ int up_putc(int ch)
uint16 ier;
up_disableuartint(priv, &ier);
- up_waittxfifonotfull(priv);
+ up_waittxready(priv);
up_serialout(priv, UART_DTRR, (uint16)ch);
/* Check for LF */
@@ -719,20 +771,20 @@ int up_putc(int ch)
{
/* Add CR */
- up_waittxfifonotfull(priv);
+ up_waittxready(priv);
up_serialout(priv, UART_DTRR, '\r');
}
- up_waittxfifonotfull(priv);
+ up_waittxready(priv);
up_restoreuartint(priv, ier);
return ch;
}
#else /* CONFIG_NFILE_DESCRIPTORS > 0 */
-/************************************************************
+/****************************************************************************
* Definitions
- ************************************************************/
+ ****************************************************************************/
# ifdef CONFIG_UART1_SERIAL_CONSOLE
# define DM320_REGISTER_BASE DM320_UART1_REGISTER_BASE
@@ -740,11 +792,11 @@ int up_putc(int ch)
# define DM320_REGISTER_BASE DM320_UART0_REGISTER_BASE
# endif
-/************************************************************
+/****************************************************************************
* Private Functions
- ************************************************************/
+ ****************************************************************************/
-static inline void up_waittxfifonotfull(void)
+static inline void up_waittxready(void)
{
int tmp;
@@ -758,13 +810,13 @@ static inline void up_waittxfifonotfull(void)
}
}
-/************************************************************
+/****************************************************************************
* Public Functions
- ************************************************************/
+ ****************************************************************************/
int up_putc(int ch)
{
- up_waittxfifonotfull();
+ up_waittxready();
putreg16((uint16)ch, DM320_REGISTER_BASE + UART_DTRR);
/* Check for LF */
@@ -773,11 +825,11 @@ int up_putc(int ch)
{
/* Add CR */
- up_waittxfifonotfull();
+ up_waittxready();
putreg16((uint16)'\r', DM320_REGISTER_BASE + UART_DTRR);
}
- up_waittxfifonotfull();
+ up_waittxready();
return ch;
}
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_serial.c b/nuttx/arch/arm/src/lpc214x/lpc214x_serial.c
index 6309194d8..b5ed8d85b 100644
--- a/nuttx/arch/arm/src/lpc214x/lpc214x_serial.c
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_serial.c
@@ -1,7 +1,7 @@
/****************************************************************************
* lpc214x/lpc214x_serial.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
@@ -82,15 +82,17 @@ struct up_dev_s
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 *status);
static void up_rxint(struct uart_dev_s *dev, boolean enable);
-static boolean up_rxfifonotempty(struct uart_dev_s *dev);
+static boolean 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, boolean enable);
-static boolean up_txfifonotfull(struct uart_dev_s *dev);
-static boolean up_txfifoempty(struct uart_dev_s *dev);
+static boolean up_txready(struct uart_dev_s *dev);
+static boolean up_txempty(struct uart_dev_s *dev);
/****************************************************************************
* Private Variables
@@ -100,15 +102,16 @@ struct uart_ops_s g_uart_ops =
{
.setup = up_setup,
.shutdown = up_shutdown,
- .handler = up_interrupt,
+ .attach = up_attach,
+ .detach = up_detach,
.ioctl = up_ioctl,
.receive = up_receive,
.rxint = up_rxint,
- .rxfifonotempty = up_rxfifonotempty,
+ .rxavailable = up_rxavailable,
.send = up_send,
.txint = up_txint,
- .txfifonotfull = up_txfifonotfull,
- .txfifoempty = up_txfifoempty,
+ .txready = up_txready,
+ .txempty = up_txempty,
};
/* I/O buffers */
@@ -124,6 +127,7 @@ static struct up_dev_s g_uart0priv =
{
.uartbase = LPC214X_UART0_BASE,
.baud = CONFIG_UART0_BAUD,
+ .irq = LPC214X_UART0_IRQ,
.parity = CONFIG_UART0_PARITY,
.bits = CONFIG_UART0_BITS,
.stopbits2 = CONFIG_UART0_2STOP,
@@ -131,7 +135,6 @@ static struct up_dev_s g_uart0priv =
static uart_dev_t g_uart0port =
{
- .irq = LPC214X_UART0_IRQ,
.recv =
{
.size = CONFIG_UART0_RXBUFSIZE,
@@ -152,6 +155,7 @@ static struct up_dev_s g_uart1priv =
{
.uartbase = LPC214X_UART1_BASE,
.baud = CONFIG_UART1_BAUD,
+ .irq = LPC214X_UART1_IRQ,
.parity = CONFIG_UART1_PARITY,
.bits = CONFIG_UART1_BITS,
.stopbits2 = CONFIG_UART1_2STOP,
@@ -159,7 +163,6 @@ static struct up_dev_s g_uart1priv =
static uart_dev_t g_uart1port =
{
- .irq = LPC214X_UART1_IRQ,
.recv =
{
.size = CONFIG_UART1_RXBUFSIZE,
@@ -234,10 +237,10 @@ static inline void up_restoreuartint(struct up_dev_s *priv, ubyte ier)
}
/****************************************************************************
- * Name: up_waittxfifonotfull
+ * Name: up_waittxready
****************************************************************************/
-static inline void up_waittxfifonotfull(struct up_dev_s *priv)
+static inline void up_waittxready(struct up_dev_s *priv)
{
int tmp;
@@ -360,6 +363,57 @@ static void up_shutdown(struct uart_dev_s *dev)
}
/****************************************************************************
+ * 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 the
+ * the setup() method is called, however, the serial console may operate 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
+ * interrupts are not enabled until the txint() and rxint() methods are called.
+ *
+ ****************************************************************************/
+
+static int up_attach(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ int ret;
+
+ /* Attach and enable the IRQ */
+
+ ret = irq_attach(priv->irq, up_interrupt);
+ if (ret == OK)
+ {
+ /* Enable the interrupt (RX and TX interrupts are still disabled
+ * in the UART
+ */
+
+ up_enable_irq(priv->irq);
+ }
+ 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)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ up_disable_irq(priv->irq);
+ irq_detach(priv->irq);
+}
+
+/****************************************************************************
* Name: up_interrupt
*
* Description:
@@ -379,11 +433,11 @@ static int up_interrupt(int irq, void *context)
ubyte status;
int passes;
- if (g_uart1port.irq == irq)
+ if (g_uart1priv.irq == irq)
{
dev = &g_uart1port;
}
- else if (g_uart0port.irq == irq)
+ else if (g_uart0priv.irq == irq)
{
dev = &g_uart0port;
}
@@ -548,14 +602,14 @@ static void up_rxint(struct uart_dev_s *dev, boolean enable)
}
/****************************************************************************
- * Name: up_rxfifonotempty
+ * Name: up_rxavailable
*
* Description:
* Return TRUE if the receive fifo is not empty
*
****************************************************************************/
-static boolean up_rxfifonotempty(struct uart_dev_s *dev)
+static boolean up_rxavailable(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
return ((up_serialin(priv, LPC214X_UART_LSR_OFFSET) & LPC214X_LSR_RDR) != 0);
@@ -600,28 +654,28 @@ static void up_txint(struct uart_dev_s *dev, boolean enable)
}
/****************************************************************************
- * Name: up_txfifonotfull
+ * Name: up_txready
*
* Description:
* Return TRUE if the tranmsit fifo is not full
*
****************************************************************************/
-static boolean up_txfifonotfull(struct uart_dev_s *dev)
+static boolean up_txready(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
return ((up_serialin(priv, LPC214X_UART_LSR_OFFSET) & LPC214X_LSR_THRE) != 0);
}
/****************************************************************************
- * Name: up_txfifoempty
+ * Name: up_txempty
*
* Description:
* Return TRUE if the transmit fifo is empty
*
****************************************************************************/
-static boolean up_txfifoempty(struct uart_dev_s *dev)
+static boolean up_txempty(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
return ((up_serialin(priv, LPC214X_UART_LSR_OFFSET) & LPC214X_LSR_THRE) != 0);
@@ -692,7 +746,7 @@ int up_putc(int ch)
ubyte ier;
up_disableuartint(priv, &ier);
- up_waittxfifonotfull(priv);
+ up_waittxready(priv);
up_serialout(priv, LPC214X_UART_THR_OFFSET, (ubyte)ch);
/* Check for LF */
@@ -701,11 +755,11 @@ int up_putc(int ch)
{
/* Add CR */
- up_waittxfifonotfull(priv);
+ up_waittxready(priv);
up_serialout(priv, LPC214X_UART_THR_OFFSET, '\r');
}
- up_waittxfifonotfull(priv);
+ up_waittxready(priv);
up_restoreuartint(priv, ier);
return ch;
}
diff --git a/nuttx/arch/c5471/src/up_serial.c b/nuttx/arch/c5471/src/up_serial.c
index 980b4ece3..6a069164d 100644
--- a/nuttx/arch/c5471/src/up_serial.c
+++ b/nuttx/arch/c5471/src/up_serial.c
@@ -1,7 +1,7 @@
-/************************************************************
+/****************************************************************************
* up_serial.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
@@ -31,11 +31,11 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Included Files
- ************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
@@ -52,9 +52,9 @@
#include "os_internal.h"
#include "up_internal.h"
-/************************************************************
+/****************************************************************************
* Definitions
- ************************************************************/
+ ****************************************************************************/
#define BASE_BAUD 115200
@@ -62,9 +62,9 @@
# define CONFIG_UART_HWFLOWCONTROL
#endif
-/************************************************************
+/****************************************************************************
* Private Types
- ************************************************************/
+ ****************************************************************************/
struct uart_regs_s
{
@@ -79,13 +79,11 @@ struct uart_regs_s
struct up_dev_s
{
- unsigned int uartbase; /* Base address of UART
- * registers */
+ unsigned int uartbase; /* Base address of UART registers */
unsigned int baud_base; /* Base baud for conversions */
unsigned int baud; /* Configured baud */
ubyte xmit_fifo_size; /* Size of transmit FIFO */
- ubyte irq; /* IRQ associated with
- * this UART */
+ ubyte irq; /* IRQ associated with this UART */
ubyte parity; /* 0=none, 1=odd, 2=even */
ubyte bits; /* Number of bits (7 or 8) */
#ifdef CONFIG_UART_HWFLOWCONTROL
@@ -97,39 +95,42 @@ struct up_dev_s
struct uart_regs_s regs; /* Shadow copy of readonly regs */
};
-/************************************************************
+/****************************************************************************
* 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, unsigned int *status);
static void up_rxint(struct uart_dev_s *dev, boolean enable);
-static boolean up_rxfifonotempty(struct uart_dev_s *dev);
+static boolean 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, boolean enable);
-static boolean up_txfifonotfull(struct uart_dev_s *dev);
-static boolean up_txfifoempty(struct uart_dev_s *dev);
+static boolean up_txready(struct uart_dev_s *dev);
+static boolean up_txempty(struct uart_dev_s *dev);
-/************************************************************
+/****************************************************************************
* Private Variables
- ************************************************************/
+ ****************************************************************************/
struct uart_ops_s g_uart_ops =
{
.setup = up_setup,
.shutdown = up_shutdown,
- .handler = up_interrupt,
+ .attach = up_attach,
+ .detach = up_detach,
.ioctl = up_ioctl,
.receive = up_receive,
.rxint = up_rxint,
- .rxfifonotempty = up_rxfifonotempty,
+ .rxavailable = up_rxavailable,
.send = up_send,
.txint = up_txint,
- .txfifonotfull = up_txfifonotfull,
- .txfifoempty = up_txfifoempty,
+ .txready = up_txready,
+ .txempty = up_txempty,
};
/* I/O buffers */
@@ -147,6 +148,7 @@ static struct up_dev_s g_irdapriv =
.baud_base = BASE_BAUD,
.uartbase = UART_IRDA_BASE,
.baud = CONFIG_UART_IRDA_BAUD,
+ .irq = C5471_IRQ_UART_IRDA,
.parity = CONFIG_UART_IRDA_PARITY,
.bits = CONFIG_UART_IRDA_BITS,
#ifdef CONFIG_UART_IRDA_HWFLOWCONTROL
@@ -157,7 +159,6 @@ static struct up_dev_s g_irdapriv =
static uart_dev_t g_irdaport =
{
- .irq = C5471_IRQ_UART_IRDA,
.recv =
{
.size = CONFIG_UART_IRDA_RXBUFSIZE,
@@ -180,6 +181,7 @@ static struct up_dev_s g_modempriv =
.baud_base = BASE_BAUD,
.uartbase = UART_MODEM_BASE,
.baud = CONFIG_UART_MODEM_BAUD,
+ .irq = C5471_IRQ_UART,
.parity = CONFIG_UART_MODEM_PARITY,
.bits = CONFIG_UART_MODEM_BITS,
#ifdef CONFIG_UART_MODEM_HWFLOWCONTROL
@@ -190,7 +192,6 @@ static struct up_dev_s g_modempriv =
static uart_dev_t g_modemport =
{
- .irq = C5471_IRQ_UART,
.recv =
{
.size = CONFIG_UART_MODEM_RXBUFSIZE,
@@ -217,31 +218,31 @@ static uart_dev_t g_modemport =
# define TTYS1_DEV g_irdaport
#endif
-/************************************************************
+/****************************************************************************
* Private Functions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Name: up_inserial
- ************************************************************/
+ ****************************************************************************/
static inline uint32 up_inserial(struct up_dev_s *priv, uint32 offset)
{
return getreg32(priv->uartbase + offset);
}
-/************************************************************
+/****************************************************************************
* Name: up_serialout
- ************************************************************/
+ ****************************************************************************/
static inline void up_serialout(struct up_dev_s *priv, uint32 offset, uint32 value)
{
putreg32(value, priv->uartbase + offset);
}
-/************************************************************
+/****************************************************************************
* Name: up_disableuartint
- ************************************************************/
+ ****************************************************************************/
static inline void up_disableuartint(struct up_dev_s *priv, uint16 *ier)
{
@@ -253,9 +254,9 @@ static inline void up_disableuartint(struct up_dev_s *priv, uint16 *ier)
up_serialout(priv, UART_IER_OFFS, priv->regs.ier);
}
-/************************************************************
+/****************************************************************************
* Name: up_restoreuartint
- ************************************************************/
+ ****************************************************************************/
static inline void up_restoreuartint(struct up_dev_s *priv, uint16 ier)
{
@@ -263,11 +264,11 @@ static inline void up_restoreuartint(struct up_dev_s *priv, uint16 ier)
up_serialout(priv, UART_IER_OFFS, priv->regs.ier);
}
-/************************************************************
- * Name: up_waittxfifonotfull
- ************************************************************/
+/****************************************************************************
+ * Name: up_waittxready
+ ****************************************************************************/
-static inline void up_waittxfifonotfull(struct up_dev_s *priv)
+static inline void up_waittxready(struct up_dev_s *priv)
{
int tmp;
@@ -279,9 +280,9 @@ static inline void up_waittxfifonotfull(struct up_dev_s *priv)
}
}
}
-/************************************************************
+/****************************************************************************
* Name: up_disablebreaks
- ************************************************************/
+ ****************************************************************************/
static inline void up_disablebreaks(struct up_dev_s *priv)
{
@@ -289,9 +290,9 @@ static inline void up_disablebreaks(struct up_dev_s *priv)
up_serialout(priv, UART_LCR_OFFS, priv->regs.lcr);
}
-/************************************************************
+/****************************************************************************
* Name: up_enablebreaks
- ************************************************************/
+ ****************************************************************************/
static inline void up_enablebreaks(struct up_dev_s *priv)
{
@@ -299,9 +300,9 @@ static inline void up_enablebreaks(struct up_dev_s *priv)
up_serialout(priv, UART_LCR_OFFS, priv->regs.lcr);
}
-/************************************************************
+/****************************************************************************
* Name: up_setrate
- ************************************************************/
+ ****************************************************************************/
static inline void up_setrate(struct up_dev_s *priv, unsigned int rate)
{
@@ -339,7 +340,7 @@ static inline void up_setrate(struct up_dev_s *priv, unsigned int rate)
up_serialout(priv, UART_DIV_BIT_RATE_OFFS, div_bit_rate);
}
-/************************************************************
+/****************************************************************************
* Name: up_setup
*
* Description:
@@ -347,7 +348,7 @@ static inline void up_setrate(struct up_dev_s *priv, unsigned int rate)
* method is called the first time that the serial port is
* opened.
*
- ************************************************************/
+ ****************************************************************************/
static int up_setup(struct uart_dev_s *dev)
{
@@ -444,13 +445,13 @@ static int up_setup(struct uart_dev_s *dev)
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)
{
@@ -458,7 +459,58 @@ static void up_shutdown(struct uart_dev_s *dev)
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 the
+ * the setup() method is called, however, the serial console may operate 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
+ * interrupts are not enabled until the txint() and rxint() methods are called.
+ *
+ ****************************************************************************/
+
+static int up_attach(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ int ret;
+
+ /* Attach and enable the IRQ */
+
+ ret = irq_attach(priv->irq, up_interrupt);
+ if (ret == OK)
+ {
+ /* Enable the interrupt (RX and TX interrupts are still disabled
+ * in the UART
+ */
+
+ up_enable_irq(priv->irq);
+ }
+ 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)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ up_disable_irq(priv->irq);
+ irq_detach(priv->irq);
+}
+
+/****************************************************************************
* Name: up_interrupt
*
* Description:
@@ -469,7 +521,7 @@ static void up_shutdown(struct uart_dev_s *dev)
* must be able to map the 'irq' number into the approprite
* uart_dev_s structure in order to call these functions.
*
- ************************************************************/
+ ****************************************************************************/
static int up_interrupt(int irq, void *context)
{
@@ -477,11 +529,11 @@ static int up_interrupt(int irq, void *context)
struct up_dev_s *priv;
volatile uint32 cause;
- if (g_irdaport.irq == irq)
+ if (g_irdapriv.irq == irq)
{
dev = &g_irdaport;
}
- else if (g_modemport.irq == irq)
+ else if (g_modempriv.irq == irq)
{
dev = &g_modemport;
}
@@ -543,13 +595,13 @@ static int up_interrupt(int irq, void *context)
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)
{
@@ -601,7 +653,7 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
return ret;
}
-/************************************************************
+/****************************************************************************
* Name: up_receive
*
* Description:
@@ -609,7 +661,7 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
* the UART. Error bits associated with the receipt are provided in the
* the return 'status'.
*
- ************************************************************/
+ ****************************************************************************/
static int up_receive(struct uart_dev_s *dev, unsigned int *status)
{
@@ -631,13 +683,13 @@ static int up_receive(struct uart_dev_s *dev, unsigned int *status)
return rhr & 0x000000ff;
}
-/************************************************************
+/****************************************************************************
* Name: up_rxint
*
* Description:
* Call to enable or disable RX interrupts
*
- ************************************************************/
+ ****************************************************************************/
static void up_rxint(struct uart_dev_s *dev, boolean enable)
{
@@ -656,27 +708,27 @@ static void up_rxint(struct uart_dev_s *dev, boolean enable)
}
}
-/************************************************************
- * Name: up_rxfifonotempty
+/****************************************************************************
+ * Name: up_rxavailable
*
* Description:
* Return TRUE if the receive fifo is not empty
*
- ************************************************************/
+ ****************************************************************************/
-static boolean up_rxfifonotempty(struct uart_dev_s *dev)
+static boolean up_rxavailable(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
return up_inserial(priv, UART_LSR_OFFS) & UART_RX_FIFO_NOEMPTY;
}
-/************************************************************
+/****************************************************************************
* Name: up_send
*
* Description:
* This method will send one byte on the UART
*
- ************************************************************/
+ ****************************************************************************/
static void up_send(struct uart_dev_s *dev, int ch)
{
@@ -684,13 +736,13 @@ static void up_send(struct uart_dev_s *dev, int ch)
up_serialout(priv, UART_THR_OFFS, (ubyte)ch);
}
-/************************************************************
+/****************************************************************************
* Name: up_txint
*
* Description:
* Call to enable or disable TX interrupts
*
- ************************************************************/
+ ****************************************************************************/
static void up_txint(struct uart_dev_s *dev, boolean enable)
{
@@ -709,39 +761,39 @@ static void up_txint(struct uart_dev_s *dev, boolean enable)
}
}
-/************************************************************
- * Name: up_txfifonotfull
+/****************************************************************************
+ * Name: up_txready
*
* Description:
* Return TRUE if the tranmsit fifo is not full
*
- ************************************************************/
+ ****************************************************************************/
-static boolean up_txfifonotfull(struct uart_dev_s *dev)
+static boolean up_txready(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
return (up_inserial(priv, UART_SSR_OFFS) & UART_SSR_TXFULL) == 0;
}
-/************************************************************
- * Name: up_txfifoempty
+/****************************************************************************
+ * Name: up_txempty
*
* Description:
* Return TRUE if the transmit fifo is empty
*
- ************************************************************/
+ ****************************************************************************/
-static boolean up_txfifoempty(struct uart_dev_s *dev)
+static boolean up_txempty(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
return (up_inserial(priv, UART_LSR_OFFS) & UART_LSR_TREF) != 0;
}
-/************************************************************
+/****************************************************************************
* Public Funtions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Name: up_serialinit
*
* Description:
@@ -749,7 +801,7 @@ static boolean up_txfifoempty(struct uart_dev_s *dev)
* debug so that the serial console will be available
* during bootup. This must be called before up_serialinit.
*
- ************************************************************/
+ ****************************************************************************/
void up_earlyserialinit(void)
{
@@ -760,14 +812,14 @@ void up_earlyserialinit(void)
up_setup(&CONSOLE_DEV);
}
-/************************************************************
+/****************************************************************************
* Name: up_serialinit
*
* Description:
* Register serial console and serial ports. This assumes
* that up_earlyserialinit was called previously.
*
- ************************************************************/
+ ****************************************************************************/
void up_serialinit(void)
{
@@ -776,14 +828,14 @@ void up_serialinit(void)
(void)uart_register("/dev/ttyS1", &TTYS1_DEV);
}
-/************************************************************
+/****************************************************************************
* Name: up_putc
*
* Description:
* Provide priority, low-level access to support OS debug
* writes
*
- ************************************************************/
+ ****************************************************************************/
int up_putc(int ch)
{
@@ -791,7 +843,7 @@ int up_putc(int ch)
uint16 ier;
up_disableuartint(priv, &ier);
- up_waittxfifonotfull(priv);
+ up_waittxready(priv);
up_serialout(priv, UART_THR_OFFS, (ubyte)ch);
/* Check for LF */
@@ -800,11 +852,11 @@ int up_putc(int ch)
{
/* Add CR */
- up_waittxfifonotfull(priv);
+ up_waittxready(priv);
up_serialout(priv, UART_THR_OFFS, '\r');
}
- up_waittxfifonotfull(priv);
+ up_waittxready(priv);
up_restoreuartint(priv, ier);
return ch;
}
diff --git a/nuttx/arch/dm320/src/up_serial.c b/nuttx/arch/dm320/src/up_serial.c
index fd843cc12..c952c159f 100644
--- a/nuttx/arch/dm320/src/up_serial.c
+++ b/nuttx/arch/dm320/src/up_serial.c
@@ -1,7 +1,7 @@
-/************************************************************
+/****************************************************************************
* up_serial.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
@@ -31,11 +31,11 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Included Files
- ************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
@@ -52,63 +52,64 @@
#include "os_internal.h"
#include "up_internal.h"
-/************************************************************
+/****************************************************************************
* Definitions
- ************************************************************/
+ ****************************************************************************/
#define BASE_BAUD 115200
-/************************************************************
+/****************************************************************************
* Private Types
- ************************************************************/
+ ****************************************************************************/
struct up_dev_s
{
- uint32 uartbase; /* Base address of UART
- * registers */
+ uint32 uartbase; /* Base address of UART registers */
uint32 baud; /* Configured baud */
uint16 msr; /* Saved MSR value */
- ubyte irq; /* IRQ associated with
- * this UART */
+ ubyte irq; /* IRQ associated with this UART */
ubyte parity; /* 0=none, 1=odd, 2=even */
ubyte bits; /* Number of bits (7 or 8) */
boolean stopbits2; /* TRUE: Configure with 2
* stop bits instead of 1 */
};
-/************************************************************
+/****************************************************************************
* 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 *status);
static void up_rxint(struct uart_dev_s *dev, boolean enable);
-static boolean up_rxfifonotempty(struct uart_dev_s *dev);
+static boolean 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, boolean enable);
-static boolean up_txfifonotfull(struct uart_dev_s *dev);
-static boolean up_txfifoempty(struct uart_dev_s *dev);
+static boolean up_txready(struct uart_dev_s *dev);
+static boolean up_txempty(struct uart_dev_s *dev);
-/************************************************************
+/****************************************************************************
* Private Variables
- ************************************************************/
+ ****************************************************************************/
struct uart_ops_s g_uart_ops =
{
.setup = up_setup,
.shutdown = up_shutdown,
- .handler = up_interrupt,
+ .attach = up_attach,
+ .detach = up_detach,
.ioctl = up_ioctl,
.receive = up_receive,
.rxint = up_rxint,
- .rxfifonotempty = up_rxfifonotempty,
+ .rxavailable = up_rxavailable,
.send = up_send,
.txint = up_txint,
- .txfifonotfull = up_txfifonotfull,
- .txfifoempty = up_txfifoempty,
+ .txready = up_txready,
+ .txempty = up_txempty,
};
/* I/O buffers */
@@ -124,6 +125,7 @@ static struct up_dev_s g_uart0priv =
{
.uartbase = DM320_UART0_REGISTER_BASE,
.baud = CONFIG_UART0_BAUD,
+ .irq = DM320_IRQ_UART0,
.parity = CONFIG_UART0_PARITY,
.bits = CONFIG_UART0_BITS,
.stopbits2 = CONFIG_UART0_2STOP,
@@ -131,7 +133,6 @@ static struct up_dev_s g_uart0priv =
static uart_dev_t g_uart0port =
{
- .irq = DM320_IRQ_UART0,
.recv =
{
.size = CONFIG_UART0_RXBUFSIZE,
@@ -152,6 +153,7 @@ static struct up_dev_s g_uart1priv =
{
.uartbase = DM320_UART1_REGISTER_BASE,
.baud = CONFIG_UART1_BAUD,
+ .irq = DM320_IRQ_UART1,
.parity = CONFIG_UART1_PARITY,
.bits = CONFIG_UART1_BITS,
.stopbits2 = CONFIG_UART1_2STOP,
@@ -159,7 +161,6 @@ static struct up_dev_s g_uart1priv =
static uart_dev_t g_uart1port =
{
- .irq = DM320_IRQ_UART1,
.recv =
{
.size = CONFIG_UART1_RXBUFSIZE,
@@ -186,31 +187,31 @@ static uart_dev_t g_uart1port =
# define TTYS1_DEV g_uart1port
#endif
-/************************************************************
+/****************************************************************************
* Private Functions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Name: up_serialin
- ************************************************************/
+ ****************************************************************************/
static inline uint16 up_serialin(struct up_dev_s *priv, uint32 offset)
{
return getreg16(priv->uartbase + offset);
}
-/************************************************************
+/****************************************************************************
* Name: up_serialout
- ************************************************************/
+ ****************************************************************************/
static inline void up_serialout(struct up_dev_s *priv, uint32 offset, uint16 value)
{
putreg16(value, priv->uartbase + offset);
}
-/************************************************************
+/****************************************************************************
* Name: up_disableuartint
- ************************************************************/
+ ****************************************************************************/
static inline void up_disableuartint(struct up_dev_s *priv, uint16 *msr)
{
@@ -223,9 +224,9 @@ static inline void up_disableuartint(struct up_dev_s *priv, uint16 *msr)
up_serialout(priv, UART_MSR, priv->msr);
}
-/************************************************************
+/****************************************************************************
* Name: up_restoreuartint
- ************************************************************/
+ ****************************************************************************/
static inline void up_restoreuartint(struct up_dev_s *priv, uint16 msr)
{
@@ -233,11 +234,11 @@ static inline void up_restoreuartint(struct up_dev_s *priv, uint16 msr)
up_serialout(priv, UART_MSR, priv->msr);
}
-/************************************************************
- * Name: up_waittxfifonotfull
- ************************************************************/
+/****************************************************************************
+ * Name: up_waittxready
+ ****************************************************************************/
-static inline void up_waittxfifonotfull(struct up_dev_s *priv)
+static inline void up_waittxready(struct up_dev_s *priv)
{
int tmp;
@@ -250,9 +251,9 @@ static inline void up_waittxfifonotfull(struct up_dev_s *priv)
}
}
-/************************************************************
+/****************************************************************************
* Name: up_enablebreaks
- ************************************************************/
+ ****************************************************************************/
static inline void up_enablebreaks(struct up_dev_s *priv, boolean enable)
{
@@ -268,7 +269,7 @@ static inline void up_enablebreaks(struct up_dev_s *priv, boolean enable)
up_serialout(priv, UART_LCR, lcr);
}
-/************************************************************
+/****************************************************************************
* Name: up_setup
*
* Description:
@@ -276,7 +277,7 @@ static inline void up_enablebreaks(struct up_dev_s *priv, boolean enable)
* method is called the first time that the serial port is
* opened.
*
- ************************************************************/
+ ****************************************************************************/
static int up_setup(struct uart_dev_s *dev)
{
@@ -380,14 +381,14 @@ static int up_setup(struct uart_dev_s *dev)
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)
{
@@ -395,7 +396,58 @@ static void up_shutdown(struct uart_dev_s *dev)
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 the
+ * the setup() method is called, however, the serial console may operate 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
+ * interrupts are not enabled until the txint() and rxint() methods are called.
+ *
+ ****************************************************************************/
+
+static int up_attach(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ int ret;
+
+ /* Attach and enable the IRQ */
+
+ ret = irq_attach(priv->irq, up_interrupt);
+ if (ret == OK)
+ {
+ /* Enable the interrupt (RX and TX interrupts are still disabled
+ * in the UART
+ */
+
+ up_enable_irq(priv->irq);
+ }
+ 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)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ up_disable_irq(priv->irq);
+ irq_detach(priv->irq);
+}
+
+/****************************************************************************
* Name: up_interrupt
*
* Description:
@@ -406,7 +458,7 @@ static void up_shutdown(struct uart_dev_s *dev)
* must be able to map the 'irq' number into the approprite
* uart_dev_s structure in order to call these functions.
*
- ************************************************************/
+ ****************************************************************************/
static int up_interrupt(int irq, void *context)
{
@@ -415,11 +467,11 @@ static int up_interrupt(int irq, void *context)
uint16 status;
int passes = 0;
- if (g_uart1port.irq == irq)
+ if (g_uart1priv.irq == irq)
{
dev = &g_uart1port;
}
- else if (g_uart0port.irq == irq)
+ else if (g_uart0priv.irq == irq)
{
dev = &g_uart0port;
}
@@ -469,13 +521,13 @@ static int up_interrupt(int irq, void *context)
}
}
-/************************************************************
+/****************************************************************************
* 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)
{
@@ -527,7 +579,7 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
return ret;
}
-/************************************************************
+/****************************************************************************
* Name: up_receive
*
* Description:
@@ -535,7 +587,7 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
* character from the UART. Error bits associated with the
* receipt are provided in the the return 'status'.
*
- ************************************************************/
+ ****************************************************************************/
static int up_receive(struct uart_dev_s *dev, uint32 *status)
{
@@ -547,13 +599,13 @@ static int up_receive(struct uart_dev_s *dev, uint32 *status)
return dtrr & UART_DTRR_DTR_MASK;
}
-/************************************************************
+/****************************************************************************
* Name: up_rxint
*
* Description:
* Call to enable or disable RX interrupts
*
- ************************************************************/
+ ****************************************************************************/
static void up_rxint(struct uart_dev_s *dev, boolean enable)
{
@@ -571,27 +623,27 @@ static void up_rxint(struct uart_dev_s *dev, boolean enable)
up_serialout(priv, UART_MSR, priv->msr);
}
-/************************************************************
- * Name: up_rxfifonotempty
+/****************************************************************************
+ * Name: up_rxavailable
*
* Description:
* Return TRUE if the receive fifo is not empty
*
- ************************************************************/
+ ****************************************************************************/
-static boolean up_rxfifonotempty(struct uart_dev_s *dev)
+static boolean up_rxavailable(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
return ((up_serialin(priv, UART_SR) & UART_SR_RFNEF) != 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)
{
@@ -599,13 +651,13 @@ static void up_send(struct uart_dev_s *dev, int ch)
up_serialout(priv, UART_DTRR, (uint16)ch);
}
-/************************************************************
+/****************************************************************************
* Name: up_txint
*
* Description:
* Call to enable or disable TX interrupts
*
- ************************************************************/
+ ****************************************************************************/
static void up_txint(struct uart_dev_s *dev, boolean enable)
{
@@ -623,39 +675,39 @@ static void up_txint(struct uart_dev_s *dev, boolean enable)
up_serialout(priv, UART_MSR, priv->msr);
}
-/************************************************************
- * Name: up_txfifonotfull
+/****************************************************************************
+ * Name: up_txready
*
* Description:
* Return TRUE if the tranmsit fifo is not full
*
- ************************************************************/
+ ****************************************************************************/
-static boolean up_txfifonotfull(struct uart_dev_s *dev)
+static boolean up_txready(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
return ((up_serialin(priv, UART_SR) & UART_SR_TFTI) != 0);
}
-/************************************************************
- * Name: up_txfifoempty
+/****************************************************************************
+ * Name: up_txempty
*
* Description:
* Return TRUE if the transmit fifo is empty
*
- ************************************************************/
+ ****************************************************************************/
-static boolean up_txfifoempty(struct uart_dev_s *dev)
+static boolean up_txempty(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
return ((up_serialin(priv, UART_SR) & UART_SR_TREF) == 0);
}
-/************************************************************
+/****************************************************************************
* Public Funtions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Name: up_serialinit
*
* Description:
@@ -663,7 +715,7 @@ static boolean up_txfifoempty(struct uart_dev_s *dev)
* debug so that the serial console will be available
* during bootup. This must be called before up_serialinit.
*
- ************************************************************/
+ ****************************************************************************/
void up_earlyserialinit(void)
{
@@ -674,14 +726,14 @@ void up_earlyserialinit(void)
up_setup(&CONSOLE_DEV);
}
-/************************************************************
+/****************************************************************************
* Name: up_serialinit
*
* Description:
* Register serial console and serial ports. This assumes
* that up_earlyserialinit was called previously.
*
- ************************************************************/
+ ****************************************************************************/
void up_serialinit(void)
{
@@ -690,14 +742,14 @@ void up_serialinit(void)
(void)uart_register("/dev/ttyS1", &TTYS1_DEV);
}
-/************************************************************
+/****************************************************************************
* Name: up_putc
*
* Description:
* Provide priority, low-level access to support OS debug
* writes
*
- ************************************************************/
+ ****************************************************************************/
int up_putc(int ch)
{
@@ -705,7 +757,7 @@ int up_putc(int ch)
uint16 ier;
up_disableuartint(priv, &ier);
- up_waittxfifonotfull(priv);
+ up_waittxready(priv);
up_serialout(priv, UART_DTRR, (uint16)ch);
/* Check for LF */
@@ -714,11 +766,11 @@ int up_putc(int ch)
{
/* Add CR */
- up_waittxfifonotfull(priv);
+ up_waittxready(priv);
up_serialout(priv, UART_DTRR, '\r');
}
- up_waittxfifonotfull(priv);
+ up_waittxready(priv);
up_restoreuartint(priv, ier);
return ch;
}
diff --git a/nuttx/arch/z16/src/z16f/z16f_lowuart.S b/nuttx/arch/z16/src/z16f/z16f_lowuart.S
index a20dbfc63..b39232122 100755
--- a/nuttx/arch/z16/src/z16f/z16f_lowuart.S
+++ b/nuttx/arch/z16/src/z16f/z16f_lowuart.S
@@ -79,15 +79,12 @@
*************************************************************************/
_z16f_lowuartinit:
- pushmlo <r0, r3> /* Save registers */
-
/* Calculate and set the baud rate generation register */
-
-#ifdef CONFIG_UART0_SERIAL_CONSOLE
- ld r3, #CONFIG_UART0_BAUD /* r3 = baud */
+#ifdef CONFIG_UART1_SERIAL_CONSOLE
+ ld r3, #CONFIG_UART1_BAUD /* r3 = Selected UART1 baud */
#else
- ld r3, #CONFIG_UART1_BAUD /* r3 = baud */
+ ld r3, #CONFIG_UART0_BAUD /* r3 = Selected UART0 (default) baud */
#endif
ld r0, r3 /* r0 = baud */
sll r0, #3 /* r0 = baud * 8 */
@@ -122,73 +119,71 @@ _z16f_lowuartinit:
ld r0, #(Z16F_UARTCTL0_TEN|Z16F_UARTCTL0_REN)
ld.b Z16F_UART0_CTL0, r0 /* Z16F_UART0_CTL0 = %c0 */
#endif
- popmlo <r0, r3> /* Restore registers */
ret /* Return */
-
/*************************************************************************
- * Name: _z16f_xmitc
+ * Name: _up_lowputc
*
* Description:
- * Send one character on the selected port
+ * Send one character to the selected serial console
*
* Parmeters:
* r1 = character
*
+ * Return:
+ * None
+ *
+ * Modifies r0 (and maybe r1)
+ *
*************************************************************************/
#ifdef CONFIG_ARCH_LOWPUTC
-_z16f_xmitc:
- pushmlo <r0> /* Save registers */
+_up_lowputc:
+ /* Check if the character to output is a linefeed */
-_z16f_xmitc1:
- ld r0, Z16F_UARTSTAT0_TDRE /* TDRE=Transmitter Data Register Empty */
-#ifdef CONFIG_UART0_SERIAL_CONSOLE
- tm.b Z16F_UART0_STAT0, r0 /* r0 = Z16F_UART0_STAT0 */
- jp eq, _z16f_xmitc1 /* While (!(Z16F_UART0_STAT0 & TDRE)) */
- ld.b Z16F_UART0_TXD, r1 /* Z16F_UART0_TXD = r1 (character) */
-#else
- tm.b Z16F_UART1_STAT0, r0 /* r0 = Z16F_UART0_STAT1 */
- jp eq, _z16f_xmitc1 /* While (!(Z16F_UART1_STAT0 & TDRE)) */
- ld.b Z16F_UART1_TXD, r1 /* Z16F_UART1_TXD = r1 (character) */
-#endif
- popmlo <r0> /* Restore registers */
- ret /* Return */
-#endif
+ ext.ub r0, r1 /* r0=Character masked to 8-bits */
+ cp r0, #10 /* Is it a linefeed ('\n') */
+ jp ne, _z16f_xmitc /* No? Jump to _z16f_xmitc with character in r1 */
+
+ /* Output a carriage return before the linefeed */
+
+ ld r1, #13 /* Output carriage reuturn ('\r') */
+ call _z16f_xmitc /* Call _z16f_xmitc with r1='\r' */
+ ld r1, #10 /* Restore r1=linefeed to output */
+ /* Fall through to _z16f_xmitc with linefeed in r1 */
/*************************************************************************
- * Name: _up_lowputc
+ * Name: _z16f_xmitc
*
* Description:
- * Send one character to the selected serial console
+ * Send one character on the selected port (really a part of up_lowputc)
*
- * Parmeters:
+ * Parameters:
* r1 = character
*
- * Return
- * R0 = 0
+ * Return:
+ * None
+ *
+ * Modifies r0
*
*************************************************************************/
#ifdef CONFIG_ARCH_LOWPUTC
-_up_lowputc:
- pushmlo <r1,r5> /* Save registers */
- ld r0, r1
- ext.ub r5, r0
- cp r5, #10
- jp ne, _up_lowputc1 /* If (character == \n) */
-
- ld r1,#13
- call _z16f_xmitc /* Call _z16f_xmitc with \r */
-
-_up_lowputc1:
- ld r1, r0
- call _z16f_xmitc /* Xall _z16f_xmitc with character */
-
- ld r0, #0 /* return r0 = 0 */
- popmlo <r1,r5> /* Restore registers */
- ret /* Return */
+_z16f_xmitc:
+_z16f_xmitc1:
+ ld r0, Z16F_UARTSTAT0_TDRE /* TDRE=Transmitter Data Register Empty */
+#ifdef CONFIG_UART1_SERIAL_CONSOLE
+ tm.b Z16F_UART1_STAT0, r0 /* r0 = Z16F_UART1_STAT0 */
+ jp eq, _z16f_xmitc1 /* While (!(Z16F_UART1_STAT0 & TDRE)) */
+ ld.b Z16F_UART1_TXD, r1 /* Z16F_UART1_TXD = r1 (character) */
+#else
+ tm.b Z16F_UART0_STAT0, r0 /* r0 = Z16F_UART0_STAT1 */
+ jp eq, _z16f_xmitc1 /* While (!(Z16F_UART0_STAT0 & TDRE)) */
+ ld.b Z16F_UART0_TXD, r1 /* Z16F_UART0_TXD = r1 (character) */
#endif
+ ret /* Return */
+
+#endif /* CONFIG_ARCH_LOWPUTC */
/*************************************************************************
* Name: _up_lowgetc
@@ -206,16 +201,16 @@ _up_lowputc1:
#ifdef CONFIG_ARCH_LOWGETC
_up_lowgetc:
-up_lowgetc1:
+_up_lowgetc1:
ld r0, #Z16F_UARTSTAT0_RDA /* RDA=Receive data available */
-#ifdef CONFIG_UART0_SERIAL_CONSOLE
- tm.b Z16F_UART0_STAT0, r0
- jp eq, _up_lowgetc1 /* While (!Z16F_UART0_STAT0 & RDA)) */
- ld.ub r0, Z16F_UART0_RXD /* r0 = Z16F_UART0_RXD */
+#ifdef CONFIG_UART1_SERIAL_CONSOLE
+ tm.b Z16F_UART1_STAT0, r0
+ jp eq, _up_lowgetc1 /* While (!Z16F_UART1_STAT0 & RDA)) */
+ ld.ub r0, Z16F_UART1_RXD /* r0 = Z16F_UART1_RXD */
#else
- tm.b Z16F_UART1_STAT0,r0 /* While (!Z16F_UART1_STAT0 & RDA) */
+ tm.b Z16F_UART0_STAT0,r0 /* While (!Z16F_UART0_STAT0 & RDA) */
jp eq, _up_lowgetc1
- ld.ub r0, Z16F_UART1_RXD /* r0 = Z16F_UART1_RXD */
+ ld.ub r0, Z16F_UART0_RXD /* r0 = Z16F_UART0_RXD */
#endif
cp r0, #%0d /* Test for '\r' */
jp eq, _up_lowgetc2
@@ -231,3 +226,4 @@ _up_lowgetc3: /* Return value in r0 */
#endif /* CONFIG_ARCH_LOWPUTC || CONFIG_ARCH_LOWGETC */
end
+
diff --git a/nuttx/arch/z16/src/z16f/z16f_serial.c b/nuttx/arch/z16/src/z16f/z16f_serial.c
index d63c6e5dd..80292c03b 100644
--- a/nuttx/arch/z16/src/z16f/z16f_serial.c
+++ b/nuttx/arch/z16/src/z16f/z16f_serial.c
@@ -77,9 +77,10 @@ struct z16f_uart_s
uint32 uartbase; /* Base address of UART
* registers */
uint32 baud; /* Configured baud */
- uint16 msr; /* Saved MSR value */
- ubyte irq; /* IRQ associated with
- * this UART */
+ boolean rxenabled; /* RX interrupt enabled */
+ boolean txenabled; /* TX interrupt enabled */
+ ubyte rxirq; /* RX IRQ associated with this UART */
+ ubyte txirq; /* RX IRQ associated with this UART */
ubyte parity; /* 0=none, 1=odd, 2=even */
boolean stopbits2; /* TRUE: Configure with 2
* stop bits instead of 1 */
@@ -91,15 +92,17 @@ struct z16f_uart_s
static int z16f_setup(struct uart_dev_s *dev);
static void z16f_shutdown(struct uart_dev_s *dev);
+static int z16f_attach(struct uart_dev_s *dev);
+static void z16f_detach(struct uart_dev_s *dev);
static int z16f_interrupt(int irq, void *context);
static int z16f_ioctl(struct file *filep, int cmd, unsigned long arg);
static int z16f_receive(struct uart_dev_s *dev, uint32 *status);
static void z16f_rxint(struct uart_dev_s *dev, boolean enable);
-static boolean z16f_rxfifonotempty(struct uart_dev_s *dev);
+static boolean z16f_rxavailable(struct uart_dev_s *dev);
static void z16f_send(struct uart_dev_s *dev, int ch);
static void z16f_txint(struct uart_dev_s *dev, boolean enable);
-static boolean z16f_txfifonotfull(struct uart_dev_s *dev);
-static boolean z16f_txfifoempty(struct uart_dev_s *dev);
+static boolean z16f_txready(struct uart_dev_s *dev);
+static boolean z16f_txempty(struct uart_dev_s *dev);
/****************************************************************************
* Private Variables
@@ -109,15 +112,16 @@ struct uart_ops_s g_uart_ops =
{
z16f_setup, /* setup */
z16f_shutdown, /* shutdown */
- z16f_interrupt, /* handler */
+ z16f_attach, /* attach */
+ z16f_detach, /* detach */
z16f_ioctl, /* ioctl */
z16f_receive, /* receive */
z16f_rxint, /* rxint */
- z16f_rxfifonotempty, /* rxfifonotempty */
+ z16f_rxavailable, /* rxavailable */
z16f_send, /* send */
z16f_txint, /* txint */
- z16f_txfifonotfull, /* txfifonotfull */
- z16f_txfifoempty /* txfifoempty */
+ z16f_txready, /* txready */
+ z16f_txempty /* txempty */
};
/* I/O buffers */
@@ -133,7 +137,10 @@ static struct z16f_uart_s g_uart0priv =
{
Z16F_UART0_BASE, /* uartbase */
CONFIG_UART0_BAUD, /* baud */
- 0, /* msr */
+ FALSE, /* rxenabled */
+ FALSE, /* txenabled */
+ Z16F_IRQ_UART0TX, /* txirq */
+ Z16F_IRQ_UART0RX, /* rxirq */
CONFIG_UART0_PARITY, /* parity */
CONFIG_UART0_2STOP /* stopbits2 */
};
@@ -141,9 +148,6 @@ static struct z16f_uart_s g_uart0priv =
static uart_dev_t g_uart0port =
{
0, /* open_count */
-/* REVISIT */
- Z16F_IRQ_UART0TX, /* txirq */
- Z16F_IRQ_UART0RX, /* rxirq */
FALSE, /* xmitwaiting */
FALSE, /* recvwaiting */
#ifdef CONFIG_UART0_SERIAL_CONSOLE
@@ -178,7 +182,10 @@ static struct z16f_uart_s g_uart1priv =
{
Z16F_UART1_BASE, /* uartbase */
CONFIG_UART1_BAUD, /* baud */
- 0, /* msr */
+ FALSE, /* rxenabled */
+ FALSE, /* txenabled */
+ Z16F_IRQ_UART1TX, /* txirq */
+ Z16F_IRQ_UART1RX, /* rxirq */
CONFIG_UART1_PARITY, /* parity */
CONFIG_UART1_2STOP /* stopbits2 */
};
@@ -186,9 +193,6 @@ static struct z16f_uart_s g_uart1priv =
static uart_dev_t g_uart1port =
{
0, /* open_count */
-/* REVISIT */
- Z16F_IRQ_UART1TX, /* txirq */
- Z16F_IRQ_UART1RX, /* rxirq */
FALSE, /* xmitwaiting */
FALSE, /* recvwaiting */
#ifdef CONFIG_UART0_SERIAL_CONSOLE
@@ -349,6 +353,68 @@ static void z16f_shutdown(struct uart_dev_s *dev)
}
/****************************************************************************
+ * Name: z16f_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 the
+ * the setup() method is called, however, the serial console may operate 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
+ * interrupts are not enabled until the txint() and rxint() methods are called.
+ *
+ ****************************************************************************/
+
+static int z16f_attach(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ int ret;
+
+ /* Attach the RX IRQ */
+
+ ret = irq_attach(priv->rxirq, z16f_rxinterrupt);
+ if (ret != OK)
+ {
+ goto errout;
+ }
+
+ /* Attach the TX IRQ */
+
+ ret = irq_attach(priv->txirq, z16f_txinterrupt);
+ if (ret != OK)
+ {
+ goto errout_with_rxirq;
+ }
+ return OK;
+
+errout_with_rxirq:
+ irq_detach(priv->rxirq);
+errout:
+ return ret;
+}
+
+/****************************************************************************
+ * Name: z16f_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 z16f_detach(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ up_disable_irq(priv->rxirq);
+ up_disable_irq(priv->txirq);
+ irq_detach(priv->rxirq);
+ irq_detach(priv->txirq);
+}
+
+/****************************************************************************
* Name: z16f_interrupt
*
* Description:
@@ -370,17 +436,15 @@ static int z16f_interrupt(int irq, void *context)
/* REVISIT */
-#if 0
- if (g_uart1port.txirq == irq || g_uart1port.rxirq == irq)
+ if (g_uart1priv.txirq == irq || g_uart1priv.rxirq == irq)
{
dev = &g_uart1port;
}
- else if (g_uart0port.txirq == irq || g_uart0port.rxirq == irq)
+ else if (g_uart0priv.txirq == irq || g_uart0priv.rxirq == irq)
{
dev = &g_uart0port;
}
else
-#endif
{
PANIC(OSERR_INTERNAL);
}
@@ -489,14 +553,14 @@ static void z16f_rxint(struct uart_dev_s *dev, boolean enable)
}
/****************************************************************************
- * Name: z16f_rxfifonotempty
+ * Name: z16f_rxavailable
*
* Description:
* Return TRUE if the receive fifo is not empty
*
****************************************************************************/
-static boolean z16f_rxfifonotempty(struct uart_dev_s *dev)
+static boolean z16f_rxavailable(struct uart_dev_s *dev)
{
struct z16f_uart_s *priv = (struct z16f_uart_s*)dev->priv;
return ((getreg8(priv->uartbase + Z16F_UART_STAT0) & Z16F_UARTSTAT0_RDA) != 0);
@@ -543,28 +607,28 @@ static void z16f_txint(struct uart_dev_s *dev, boolean enable)
}
/****************************************************************************
- * Name: z16f_txfifonotfull
+ * Name: z16f_txready
*
* Description:
* Return TRUE if the tranmsit fifo is not full
*
****************************************************************************/
-static boolean z16f_txfifonotfull(struct uart_dev_s *dev)
+static boolean z16f_txready(struct uart_dev_s *dev)
{
struct z16f_uart_s *priv = (struct z16f_uart_s*)dev->priv;
return ((getreg8(priv->uartbase + Z16F_UART_STAT0) & Z16F_UARTSTAT0_TDRE) != 0);
}
/****************************************************************************
- * Name: z16f_txfifoempty
+ * Name: z16f_txempty
*
* Description:
* Return TRUE if the transmit fifo is empty
*
****************************************************************************/
-static boolean z16f_txfifoempty(struct uart_dev_s *dev)
+static boolean z16f_txempty(struct uart_dev_s *dev)
{
struct z16f_uart_s *priv = (struct z16f_uart_s*)dev->priv;
return ((getreg8(priv->uartbase + Z16F_UART_STAT0) & Z16F_UARTSTAT0_TXE) != 0);