summaryrefslogtreecommitdiff
path: root/nuttx/arch/z80
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/arch/z80')
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_lowuart.c110
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_serial.c79
2 files changed, 163 insertions, 26 deletions
diff --git a/nuttx/arch/z80/src/ez80/ez80_lowuart.c b/nuttx/arch/z80/src/ez80/ez80_lowuart.c
index ebf1428d4..32d08e875 100644
--- a/nuttx/arch/z80/src/ez80/ez80_lowuart.c
+++ b/nuttx/arch/z80/src/ez80/ez80_lowuart.c
@@ -55,9 +55,39 @@
* Private Definitions
****************************************************************************/
-/* The system clock frequency is defined in the linkcmd file */
+/* The system clock frequency is defined in the board.h file */
-#ifdef CONFIG_UART0_SERIAL_CONSOLE
+/* Is there any serial support? This might be the case if the board does
+ * not have serial ports but supports stdout through, say, an LCD.
+ */
+
+#if defined(CONFIG_UART0_DISABLE) || defined(CONFIG_UART1_DISABLE)
+# define HAVE_SERIAL
+#else
+# undef HAVE_SERIAL
+#endif
+
+/* Is one of the serial ports a console? */
+
+#if defined(CONFIG_UART0_SERIAL_CONSOLE) && !defined(CONFIG_UART0_DISABLE)
+# define HAVE_SERIALCONSOLE 1
+# undef CONFIG_UART1_SERIAL_CONSOLE
+#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && !defined(CONFIG_UART1_DISABLE)
+# define HAVE_SERIALCONSOLE 1
+# undef CONFIG_UART0_SERIAL_CONSOLE
+#else
+# warning "No console is defined"
+# if defined(CONFIG_UART0_SERIAL_CONSOLE) || defined(CONFIG_UART1_SERIAL_CONSOLE)
+# error "A serial console selected, but corresponding UART not enabled"
+# endif
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef HAVE_SERIALCONSOLE
+#endif
+
+/* Select UART parameters for the selected console */
+
+#if defined(CONFIG_UART0_SERIAL_CONSOLE)
# define ez80_inp(offs) inp((EZ80_UART0_BASE+(offs)))
# define ez80_outp(offs,val) outp((EZ80_UART0_BASE+(offs)), (val))
# define CONFIG_UART_BAUD CONFIG_UART0_BAUD
@@ -78,7 +108,7 @@
# else
# define CONFIG_UART_PARITY 0
# endif
-#else
+#elif defined(CONFIG_UART0_SERIAL_CONSOLE)
# define ez80_inp(offs) inp((EZ80_UART1_BASE+(offs)))
# define ez80_outp(offs.val) outp((EZ80_UART1_BASE+(offs)), (val))
# define CONFIG_UART_BAUD CONFIG_UART1_BAUD
@@ -109,7 +139,7 @@
* Private Functions
****************************************************************************/
-#ifndef CONFIG_SUPPRESS_UART_CONFIG
+#if defined(HAVE_SERIALCONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
static void ez80_setbaud(void)
{
uint32 brg_divisor;
@@ -139,7 +169,7 @@ static void ez80_setbaud(void)
lctl &= ~EZ80_UARTLCTL_DLAB;
ez80_outp(EZ80_UART_LCTL, lctl);
}
-#endif /* CONFIG_SUPPRESS_UART_CONFIG */
+#endif /* HAVE_SERIALCONSOLE && !CONFIG_SUPPRESS_UART_CONFIG */
/****************************************************************************
* Public Functions
@@ -151,14 +181,49 @@ static void ez80_setbaud(void)
void up_lowuartinit(void)
{
-#ifndef CONFIG_SUPPRESS_UART_CONFIG
- ubyte reg;
+#ifdef HAVE_SERIAL
+ ubyte regval;
+
+ /* Configure pins for usage of UARTs (whether or not we have a console) */
+#ifndef CONFIG_UART0_DISABLE
+ /* Set Port D, pins 0 and 1 for their alternate function (Mode 7) to enable UART0 */
+
+ regval = inp(EZ80_PD_DDR);
+ regval |= 3;
+ outp(EZ80_PD_DDR, regval);
+
+ regval = inp(EZ80_PD_ALT1);
+ regval &= ~3;
+ outp(EZ80_PD_ALT1, regval);
+
+ regval = inp(EZ80_PD_ALT2);
+ regval |= 3;
+ outp(EZ80_PD_ALT2, regval);
+#endif
+
+#ifndef CONFIG_UART1_DISABLE
+ /* Set Port C, pins 0 and 1 for their alternate function (Mode 7) to enable UART1 */
+
+ regval = inp(EZ80_PC_DDR);
+ regval |= 3;
+ outp(EZ80_PC_DDR, regval);
+
+ regval = inp(EZ80_PC_ALT1);
+ regval &= ~3;
+ outp(EZ80_PC_ALT1, regval);
+
+ regval = inp(EZ80_PC_ALT2);
+ regval |= 3;
+ outp(EZ80_PC_ALT2, regval);
+#endif
+
+#if defined(HAVE_SERIALCONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
/* Disable interrupts from the UART */
- reg = ez80_inp(EZ80_UART_IER);
- reg &= ~EZ80_UARTEIR_INTMASK;
- ez80_outp(EZ80_UART_IER, reg);
+ regval = ez80_inp(EZ80_UART_IER);
+ regval &= ~EZ80_UARTEIR_INTMASK;
+ ez80_outp(EZ80_UART_IER, regval);
/* Set the baud rate */
@@ -167,22 +232,25 @@ void up_lowuartinit(void)
/* Set the character properties */
- reg = ez80_inp(EZ80_UART_LCTL);
- reg &= ~EZ80_UARTLCTL_MASK;
- reg |= (CONFIG_UART_BITS | CONFIG_UART_2STOP | CONFIG_UART_PARITY);
- ez80_outp(EZ80_UART_LCTL, reg);
+ regval = ez80_inp(EZ80_UART_LCTL);
+ regval &= ~EZ80_UARTLCTL_MASK;
+ regval |= (CONFIG_UART_BITS | CONFIG_UART_2STOP | CONFIG_UART_PARITY);
+ ez80_outp(EZ80_UART_LCTL, regval);
/* Enable and flush the receive FIFO */
- reg = EZ80_UARTFCTL_FIFOEN;
- ez80_outp(EZ80_UART_FCTL, reg);
- reg |= (EZ80_UARTFCTL_CLRTxF|EZ80_UARTFCTL_CLRRxF);
- ez80_outp(EZ80_UART_FCTL, reg);
+ regval = EZ80_UARTFCTL_FIFOEN;
+ ez80_outp(EZ80_UART_FCTL, regval);
+ regval |= (EZ80_UARTFCTL_CLRTxF|EZ80_UARTFCTL_CLRRxF);
+ ez80_outp(EZ80_UART_FCTL, regval);
/* Set the receive trigger level to 1 */
- reg |= EZ80_UARTTRIG_1;
- ez80_outp(EZ80_UART_FCTL, reg);
-#endif /* CONFIG_SUPPRESS_UART_CONFIG */
+ regval |= EZ80_UARTTRIG_1;
+ ez80_outp(EZ80_UART_FCTL, regval);
+
+#endif /* HAVE_SERIALCONSOLE && !CONFIG_SUPPRESS_UART_CONFIG */
+#endif /* HAVE_SERIAL */
}
+
#endif /* CONFIG_USE_LOWUARTINIT */
diff --git a/nuttx/arch/z80/src/ez80/ez80_serial.c b/nuttx/arch/z80/src/ez80/ez80_serial.c
index face96e42..139dd6939 100644
--- a/nuttx/arch/z80/src/ez80/ez80_serial.c
+++ b/nuttx/arch/z80/src/ez80/ez80_serial.c
@@ -116,13 +116,18 @@ struct uart_ops_s g_uart_ops =
/* I/O buffers */
+#ifndef CONFIG_UART0_DISABLE
static char g_uart0rxbuffer[CONFIG_UART0_RXBUFSIZE];
static char g_uart0txbuffer[CONFIG_UART0_TXBUFSIZE];
+#endif
+#ifndef CONFIG_UART1_DISABLE
static char g_uart1rxbuffer[CONFIG_UART1_RXBUFSIZE];
static char g_uart1txbuffer[CONFIG_UART1_TXBUFSIZE];
+#endif
/* This describes the state of the UART0 port. */
+#ifndef CONFIG_UART0_DISABLE
static struct ez80_dev_s g_uart0priv =
{
EZ80_UART0_BASE, /* uartbase */
@@ -163,9 +168,11 @@ static uart_dev_t g_uart0port =
&g_uart_ops, /* ops */
&g_uart0priv, /* priv */
};
+#endif
/* This describes the state of the UART1 port. */
+#ifndef CONFIG_UART1_DISABLE
static struct ez80_dev_s g_uart1priv =
{
EZ80_UART1_BASE, /* uartbase */
@@ -206,17 +213,29 @@ static uart_dev_t g_uart1port =
&g_uart_ops, /* ops */
&g_uart1priv, /* priv */
};
+#endif
/* Now, which one with be tty0/console and which tty1? */
-#ifdef CONFIG_UART0_SERIAL_CONSOLE
+#if defined(CONFIG_UART0_SERIAL_CONSOLE) && !defined(CONFIG_DISABLE_UART0)
# define CONSOLE_DEV g_uart0port
# define TTYS0_DEV g_uart0port
-# define TTYS1_DEV g_uart1port
-#else
+# if !defined(CONFIG_UART1_DISABLE)
+# define TTYS1_DEV g_uart1port
+# endif
+#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && !defined(CONFIG_DISABLE_UART1)
# define CONSOLE_DEV g_uart1port
# define TTYS0_DEV g_uart1port
-# define TTYS1_DEV g_uart0port
+# if !defined(CONFIG_UART0_DISABLE)
+# define TTYS1_DEV g_uart0port
+# endif
+#elif !defined(CONFIG_DISABLE_UART0)
+# define TTYS0_DEV g_uart0port
+# if !defined(CONFIG_UART1_DISABLE)
+# define TTYS1_DEV g_uart1port
+# endif
+#elif !defined(CONFIG_DISABLE_UART0)
+# define TTYS0_DEV g_uart1port
#endif
/****************************************************************************
@@ -389,7 +408,7 @@ static int ez80_setup(struct uart_dev_s *dev)
static void ez80_shutdown(struct uart_dev_s *dev)
{
- struct ez80_dev_s *priv = (struct ez80_dev_s*)CONSOLE_DEV.priv;
+ struct ez80_dev_s *priv = (struct ez80_dev_s*)dev->priv;
ez80_disableuartint(priv);
}
@@ -644,11 +663,55 @@ static boolean ez80_txempty(struct uart_dev_s *dev)
void up_earlyserialinit(void)
{
+ ubyte regval;
+
+ /* Make sure that all UART interrupts are disabled */
+
ez80_disableuartint(TTYS0_DEV.priv);
+#ifdef TTYS1DEV
ez80_disableuartint(TTYS1_DEV.priv);
+#endif
+
+ /* Configure pins for usage of UARTs */
+
+#ifndef CONFIG_UART0_DISABLE
+ /* Set Port D, pins 0 and 1 for their alternate function (Mode 7) to enable UART0 */
+ regval = inp(EZ80_PD_DDR);
+ regval |= 3;
+ outp(EZ80_PD_DDR, regval);
+
+ regval = inp(EZ80_PD_ALT1);
+ regval &= ~3;
+ outp(EZ80_PD_ALT1, regval);
+
+ regval = inp(EZ80_PD_ALT2);
+ regval |= 3;
+ outp(EZ80_PD_ALT2, regval);
+#endif
+
+#ifndef CONFIG_UART1_DISABLE
+ /* Set Port C, pins 0 and 1 for their alternate function (Mode 7) to enable UART1 */
+
+ regval = inp(EZ80_PC_DDR);
+ regval |= 3;
+ outp(EZ80_PC_DDR, regval);
+
+ regval = inp(EZ80_PC_ALT1);
+ regval &= ~3;
+ outp(EZ80_PC_ALT1, regval);
+
+ regval = inp(EZ80_PC_ALT2);
+ regval |= 3;
+ outp(EZ80_PC_ALT2, regval);
+#endif
+
+ /* If there is a console, then configure the console now */
+
+#ifdef CONSOLE_DEV
CONSOLE_DEV.isconsole = TRUE;
ez80_setup(&CONSOLE_DEV);
+#endif
}
/****************************************************************************
@@ -662,9 +725,13 @@ void up_earlyserialinit(void)
void up_serialinit(void)
{
+#ifdef CONSOLE_DEV
(void)uart_register("/dev/console", &CONSOLE_DEV);
+#endif
(void)uart_register("/dev/ttyS0", &TTYS0_DEV);
+#ifdef TTYS1DEV
(void)uart_register("/dev/ttyS1", &TTYS1_DEV);
+#endif
}
/****************************************************************************
@@ -678,6 +745,7 @@ void up_serialinit(void)
int up_putc(int ch)
{
+#ifdef CONSOLE_DEV
struct ez80_dev_s *priv = (struct ez80_dev_s*)CONSOLE_DEV.priv;
ubyte ier = ez80_serialin(priv, EZ80_UART_IER);
@@ -703,6 +771,7 @@ int up_putc(int ch)
ez80_waittxready(priv);
ez80_restoreuartint(priv, ier);
return ch;
+#endif
}
#else /* CONFIG_USE_SERIALDRIVER */