summaryrefslogtreecommitdiff
path: root/nuttx/arch/z80/src/z180
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-12-14 19:15:07 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-12-14 19:15:07 +0000
commit862ecc12715cd262c761451634583bb59e4e5157 (patch)
tree3a3c3569a70963255e41023e836b4e5ecada1bed /nuttx/arch/z80/src/z180
parent9e96b774dc77f51d965a8b2b9cf3d9d72637aa02 (diff)
downloadpx4-nuttx-862ecc12715cd262c761451634583bb59e4e5157.tar.gz
px4-nuttx-862ecc12715cd262c761451634583bb59e4e5157.tar.bz2
px4-nuttx-862ecc12715cd262c761451634583bb59e4e5157.zip
More z180 serial logic
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5437 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/z80/src/z180')
-rw-r--r--nuttx/arch/z80/src/z180/Kconfig16
-rw-r--r--nuttx/arch/z80/src/z180/Make.defs4
-rw-r--r--nuttx/arch/z80/src/z180/z180_config.h27
-rw-r--r--nuttx/arch/z80/src/z180/z180_iomap.h10
-rw-r--r--nuttx/arch/z80/src/z180/z180_lowscc.c61
-rw-r--r--nuttx/arch/z80/src/z180/z180_lowserial.c112
-rw-r--r--nuttx/arch/z80/src/z180/z180_lowuart.c148
-rw-r--r--nuttx/arch/z80/src/z180/z180_scc.c78
-rw-r--r--nuttx/arch/z80/src/z180/z180_serial.h109
9 files changed, 461 insertions, 104 deletions
diff --git a/nuttx/arch/z80/src/z180/Kconfig b/nuttx/arch/z80/src/z180/Kconfig
index d00fa643b..34297f7a7 100644
--- a/nuttx/arch/z80/src/z180/Kconfig
+++ b/nuttx/arch/z80/src/z180/Kconfig
@@ -156,14 +156,14 @@ config Z180_UART1
config Z180_SCC
bool "SCC"
default n
- depends on ARCH_CHIP_Z8L181
+ depends on ARCH_CHIP_Z80181 || ARCH_CHIP_Z8L181
---help---
Select to enable a serial port on the SCC
config Z180_ESCCA
bool "ESCC Channel A"
default n
- depends on ARCH_CHIP_Z8L182 && !Z180_PORTC
+ depends on ARCH_CHIP_Z80182 || ARCH_CHIP_Z8L182
---help---
Select to enable a serial port on ESCC Channel A. Not available
if port C is selected.
@@ -171,7 +171,7 @@ config Z180_ESCCA
config Z180_ESCCB
bool "ESCC Channel B"
default n
- depends on ARCH_CHIP_Z8L182 && !Z180_MIMIC
+ depends on (ARCH_CHIP_Z80182 || ARCH_CHIP_Z8L182) && !Z180_MIMIC
---help---
Select to enable a serial port on ESCC Channel B
@@ -196,14 +196,14 @@ config Z180_TMR1
config Z180_PORTA
bool "PORT A"
default n
- depends on ARCH_CHIP_Z8L181 || ARCH_CHIP_Z8L182 || !Z180_CTC
+ depends on (ARCH_CHIP_Z80181 || ARCH_CHIP_Z8L181 || ARCH_CHIP_Z80182 || ARCH_CHIP_Z8L182) && !Z180_CTC
---help---
Select to enable a Port A (called PIA1 on the Z8x181)
config Z180_PORTB
bool "PORT B"
default n
- depends on ARCH_CHIP_Z8L181 || ARCH_CHIP_Z8L182
+ depends on ARCH_CHIP_Z80181 || ARCH_CHIP_Z8L181 || ARCH_CHIP_Z80182 || ARCH_CHIP_Z8L182
---help---
Select to enable a Port B (called PIA2 on the Z8x181). On the Z8x182,
Bits 5-7 will not be available if ASCI channel 1 is used; Bits 0-4 will
@@ -212,21 +212,21 @@ config Z180_PORTB
config Z180_PORTC
bool "PORT C"
default n
- depends on ARCH_CHIP_Z8L182 && !Z180_ESCCA
+ depends on (ARCH_CHIP_Z80182 || ARCH_CHIP_Z8L182) && !Z180_ESCCA
---help---
Select to enable a Port C. Not available if ESCC channel A is selected.
config Z180_CTC
bool "CTC"
default n
- depends on ARCH_CHIP_Z8L181
+ depends on ARCH_CHIP_Z80181 || ARCH_CHIP_Z8L181
---help---
Select to enable the Counter/Timer (CTC)
config Z180_MIMIC
bool "16550 MIMIC"
default n
- depends on ARCH_CHIP_Z8L182 && !Z180_ESCCB
+ depends on ARCH_CHIP_Z80182 || ARCH_CHIP_Z8L182
---help---
Select to enable the 16550 MIMIC
diff --git a/nuttx/arch/z80/src/z180/Make.defs b/nuttx/arch/z80/src/z180/Make.defs
index a50c67f39..7b495e693 100644
--- a/nuttx/arch/z80/src/z180/Make.defs
+++ b/nuttx/arch/z80/src/z180/Make.defs
@@ -58,5 +58,5 @@ CHIP_ASRCS += z180_vectors.asm
endif
CHIP_CSRCS = z180_copystate.c z180_initialstate.c z180_io.c z180_irq.c
-CHIP_CSRCS += z180_modifiyreg8.c z180_mmu.c z180_registerdump.c
-CHIP_CSRCS += z180_schedulesigaction.c z180_sigdeliver.c
+CHIP_CSRCS += z180_lowscc.c z180_lowserial.c z180_modifiyreg8.c z180_mmu.c
+CHIP_CSRCS += z180_registerdump.c z180_schedulesigaction.c z180_sigdeliver.c
diff --git a/nuttx/arch/z80/src/z180/z180_config.h b/nuttx/arch/z80/src/z180/z180_config.h
index 9f5bb9589..65815c21b 100644
--- a/nuttx/arch/z80/src/z180/z180_config.h
+++ b/nuttx/arch/z80/src/z180/z180_config.h
@@ -68,10 +68,18 @@
/* Are any UARTs enabled? */
+#undef HAVE_UART
+#undef HAVE_SCC
#undef HAVE_SERIAL
-#if defined(CONFIG_Z180_UART0) || defined(CONFIG_Z180_UART1) || \
- defined(CONFIG_Z180_SCC) || defined(CONFIG_Z180_ESCCA) || \
+
+#if defined(CONFIG_Z180_UART0) || defined(CONFIG_Z180_UART1)
+# define HAVE_UART 1
+# define HAVE_SERIAL 1
+#endif
+
+#if defined(CONFIG_Z180_SCC) || defined(CONFIG_Z180_ESCCA) || \
defined(CONFIG_Z180_ESCCB)
+# define HAVE_SCC 1
# define HAVE_SERIAL 1
#endif
@@ -101,28 +109,39 @@
/* Is there a serial console? There should be at most one defined. */
+#undef HAVE_UART_CONSOLE
+#undef HAVE_SCC_CONSOLE
+#undef HAVE_SERIAL_CONSOLE
+
#if defined(CONFIG_Z180_UART0_SERIAL_CONSOLE)
# undef CONFIG_Z180_UART1_SERIAL_CONSOLE
# undef CONFIG_Z180_SCC_SERIAL_CONSOLE
# undef CONFIG_Z180_ESCCA_SERIAL_CONSOLE
# undef CONFIG_Z180_ESCCB_SERIAL_CONSOLE
+# define HAVE_UART_CONSOLE 1
# define HAVE_SERIAL_CONSOLE 1
+
#elif defined(CONFIG_Z180_UART1_SERIAL_CONSOLE)
# undef CONFIG_Z180_SCC_SERIAL_CONSOLE
# undef CONFIG_Z180_ESCCA_SERIAL_CONSOLE
# undef CONFIG_Z180_ESCCB_SERIAL_CONSOLE
+# define HAVE_UART_CONSOLE 1
# define HAVE_SERIAL_CONSOLE 1
+
#elif defined(CONFIG_Z180_ESCC_SERIAL_CONSOLE)
# undef CONFIG_Z180_ESCCA_SERIAL_CONSOLE
# undef CONFIG_Z180_ESCCB_SERIAL_CONSOLE
+# define HAVE_SCC_CONSOLE 1
# define HAVE_SERIAL_CONSOLE 1
+
#elif defined(CONFIG_Z180_ESCCA_SERIAL_CONSOLE)
# undef CONFIG_Z180_ESCCB_SERIAL_CONSOLE
+# define HAVE_SCC_CONSOLE 1
# define HAVE_SERIAL_CONSOLE 1
+
#elif defined(CONFIG_Z180_ESCCB_SERIAL_CONSOLE)
+# define HAVE_SCC_CONSOLE 1
# define HAVE_SERIAL_CONSOLE 1
-#else
-# undef HAVE_SERIAL_CONSOLE
#endif
/************************************************************************************
diff --git a/nuttx/arch/z80/src/z180/z180_iomap.h b/nuttx/arch/z80/src/z180/z180_iomap.h
index c429fe7d3..8717ae814 100644
--- a/nuttx/arch/z80/src/z180/z180_iomap.h
+++ b/nuttx/arch/z80/src/z180/z180_iomap.h
@@ -629,13 +629,13 @@
/* RR0: Transmit and Receive buffer status and external status */
-#define RR0_BA (0x80) /* Bit 7: Break/abort*/
-#define RR0_TXUEOM (0x40) /* Bit 6: Tx Underrun/EOM*/
+#define RR0_BA (0x80) /* Bit 7: Break/abort */
+#define RR0_TXUEOM (0x40) /* Bit 6: Tx Underrun/EOM */
#define RR0_CTS (0x20) /* Bit 5: CTS */
-#define RR0_SH (0x10) /* Bit4: Sync/Hunt */
+#define RR0_SH (0x10) /* Bit 4: Sync/Hunt */
#define RR0_DCD (0x08) /* Bit 3: DCD */
#define RR0_TXBE (0x04) /* Bit 2: Tx Buffer Empty */
-#define RR0_ZC (0x02) /* Bit 1: Zero Count*/
+#define RR0_ZC (0x02) /* Bit 1: Zero Count */
#define RR0_RXA (0x01) /* Bit 0: Rx Character Available */
/* RR1: Special Receive Condition status */
@@ -647,7 +647,7 @@
#define RR0_RES0 (0x08) /* Bit 3: Residue Code 0 */
#define RR0_RES1 (0x04) /* Bit 2: Residue Code 1 */
#define RR0_RES2 (0x02) /* Bit 1: Residue Code 2 */
-#define RR0_ALL (0x01) /* Bit 0: All Sent*/
+#define RR0_ALL (0x01) /* Bit 0: All Sent */
/* RR2: Interrupt vector (modified if VIS Bit in WR9 is set) -- 8-bit vector value */
diff --git a/nuttx/arch/z80/src/z180/z180_lowscc.c b/nuttx/arch/z80/src/z180/z180_lowscc.c
index b44414d55..e5d5171c1 100644
--- a/nuttx/arch/z80/src/z180/z180_lowscc.c
+++ b/nuttx/arch/z80/src/z180/z180_lowscc.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * arch/z80/src/z180/z180_loweruart.c
+ * arch/z80/src/z180/z180_lowscc.c
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -48,9 +48,9 @@
#include "chip/chip.h"
#include "common/up_internal.h"
-#include "z80_config.h"
+#include "z180_config.h"
-#ifdef USE_LOWUARTINIT
+#if defined(USE_LOWSERIALINIT) && defined(HAVE_SCC)
/****************************************************************************
* Private Definitions
@@ -66,7 +66,7 @@
# define CONSOLE_2STOP CONFIG_Z180_SCC_2STOP
# define CONSOLE_PARITY CONFIG_Z180_SCC_PARITY
-#elif defined(CONFIG_Z180_ESCCB_SERIAL_CONSOLE)
+#elif defined(CONFIG_Z180_ESCCA_SERIAL_CONSOLE)
# define CONSOLE_CR Z182_ESCCA_CR
# define CONSOLE_DR Z182_ESCCA_DR
# define CONSOLE_BAUD CONFIG_Z180_ESCCA_BAUD
@@ -90,24 +90,34 @@
* Private Functions
****************************************************************************/
-#if defined(HAVE_SERIAL_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
-static void z180_setbaud(void)
+/****************************************************************************
+ * Name: z180_scc_setbaud
+ *
+ * Description:
+ *
+ ****************************************************************************/
+
+#if defined(HAVE_SCC_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
+static void z180_scc_setbaud(void)
{
#warning "Missing logic"
}
-#endif /* HAVE_SERIAL_CONSOLE && !CONFIG_SUPPRESS_UART_CONFIG */
+#endif /* HAVE_SCC_CONSOLE && !CONFIG_SUPPRESS_UART_CONFIG */
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
- * Name: up_lowuartinit
+ * Name: z180_scc_lowinit
+ *
+ * Description:
+ * Called early in the boot sequence to initialize the [E]SCC channel(s)
+ *
****************************************************************************/
-void up_lowuartinit(void)
+void z180_scc_lowinit(void)
{
-#ifdef HAVE_SERIAL
#warning "Missing logic"
/* Configure for usage of {E]SCC channels (whether or not we have a console) */
@@ -126,10 +136,33 @@ void up_lowuartinit(void)
/* Configure the console for immediate usage */
-#if defined(HAVE_SERIAL_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
+#if defined(HAVE_SCC_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
#warning "Missing logic"
-#endif /* HAVE_SERIAL_CONSOLE && !CONFIG_SUPPRESS_UART_CONFIG */
-#endif /* HAVE_SERIAL */
+#endif /* HAVE_SCC_CONSOLE && !CONFIG_SUPPRESS_UART_CONFIG */
}
-#endif /* USE_LOWUARTINIT */
+/****************************************************************************
+ * Name: z180_putc
+ *
+ * Description:
+ * Low-level character output
+ *
+ ****************************************************************************/
+
+#ifdef HAVE_SCC_CONSOLE
+void z180_putc(uint8_t ch) __naked
+{
+ __asm
+txbe:
+ in0 a,(CONSOLE_CR) ; Read RR0
+ bit 2, a ; Bit 2, Tx buffer empty?
+ jr z, txbe ; No, wait until the Tx buffer is empty
+
+ ld a, 4(ix) ; Character to output
+ out (CONSOLE_DR), a ; Send it
+ ret
+ __endasm;
+}
+#endif
+
+#endif /* USE_LOWSERIALINIT && HAVE_SCC*/
diff --git a/nuttx/arch/z80/src/z180/z180_lowserial.c b/nuttx/arch/z80/src/z180/z180_lowserial.c
new file mode 100644
index 000000000..5382c56cd
--- /dev/null
+++ b/nuttx/arch/z80/src/z180/z180_lowserial.c
@@ -0,0 +1,112 @@
+/****************************************************************************
+ * arch/z80/src/z180/z180_lowserial.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 "common/up_internal.h"
+
+#include "z180_config.h"
+#include "z180_serial.h"
+
+#ifdef HAVE_SERIAL
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_lowserialinit
+ *
+ * Description:
+ * Called early in the boot sequence to initialize the serial ports
+ *
+ ****************************************************************************/
+
+#ifdef USE_LOWSERIALINIT
+void up_lowserialinit(void)
+{
+ /* Initialize UART and [E]SCC serial devices */
+
+ z180_uart_lowinit();
+ z180_scc_lowinit();
+}
+#endif
+
+/****************************************************************************
+ * Name: up_putc/up_lowputc
+ *
+ * Description:
+ * Low-level console output
+ *
+ ****************************************************************************/
+
+#ifdef USE_SERIALDRIVER
+int up_lowputc(int ch)
+#else
+int up_putc(int ch)
+#endif
+{
+ /* Check for LF */
+
+ if (ch == '\n')
+ {
+ /* Output CR before LF */
+
+ z180_putc('\r');
+ }
+
+ /* Output the character */
+
+ z180_putc(ch);
+ return ch;
+}
+
+#endif /* HAVE_SERIAL */
diff --git a/nuttx/arch/z80/src/z180/z180_lowuart.c b/nuttx/arch/z80/src/z180/z180_lowuart.c
new file mode 100644
index 000000000..493a793cd
--- /dev/null
+++ b/nuttx/arch/z80/src/z180/z180_lowuart.c
@@ -0,0 +1,148 @@
+/****************************************************************************
+ * arch/z80/src/z180/z180_lowuart.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 <stdint.h>
+#include <string.h>
+
+#include <arch/io.h>
+#include <nuttx/arch.h>
+#include <nuttx/sched.h>
+
+#include "chip/chip.h"
+#include "common/up_internal.h"
+#include "z180_config.h"
+
+#if defined(USE_LOWSERIALINIT) && defined(HAVE_UART)
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/* Select UART parameters for the selected console */
+
+#if defined(CONFIG_Z180_UART0_SERIAL_CONSOLE)
+# define CONSOLE_CR Z181_UART0_CR
+# define CONSOLE_DR Z181_UART0_DR
+# define CONSOLE_BAUD CONFIG_Z180_UART0_BAUD
+# define CONSOLE_BITS CONFIG_Z180_UART0_BITS
+# define CONSOLE_2STOP CONFIG_Z180_UART0_2STOP
+# define CONSOLE_PARITY CONFIG_Z180_UART0_PARITY
+
+#elif defined(CONFIG_Z180_UART1_SERIAL_CONSOLE)
+# define CONSOLE_CR Z182_UART1_CR
+# define CONSOLE_DR Z182_UART1_DR
+# define CONSOLE_BAUD CONFIG_Z180_UART1_BAUD
+# define CONSOLE_BITS CONFIG_Z180_UART1_BITS
+# define CONSOLE_2STOP CONFIG_Z180_UART1_2STOP
+# define CONSOLE_PARITY CONFIG_Z180_UART1_PARITY
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: z180_uart_setbaud
+ *
+ * Description:
+ *
+ ****************************************************************************/
+
+#if defined(HAVE_UART_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
+static void z180_uart_setbaud(void)
+{
+#warning "Missing logic"
+}
+#endif /* HAVE_UART_CONSOLE && !CONFIG_SUPPRESS_UART_CONFIG */
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: z180_uart_lowinit
+ *
+ * Description:
+ * Called early in the boot sequence to initialize the [E]SCC channel(s)
+ *
+ ****************************************************************************/
+
+void z180_uart_lowinit(void)
+{
+#warning "Missing logic"
+
+ /* Configure for usage of {E]SCC channels (whether or not we have a console) */
+
+#ifdef CONFIG_Z180_UART0
+#warning "Missing logic"
+#endif
+
+#ifdef CONFIG_Z180_UART1
+#warning "Missing logic"
+#endif
+
+ /* Configure the console for immediate usage */
+
+#if defined(HAVE_UART_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
+#warning "Missing logic"
+#endif /* HAVE_UART0_CONSOLE && !CONFIG_SUPPRESS_UART_CONFIG */
+}
+
+/****************************************************************************
+ * Name: z180_putc
+ *
+ * Description:
+ * Low-level character output
+ *
+ ****************************************************************************/
+
+#ifdef HAVE_UART_CONSOLE
+void z180_putc(uint8_t ch)
+{
+#warning "Missing logic"
+}
+#endif
+
+#endif /* USE_LOWSERIALINIT && HAVE_UART*/
diff --git a/nuttx/arch/z80/src/z180/z180_scc.c b/nuttx/arch/z80/src/z180/z180_scc.c
index b15183bda..2ac08f7f1 100644
--- a/nuttx/arch/z80/src/z180/z180_scc.c
+++ b/nuttx/arch/z80/src/z180/z180_scc.c
@@ -58,6 +58,9 @@
#include "os_internal.h"
#include "up_internal.h"
+#include "z180_config.h"
+#include "z180_serial.h"
+
#ifdef USE_SERIALDRIVER
/****************************************************************************
@@ -619,79 +622,12 @@ void up_serialinit(void)
int up_putc(int ch)
{
#ifdef CONSOLE_DEV
-#warning "Missing logic"
- z180_disableuartint(priv);
-
- /* Check for LF */
-
- if (ch == '\n')
- {
- /* Output CR before LF*/
-#warning "Missing logic"
-
- }
+ /* Disable [E]SCC interrupts and perform the low-level output */
- /* Output the character */
-
-#warning "Missing logic"
-
- /* Wait for the character to be sent before re-enabling interrupts */
-
-#warning "Missing logic"
+ z180_disableuartint(priv);
+ up_lowputc(ch);
+ z180_restoreuartint(priv);
return ch;
#endif
}
-
-#else /* USE_SERIALDRIVER */
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: z180_putc
- ****************************************************************************/
-
-static void z180_putc(int ch)
-{
-#warning "Missing logic"
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: up_putc
- ****************************************************************************/
-
-int up_putc(int ch)
-{
- /* Check for LF */
-
- if (ch == '\n')
- {
- /* Output CR before LF */
-
- z180_putc('\r');
- }
-
- /* Output character */
-
- z180_putc(ch);
- return ch;
-}
-
#endif /* USE_SERIALDRIVER */
diff --git a/nuttx/arch/z80/src/z180/z180_serial.h b/nuttx/arch/z80/src/z180/z180_serial.h
new file mode 100644
index 000000000..31248eb51
--- /dev/null
+++ b/nuttx/arch/z80/src/z180/z180_serial.h
@@ -0,0 +1,109 @@
+/****************************************************************************
+ * arch/z80/src/z180/z180_serial.h
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_Z80_SRC_Z180_Z180_SERIAL_H
+#define __ARCH_Z80_SRC_Z180_Z180_SERIAL_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "up_internal.h"
+#include "z180_config.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+ /****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: z180_uart_lowinit
+ *
+ * Description:
+ * Called early in the boot sequence to initialize the UART(s)
+ *
+ ****************************************************************************/
+
+#ifdef HAVE_UART
+void z180_uart_lowinit(void);
+#else
+# define z180_uart_lowinit()
+#endif
+
+/****************************************************************************
+ * Name: z180_scc_lowinit
+ *
+ * Description:
+ * Called early in the boot sequence to initialize the [E]SCC channel(s)
+ *
+ ****************************************************************************/
+
+#ifdef HAVE_SCC
+void z180_scc_lowinit(void);
+#else
+# define z180_scc_lowinit()
+#endif
+
+/****************************************************************************
+ * Name: z180_putc
+ *
+ * Description:
+ * Low-level character output
+ *
+ ****************************************************************************/
+
+void z180_putc(uint8_t ch) __naked;
+
+/****************************************************************************
+ * Name: up_putc/up_lowputc
+ *
+ * Description:
+ * Low-level console output
+ *
+ ****************************************************************************/
+
+#ifdef USE_SERIALDRIVER
+int up_lowputc(int ch);
+#else
+int up_putc(int ch);
+# define up_lowputc(ch) up_putc(ch)
+#endif
+
+#endif /* __ARCH_Z80_SRC_Z180_Z180_SERIAL_H */