summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-02-18 16:27:25 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-02-18 16:27:25 +0000
commit729c58f09da86256667803ebe66764688271ec92 (patch)
treedcd821ac5bf0cea1508de97ba14eb25118463596 /nuttx/arch
parent932dd4c4c8c8f8b49904a068c32c7f879b90a639 (diff)
downloadpx4-nuttx-729c58f09da86256667803ebe66764688271ec92.tar.gz
px4-nuttx-729c58f09da86256667803ebe66764688271ec92.tar.bz2
px4-nuttx-729c58f09da86256667803ebe66764688271ec92.zip
Add framework for UART support
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@704 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/z80/src/common/up_initialize.c6
-rw-r--r--nuttx/arch/z80/src/common/up_internal.h21
-rw-r--r--nuttx/arch/z80/src/z8/Make.defs4
-rw-r--r--nuttx/arch/z80/src/z8/chip.h67
-rw-r--r--nuttx/arch/z80/src/z8/switch.h8
-rwxr-xr-xnuttx/arch/z80/src/z8/z8_lowuart.S156
-rwxr-xr-xnuttx/arch/z80/src/z8/z8_serial.c802
7 files changed, 1058 insertions, 6 deletions
diff --git a/nuttx/arch/z80/src/common/up_initialize.c b/nuttx/arch/z80/src/common/up_initialize.c
index 036e4618a..a572919b0 100644
--- a/nuttx/arch/z80/src/common/up_initialize.c
+++ b/nuttx/arch/z80/src/common/up_initialize.c
@@ -154,7 +154,13 @@ void up_initialize(void)
/* Initialize the serial device driver */
+#ifdef CONFIG_USE_SERIALDRIVER
up_serialinit();
+#endif
+
+#ifdef CONFIG_USE_LOWCONSOLE
+ lowconsole_init();
+#endif
/* Initialize the netwok */
diff --git a/nuttx/arch/z80/src/common/up_internal.h b/nuttx/arch/z80/src/common/up_internal.h
index 838b4cf36..5eefa5069 100644
--- a/nuttx/arch/z80/src/common/up_internal.h
+++ b/nuttx/arch/z80/src/common/up_internal.h
@@ -50,6 +50,8 @@
#undef CONFIG_SUPPRESS_SERIAL_INTS /* Console will poll */
#undef CONFIG_SUPPRESS_UART_CONFIG /* Do not reconfig UART */
#undef CONFIG_DUMP_ON_EXIT /* Dump task state on exit */
+#undef CONFIG_Z80_LOWPUTC /* Support up_lowputc for debug */
+#undef CONFIG_Z80_LOWGETC /* support up_lowgetc for debug */
/****************************************************************************
* Included Files
@@ -63,6 +65,17 @@
* Definitions
****************************************************************************/
+ /* Determine which (if any) console driver to use */
+
+#if defined(CONFIG_Z80_LOWPUTC) || defined(CONFIG_Z80_LOWGETC) || \
+ CONFIG_NFILE_DESCRIPTORS == 0 || defined(CONFIG_DEV_LOWCONSOLE)
+# define CONFIG_USE_LOWCONSOLE 1
+# define CONFIG_USE_LOWUARTINIT 1
+#elif defined(CONFIG_DEV_CONSOLE) && CONFIG_NFILE_DESCRIPTORS > 0
+# define CONFIG_USE_SERIALDRIVER 1
+# define CONFIG_USE_EARLYSERIALINIT 1
+#endif
+
/****************************************************************************
* Public Types
****************************************************************************/
@@ -106,7 +119,7 @@ void up_addregion(void);
/* Defined in up_serial.c */
-#if CONFIG_NFILE_DESCRIPTORS > 0
+#ifdef CONFIG_USE_SERIALDRIVER
EXTERN void up_earlyserialinit(void);
EXTERN void up_serialinit(void);
#else
@@ -114,6 +127,12 @@ EXTERN void up_serialinit(void);
# define up_serialinit()
#endif
+#ifdef CONFIG_USE_LOWCONSOLE
+EXTERN void lowconsole_init(void);
+#else
+# define lowconsole_init()
+#endif
+
/* Defined in up_timerisr.c */
EXTERN void up_timerinit(void);
diff --git a/nuttx/arch/z80/src/z8/Make.defs b/nuttx/arch/z80/src/z8/Make.defs
index ecf1b84b7..c1df518c4 100644
--- a/nuttx/arch/z80/src/z8/Make.defs
+++ b/nuttx/arch/z80/src/z8/Make.defs
@@ -42,8 +42,8 @@ CMN_CSRCS = up_initialize.c up_allocateheap.c up_createstack.c \
up_reprioritizertr.c up_idle.c up_assert.c up_doirq.c \
up_mdelay.c up_udelay.c up_usestack.c
-CHIP_SSRCS = z8_vector.S z8_saveusercontext.S z8_restorecontext.S
+CHIP_SSRCS = z8_lowuart.S z8_vector.S z8_saveusercontext.S z8_restorecontext.S
CHIP_CSRCS = z8_initialstate.c z8_irq.c z8_saveirqcontext.c \
z8_schedulesigaction.c z8_sigdeliver.c z8_timerisr.c \
- z8_registerdump.c
+ z8_serial.c z8_registerdump.c
diff --git a/nuttx/arch/z80/src/z8/chip.h b/nuttx/arch/z80/src/z8/chip.h
index a8b94f80d..a79bf054a 100644
--- a/nuttx/arch/z80/src/z8/chip.h
+++ b/nuttx/arch/z80/src/z8/chip.h
@@ -97,6 +97,73 @@
#define Z8_TIMERCTL_GATED _HX(06)
#define Z8_TIMERCTL_CAPCMP _HX(07)
+/* UART Register Offsets *************************************************************/
+
+#define Z8_UART_TXD _HX(00) /* 8-bits: UART Transmit Data */
+#define Z8_UART_RXD _HX(00) /* 8-bits: UART Receive Data */
+#define Z8_UART_STAT0 _HX(01) /* 8-bits: UART Status 0 */
+#define Z8_UART_CTL _HX(02) /* 16-bits: UART Control */
+#define Z8_UART_CTL0 _HX(02) /* 8-bits: UART Control 0 */
+#define Z8_UART_CTL1 _HX(03) /* 8-bits: UART COntrol 1 */
+#if defined(_Z8FMC16) || defined(_Z8F1680)
+# define Z8_UART_MDSTAT _HX(04) /* 8-bits: UART Mode Select & Status */
+#else
+# define Z8_UART_STAT1 _HX(04) /* 8-bits: UART Status 1 */
+#endif
+#define Z8_UART_ADDR _HX(05) /* 8-bits: UART Address Compare */
+#define Z8_UART_BR _HX(06) /* 16-bits: UART Baud Rate */
+#define Z8_UART_BRH _HX(06) /* 8-bits: UART Baud Rate High Byte */
+#define Z8_UART_BRL _HX(07) /* 8-bits: UART Baud Rate Low Byte */
+
+/* UART0/1 Base Register Addresses **************************************************/
+
+#ifdef EZ8_UART0
+# define Z8_UART0_BASE ((ubyte volatile far*)0xf40)
+#endif
+
+#ifdef EZ8_UART1
+# define Z8_UART1_BASE ((ubyte volatile far*)0xf48)
+#endif
+
+/* UART0/1 Status 0 Register Bit Definitions ****************************************/
+
+#define Z8_UARTSTAT0_RDA _HX(80) /* Bit 7: Receive Data Available */
+#define Z8_UARTSTAT0_PE _HX(40) /* Bit 6: Parity Error */
+#define Z8_UARTSTAT0_OE _HX(20) /* Bit 5: Overrun Error */
+#define Z8_UARTSTAT0_FE _HX(10) /* Bit 4: Framing Error */
+#define Z8_UARTSTAT0_BRKD _HX(08) /* Bit 3: Break Detect */
+#define Z8_UARTSTAT0_TDRE _HX(04) /* Bit 2: Transmitter Data Register Empty */
+#define Z8_UARTSTAT0_TXE _HX(02) /* Bit 1: Transmitter Empty */
+#define Z8_UARTSTAT0_CTS _HX(01) /* Bit 0: Clear To Send */
+
+/* UART0/1 Control 0/1 Register Bit Definitions *************************************/
+
+#define Z8_UARTCTL0_TEN _HX(80) /* Bit 7: Transmit Enable */
+#define Z8_UARTCTL0_REN _HX(40) /* Bit 6: Receive Enable */
+#define Z8_UARTCTL0_CTSE _HX(20) /* Bit 5: CTS Enable */
+#define Z8_UARTCTL0_PEN _HX(10) /* Bit 4: Parity Enable */
+#define Z8_UARTCTL0_PSEL _HX(08) /* Bit 3: Odd Parity Select */
+#define Z8_UARTCTL0_SBRK _HX(04) /* Bit 2: Send Break */
+#define Z8_UARTCTL0_STOP _HX(02) /* Bit 1: Stop Bit Select */
+#define Z8_UARTCTL0_LBEN _HX(01) /* Bit 0: Loopback Enable */
+
+#define Z8_UARTCTL1_MPMD1 _HX(80) /* Bit 7: Multiprocessor Mode (bit1) */
+#define Z8_UARTCTL1_MPEN _HX(40) /* Bit 6: Multiprocessor Enable */
+#define Z8_UARTCTL1_MPMD0 _HX(20) /* Bit 5: Multiprocessor Mode (bit0) */
+#define Z8_UARTCTL1_MPBT _HX(10) /* Bit 4: Multiprocessor Bit Transmit */
+#define Z8_UARTCTL1_DEPOL _HX(08) /* Bit 3: Driver Enable Polarity */
+#define Z8_UARTCTL1_BRGCTL _HX(04) /* Bit 2: Baud Rate Generator Control */
+#define Z8_UARTCTL1_RDAIRQ _HX(02) /* Bit 1: Receive Data Interrupt Enable */
+#define Z8_UARTCTL1_IREN _HX(01) /* Bit 0: Infrared Encoder/Decoder Eanble */
+
+/* UART0/1 Mode Status/Select Register Bit Definitions ******************************/
+
+#define Z8_UARTMDSEL_NORMAL _HX(00) /* Bits 5-7=0: Multiprocessor and Normal Mode */
+#define Z8_UARTMDSEL_FILTER HX(20) /* Bits 5-7=1: Noise Filter Control/Status */
+#define Z8_UARTMDSEL_LINP HX(40) /* Bits 5-7=2: LIN protocol Contol/Status */
+#define Z8_UARTMDSEL_HWREV HX(e0) /* Bits 5-7=7: LIN-UART Hardware Revision */
+ /* Bits 0-4: Mode dependent status */
+
/* Register access macros ***********************************************************
*
* The register access mechanism provided in ez8.h differs from the useful in other
diff --git a/nuttx/arch/z80/src/z8/switch.h b/nuttx/arch/z80/src/z8/switch.h
index 708ce5944..96038c9b7 100644
--- a/nuttx/arch/z80/src/z8/switch.h
+++ b/nuttx/arch/z80/src/z8/switch.h
@@ -42,9 +42,11 @@
************************************************************************************/
#include <sys/types.h>
-#include <nuttx/sched.h>
-#include <nuttx/arch.h>
-#include "up_internal.h"
+#ifndef __ASSEMBLY__
+# include <nuttx/sched.h>
+# include <nuttx/arch.h>
+#endif
+#include "common/up_internal.h"
/************************************************************************************
* Definitions
diff --git a/nuttx/arch/z80/src/z8/z8_lowuart.S b/nuttx/arch/z80/src/z8/z8_lowuart.S
new file mode 100755
index 000000000..152748b96
--- /dev/null
+++ b/nuttx/arch/z80/src/z8/z8_lowuart.S
@@ -0,0 +1,156 @@
+/*************************************************************************
+ * arch/z80/src/z8/z8_lowuart.asm
+ * ez8 UART management
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSeqUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ *************************************************************************/
+
+/*************************************************************************
+ * Included Files
+ *************************************************************************/
+
+#include <nuttx/config.h>
+#include "chip/chip.h"
+#include "common/up_internal.h"
+
+#ifdef CONFIG_USE_LOWUARTINIT
+
+/*************************************************************************
+ * External References / External Definitions
+ *************************************************************************/
+
+ xdef _z8_lowuartinit
+#ifdef CONFIG_Z80_LOWPUTC
+ xdef _up_lowputc
+#endif
+#ifdef CONFIG_Z80_LOWGETC
+ xdef _up_lowgetc
+#endif
+
+/*************************************************************************
+ * Data Allocation
+ *************************************************************************/
+
+ define CODESEG, SPACE=ROM
+ segment CODESEG
+
+/*************************************************************************
+ * Code
+ *************************************************************************/
+
+/*************************************************************************
+ * Name: z8_lowuartinit
+ *
+ * Description:
+ * Initialize UART0 or UART1
+ *
+ * Parameters:
+ * None
+ *
+ *************************************************************************/
+
+_z8_lowuartinit:
+#endif /* CONFIG_USE_LOWUARTINIT */
+
+/*************************************************************************
+ * Name: _up_lowputc
+ *
+ * Description:
+ * Send one character to the selected serial console
+ *
+ * Parmeters:
+ * r1 = character
+ *
+ * Return:
+ * None
+ *
+ * Modifies r0 (and maybe r1)
+ *
+ *************************************************************************/
+
+#ifdef CONFIG_Z80_LOWPUTC
+_up_lowputc:
+ /* Check if the character to output is a linefeed */
+
+
+ /* Output a carriage return before the linefeed */
+
+
+/*************************************************************************
+ * Name: _z8_xmitc
+ *
+ * Description:
+ * Send one character on the selected port (really a part of up_lowputc)
+ *
+ * Parameters:
+ * r1 = character
+ *
+ * Return:
+ * None
+ *
+ * Modifies r0
+ *
+ *************************************************************************/
+
+_z8_xmitc:
+_z8_xmitc1:
+#ifdef CONFIG_UART1_SERIAL_CONSOLE
+#else
+#endif
+ ret /* Return */
+
+#endif /* CONFIG_Z80_LOWPUTC */
+
+/*************************************************************************
+ * Name: _up_lowgetc
+ *
+ * Description:
+ * Get a character from the serial port
+ *
+ * Parmeters:
+ * None
+ *
+ * Return
+ * R0 = Character read
+ *
+ *************************************************************************/
+
+#ifdef CONFIG_Z80_LOWGETC
+_up_lowgetc:
+_up_lowgetc1:
+#ifdef CONFIG_UART1_SERIAL_CONSOLE
+#else
+#endif
+#endif
+
+ end
+
diff --git a/nuttx/arch/z80/src/z8/z8_serial.c b/nuttx/arch/z80/src/z8/z8_serial.c
new file mode 100755
index 000000000..19ee84786
--- /dev/null
+++ b/nuttx/arch/z80/src/z8/z8_serial.c
@@ -0,0 +1,802 @@
+/****************************************************************************
+ * arch/z80/src/z8/z8_serial.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <unistd.h>
+#include <semaphore.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+#include <ez8.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include <nuttx/serial.h>
+#include <arch/serial.h>
+
+#include "chip/chip.h"
+#include "os_internal.h"
+#include "up_internal.h"
+
+#ifdef CONFIG_USE_SERIALDRIVER
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* System clock frequency value from ZDS target settings */
+
+#define STATE_DISABLED 0
+#define STATE_RXENABLED 1
+#define STATE_TXENABLED 2
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct z8_uart_s
+{
+ (ubyte volatile far*) uartbase; /* Base address of UART
+ * registers */
+ uint32 baud; /* Configured baud */
+ 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 */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static int z8_setup(struct uart_dev_s *dev);
+static void z8_shutdown(struct uart_dev_s *dev);
+static int z8_attach(struct uart_dev_s *dev);
+static void z8_detach(struct uart_dev_s *dev);
+static int z8_rxinterrupt(int irq, void *context);
+static int z8_txinterrupt(int irq, void *context);
+static int z8_ioctl(struct file *filep, int cmd, unsigned long arg);
+static int z8_receive(struct uart_dev_s *dev, uint32 *status);
+static void z8_rxint(struct uart_dev_s *dev, boolean enable);
+static boolean z8_rxavailable(struct uart_dev_s *dev);
+static void z8_send(struct uart_dev_s *dev, int ch);
+static void z8_txint(struct uart_dev_s *dev, boolean enable);
+static boolean z8_txready(struct uart_dev_s *dev);
+static boolean z8_txempty(struct uart_dev_s *dev);
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+struct uart_ops_s g_uart_ops =
+{
+ z8_setup, /* setup */
+ z8_shutdown, /* shutdown */
+ z8_attach, /* attach */
+ z8_detach, /* detach */
+ z8_ioctl, /* ioctl */
+ z8_receive, /* receive */
+ z8_rxint, /* rxint */
+ z8_rxavailable, /* rxavailable */
+ z8_send, /* send */
+ z8_txint, /* txint */
+ z8_txready, /* txready */
+ z8_txempty /* txempty */
+};
+
+/* I/O buffers */
+
+static char g_uart0rxbuffer[CONFIG_UART0_RXBUFSIZE];
+static char g_uart0txbuffer[CONFIG_UART0_TXBUFSIZE];
+static char g_uart1rxbuffer[CONFIG_UART1_RXBUFSIZE];
+static char g_uart1txbuffer[CONFIG_UART1_TXBUFSIZE];
+
+/* This describes the state of the DM320 uart0 port. */
+
+static struct z8_uart_s g_uart0priv =
+{
+ Z8_UART0_BASE, /* uartbase */
+ CONFIG_UART0_BAUD, /* baud */
+ FALSE, /* rxenabled */
+ FALSE, /* txenabled */
+ Z8_IRQ_UART0RX, /* rxirq */
+ Z8_IRQ_UART0TX, /* txirq */
+ CONFIG_UART0_PARITY, /* parity */
+ CONFIG_UART0_2STOP /* stopbits2 */
+};
+
+static uart_dev_t g_uart0port =
+{
+ 0, /* open_count */
+ FALSE, /* xmitwaiting */
+ FALSE, /* recvwaiting */
+#ifdef CONFIG_UART0_SERIAL_CONSOLE
+ TRUE, /* isconsole */
+#else
+ FALSE, /* isconsole */
+#endif
+ { 0 }, /* closesem */
+ { 0 }, /* xmitsem */
+ { 0 }, /* recvsem */
+ {
+ { 0 }, /* xmit.sem */
+ 0, /* xmit.head */
+ 0, /* xmit.tail */
+ CONFIG_UART0_TXBUFSIZE, /* xmit.size */
+ g_uart0txbuffer, /* xmit.buffer */
+ },
+ {
+ { 0 }, /* recv.sem */
+ 0, /* recv.head */
+ 0, /* recv.tail */
+ CONFIG_UART0_RXBUFSIZE, /* recv.size */
+ g_uart0rxbuffer, /* recv.buffer */
+ },
+ &g_uart_ops, /* ops */
+ &g_uart0priv, /* priv */
+};
+
+/* This describes the state of the DM320 uart1 port. */
+
+static struct z8_uart_s g_uart1priv =
+{
+ Z8_UART1_BASE, /* uartbase */
+ CONFIG_UART1_BAUD, /* baud */
+ FALSE, /* rxenabled */
+ FALSE, /* txenabled */
+ Z8_IRQ_UART1RX, /* rxirq */
+ Z8_IRQ_UART1TX, /* txirq */
+ CONFIG_UART1_PARITY, /* parity */
+ CONFIG_UART1_2STOP /* stopbits2 */
+};
+
+static uart_dev_t g_uart1port =
+{
+ 0, /* open_count */
+ FALSE, /* xmitwaiting */
+ FALSE, /* recvwaiting */
+#ifdef CONFIG_UART1_SERIAL_CONSOLE
+ TRUE, /* isconsole */
+#else
+ FALSE, /* isconsole */
+#endif
+ { 0 }, /* closesem */
+ { 0 }, /* xmitsem */
+ { 0 }, /* recvsem */
+ {
+ { 0 }, /* xmit.sem */
+ 0, /* xmit.head */
+ 0, /* xmit.tail */
+ CONFIG_UART1_TXBUFSIZE, /* xmit.size */
+ g_uart1txbuffer, /* xmit.buffer */
+ },
+ {
+ { 0 }, /* recv.sem */
+ 0, /* recv.head */
+ 0, /* recv.tail */
+ CONFIG_UART0_RXBUFSIZE, /* recv.size */
+ g_uart0rxbuffer, /* recv.buffer */
+ },
+ &g_uart_ops, /* ops */
+ &g_uart1priv, /* priv */
+};
+
+/* Now, which one with be tty0/console and which tty1? */
+
+#ifdef CONFIG_UART1_SERIAL_CONSOLE
+# define CONSOLE_DEV g_uart1port
+# define TTYS0_DEV g_uart1port
+# define TTYS1_DEV g_uart0port
+#else
+# define CONSOLE_DEV g_uart0port
+# define TTYS0_DEV g_uart0port
+# define TTYS1_DEV g_uart1port
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: z8_disableuartirq
+ ****************************************************************************/
+
+static ubyte z8_disableuartirq(struct uart_dev_s *dev)
+{
+ struct z8_uart_s *priv = (struct z8_uart_s*)dev->priv;
+ irqstate_t flags = irqsave();
+ ubyte state = priv->rxenabled ? STATE_RXENABLED : STATE_DISABLED | \
+ priv->txenabled ? STATE_TXENABLED : STATE_DISABLED;
+
+ z8_txint(dev, FALSE);
+ z8_rxint(dev, FALSE);
+
+ irqrestore(flags);
+ return state;
+}
+
+/****************************************************************************
+ * Name: z8_restoreuartirq
+ ****************************************************************************/
+
+static void z8_restoreuartirq(struct uart_dev_s *dev, ubyte state)
+{
+ struct z8_uart_s *priv = (struct z8_uart_s*)dev->priv;
+ irqstate_t flags = irqsave();
+
+ z8_txint(dev, (state & STATE_TXENABLED) ? TRUE : FALSE);
+ z8_rxint(dev, (state & STATE_RXENABLED) ? TRUE : FALSE);
+
+ irqrestore(flags);
+}
+
+/****************************************************************************
+ * Name: z8_consoleput
+ ****************************************************************************/
+
+static void z8_consoleput(ubyte ch)
+{
+ struct z8_uart_s *priv = (struct z8_uart_s*)CONSOLE_DEV.priv;
+ int tmp;
+
+ for (tmp = 1000 ; tmp > 0 ; tmp--)
+ {
+ if (z8_txready(&CONSOLE_DEV))
+ {
+ break;
+ }
+ }
+ putreg8(ch, priv->uartbase + Z8_UART_TXD);
+}
+
+/****************************************************************************
+ * Name: z8_setup
+ *
+ * Description:
+ * Configure the UART baud, parity, etc. This method is called the first
+ * time that the serial port is opened.
+ *
+ ****************************************************************************/
+
+static int z8_setup(struct uart_dev_s *dev)
+{
+#ifndef CONFIG_SUPPRESS_UART_CONFIG
+ struct z8_uart_s *priv = (struct z8_uart_s*)dev->priv;
+ uint32 brg;
+ ubyte ctl0;
+ ubyte ctl1;
+
+ /* Calculate and set the baud rate generation register.
+ * BRG = (freq + baud * 8)/(baud * 16)
+ */
+
+ brg = (_DEFCLK + (priv->baud << 3))/(priv->baud << 4);
+ putreg16((uint16)brg, priv->uartbase + Z8_UART_BR);
+
+ /* Configure STOP bits */
+
+ ctl0 = ctl1 = 0;
+ if (priv->stopbits2)
+ {
+ ctl0 |= Z8_UARTCTL0_STOP;
+ }
+
+ /* Configure parity */
+
+ if (priv->parity == 1)
+ {
+ ctl0 |= (Z8_UARTCTL0_PEN|Z8_UARTCTL0_PSEL);
+ }
+ else if (priv->parity == 2)
+ {
+ ctl0 |= Z8_UARTCTL0_PEN;
+ }
+
+ putreg8(ctl0, priv->uartbase + Z8_UART_CTL0);
+ putreg8(ctl1, priv->uartbase + Z8_UART_CTL1);
+
+ /* Enable UART receive (REN) and transmit (TEN) */
+
+ ctl0 |= (Z8_UARTCTL0_TEN|Z8_UARTCTL0_REN);
+ putreg8(ctl0, priv->uartbase + Z8_UART_CTL0);
+#endif
+ return OK;
+}
+
+/****************************************************************************
+ * Name: z8_shutdown
+ *
+ * Description:
+ * Disable the UART. This method is called when the serial
+ * port is closed
+ *
+ ****************************************************************************/
+
+static void z8_shutdown(struct uart_dev_s *dev)
+{
+ struct z8_uart_s *priv = (struct z8_uart_s*)dev->priv;
+ (void)z8_disableuartirq(dev);
+}
+
+/****************************************************************************
+ * Name: z8_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 z8_attach(struct uart_dev_s *dev)
+{
+ struct z8_uart_s *priv = (struct z8_uart_s*)dev->priv;
+ int ret;
+
+ /* Attach the RX IRQ */
+
+ ret = irq_attach(priv->rxirq, z8_rxinterrupt);
+ if (ret == OK)
+ {
+ /* Attach the TX IRQ */
+
+ ret = irq_attach(priv->txirq, z8_txinterrupt);
+ if (ret != OK)
+ {
+ irq_detach(priv->rxirq);
+ }
+ }
+ return ret;
+}
+
+/****************************************************************************
+ * Name: z8_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 z8_detach(struct uart_dev_s *dev)
+{
+ struct z8_uart_s *priv = (struct z8_uart_s*)dev->priv;
+ up_disable_irq(priv->rxirq);
+ up_disable_irq(priv->txirq);
+ irq_detach(priv->rxirq);
+ irq_detach(priv->txirq);
+}
+
+/****************************************************************************
+ * Name: z8_rxinterrupt
+ *
+ * Description:
+ * This is the UART interrupt handler. It will be invoked when an RX
+ * event occurs at the z8's LIN-UART.
+ *
+ ****************************************************************************/
+
+static int z8_rxinterrupt(int irq, void *context)
+{
+ struct uart_dev_s *dev = NULL;
+ struct z8_uart_s *priv;
+ ubyte status;
+
+ if (g_uart1priv.rxirq == irq)
+ {
+ dev = &g_uart1port;
+ }
+ else if (g_uart0priv.rxirq == irq)
+ {
+ dev = &g_uart0port;
+ }
+ else
+ {
+ PANIC(OSERR_INTERNAL);
+ }
+
+ priv = (struct z8_uart_s*)dev->priv;
+
+ /* Check the LIN-UART status 0 register to determine whether the source of
+ * the interrupt is error, break, or received data
+ */
+
+ status = getreg8(priv->uartbase + Z8_UART_STAT0);
+
+ /* REVISIT error and break handling */
+
+ /* Check if received data is available */
+
+ if (status & Z8_UARTSTAT0_RDA)
+ {
+ /* Handline an incoming, receive byte */
+
+ uart_recvchars(dev);
+ }
+ return OK;
+}
+
+/****************************************************************************
+ * Name: z8_txinterrupt
+ *
+ * Description:
+ * This is the UART TX interrupt handler. This interrupt handler will
+ * be invoked when the X16F LIN UART transmit data register is empty.
+ *
+ ****************************************************************************/
+
+static int z8_txinterrupt(int irq, void *context)
+{
+ struct uart_dev_s *dev = NULL;
+ struct z8_uart_s *priv;
+ ubyte status;
+
+ if (g_uart1priv.txirq == irq)
+ {
+ dev = &g_uart1port;
+ }
+ else if (g_uart0priv.txirq == irq)
+ {
+ dev = &g_uart0port;
+ }
+ else
+ {
+ PANIC(OSERR_INTERNAL);
+ }
+
+ priv = (struct z8_uart_s*)dev->priv;
+
+ /* Verify that the transmit data register is empty */
+
+ status = getreg8(priv->uartbase + Z8_UART_STAT0);
+ if (status & Z8_UARTSTAT0_TDRE)
+ {
+ /* Handle outgoing, transmit bytes */
+
+ uart_xmitchars(dev);
+ }
+ return OK;
+}
+
+/****************************************************************************
+ * Name: z8_ioctl
+ *
+ * Description:
+ * All ioctl calls will be routed through this method
+ *
+ ****************************************************************************/
+
+static int z8_ioctl(struct file *filep, int cmd, unsigned long arg)
+{
+ *get_errno_ptr() = ENOTTY;
+ return ERROR;
+}
+
+/****************************************************************************
+ * Name: z8_receive
+ *
+ * Description:
+ * Called (usually) from the interrupt level to receive one character from
+ * the UART. Error bits associated with the receipt are provided in the
+ * return 'status'.
+ *
+ ****************************************************************************/
+
+static int z8_receive(struct uart_dev_s *dev, uint32 *status)
+{
+ struct z8_uart_s *priv = (struct z8_uart_s*)dev->priv;
+ ubyte rxd;
+ ubyte stat0;
+
+ rxd = getreg8(priv->uartbase + Z8_UART_RXD);
+ stat0 = getreg8(priv->uartbase + Z8_UART_STAT0);
+ *status = (uint32)rxd | (((uint32)stat0) << 8);
+ return rxd;
+}
+
+/****************************************************************************
+ * Name: z8_rxint
+ *
+ * Description:
+ * Call to enable or disable RX interrupts
+ *
+ ****************************************************************************/
+
+static void z8_rxint(struct uart_dev_s *dev, boolean enable)
+{
+ struct z8_uart_s *priv = (struct z8_uart_s*)dev->priv;
+ irqstate_t flags = irqsave();
+
+ if (enable)
+ {
+#ifndef CONFIG_SUPPRESS_SERIAL_INTS
+ up_enable_irq(priv->rxirq);
+#endif
+ }
+ else
+ {
+ up_disable_irq(priv->rxirq);
+ }
+
+ priv->rxenabled = enable;
+ irqrestore(flags);
+}
+
+/****************************************************************************
+ * Name: z8_rxavailable
+ *
+ * Description:
+ * Return TRUE if the receive fifo is not empty
+ *
+ ****************************************************************************/
+
+static boolean z8_rxavailable(struct uart_dev_s *dev)
+{
+ struct z8_uart_s *priv = (struct z8_uart_s*)dev->priv;
+ return ((getreg8(priv->uartbase + Z8_UART_STAT0) & Z8_UARTSTAT0_RDA) != 0);
+}
+
+/****************************************************************************
+ * Name: z8_send
+ *
+ * Description:
+ * This method will send one byte on the UART
+ *
+ ****************************************************************************/
+
+static void z8_send(struct uart_dev_s *dev, int ch)
+{
+ struct z8_uart_s *priv = (struct z8_uart_s*)dev->priv;
+ putreg8(ch, priv->uartbase + Z8_UART_TXD);
+}
+
+/****************************************************************************
+ * Name: z8_txint
+ *
+ * Description:
+ * Call to enable or disable TX interrupts
+ *
+ ****************************************************************************/
+
+static void z8_txint(struct uart_dev_s *dev, boolean enable)
+{
+ struct z8_uart_s *priv = (struct z8_uart_s*)dev->priv;
+ irqstate_t flags = irqsave();
+
+ if (enable)
+ {
+#ifndef CONFIG_SUPPRESS_SERIAL_INTS
+ up_enable_irq(priv->txirq);
+#endif
+ }
+ else
+ {
+ up_disable_irq(priv->txirq);
+ }
+
+ priv->txenabled = enable;
+ irqrestore(flags);
+}
+
+/****************************************************************************
+ * Name: z8_txready
+ *
+ * Description:
+ * Return TRUE if the tranmsit fifo is not full
+ *
+ ****************************************************************************/
+
+static boolean z8_txready(struct uart_dev_s *dev)
+{
+ struct z8_uart_s *priv = (struct z8_uart_s*)dev->priv;
+ return ((getreg8(priv->uartbase + Z8_UART_STAT0) & Z8_UARTSTAT0_TDRE) != 0);
+}
+
+/****************************************************************************
+ * Name: z8_txempty
+ *
+ * Description:
+ * Return TRUE if the transmit fifo is empty
+ *
+ ****************************************************************************/
+
+static boolean z8_txempty(struct uart_dev_s *dev)
+{
+ struct z8_uart_s *priv = (struct z8_uart_s*)dev->priv;
+ return ((getreg8(priv->uartbase + Z8_UART_STAT0) & Z8_UARTSTAT0_TXE) != 0);
+}
+
+/****************************************************************************
+ * Public Funtions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_earlyserialinit
+ *
+ * Description:
+ * Performs the low level UART initialization early in
+ * debug so that the serial console will be available
+ * during bootup. This must be called before z8_serialinit.
+ *
+ ****************************************************************************/
+
+void up_earlyserialinit(void)
+{
+ (void)z8_disableuartirq(&TTYS0_DEV);
+ (void)z8_disableuartirq(&TTYS1_DEV);
+
+ CONSOLE_DEV.isconsole = TRUE;
+ z8_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)
+{
+ (void)uart_register("/dev/console", &CONSOLE_DEV);
+ (void)uart_register("/dev/ttyS0", &TTYS0_DEV);
+ (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)
+{
+ ubyte state;
+
+ /* Keep interrupts disabled so that we do not interfere with normal
+ * driver operation
+ */
+
+ state = z8_disableuartirq(&CONSOLE_DEV);
+
+ /* Check for LF */
+
+ if (ch == '\n')
+ {
+ /* Add CR before LF */
+
+ z8_consoleput('\r');
+ }
+
+ /* Output the character */
+
+ z8_consoleput((ubyte)ch);
+
+ /* It is important to restore the TX interrupt while the send is pending.
+ * otherwise, TRDE interrupts can be lost since they do not pend after the
+ * TRDE false->true transition.
+ */
+
+ z8_restoreuartirq(&CONSOLE_DEV, state);
+ return ch;
+}
+
+#else /* CONFIG_USE_SERIALDRIVER */
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#ifdef CONFIG_UART1_SERIAL_CONSOLE
+# define z8_contrde() \
+ ((getreg8(*(Z8_UART1_BASE+Z8_UART_STAT0)) & Z8_UARTSTAT0_TDRE) != 0)
+# define z8_contxd(ch) \
+ putreg8((ubyte)(ch), *(Z8_UART1_BASE+Z8_UART_TXD))
+#else
+# define z8_contrde() \
+ ((getreg8(*(Z8_UART0_BASE+Z8_UART_STAT0)) & Z8_UARTSTAT0_TDRE) != 0)
+# define z8_contxd(ch) \
+ putreg8((ubyte)(ch), *(Z8_UART0_BASE+Z8_UART_TXD))
+#endif
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: z8_putc
+ ****************************************************************************/
+
+static void z8_putc(int ch)
+{
+ int tmp;
+ for (tmp = 1000 ; tmp > 0 && !z8_contrde(); tmp--);
+ z8_contxd(ch);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_putc
+ ****************************************************************************/
+
+int up_putc(int ch)
+{
+ /* Check for LF */
+
+ if (ch == '\n')
+ {
+ /* Output CR before LF */
+
+ z8_putc('\r');
+ }
+
+ /* Output character */
+
+ z8_putc(ch);
+ return ch;
+}
+
+#endif /* CONFIG_USE_SERIALDRIVER */