summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-12-10 17:03:34 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-12-10 17:03:34 +0000
commit876a38713e205a601078e587d0b34c456f8b8343 (patch)
tree895a81fa1c3c6163d05b0996afb9a6b8bb7d4dd6 /nuttx
parent20b116f713d7cb943f30c4fe3401633fb92e26a4 (diff)
downloadpx4-nuttx-876a38713e205a601078e587d0b34c456f8b8343.tar.gz
px4-nuttx-876a38713e205a601078e587d0b34c456f8b8343.tar.bz2
px4-nuttx-876a38713e205a601078e587d0b34c456f8b8343.zip
Add header files for z180
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5425 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog2
-rw-r--r--nuttx/arch/z80/include/z180/arch.h77
-rw-r--r--nuttx/arch/z80/include/z180/chip.h428
-rw-r--r--nuttx/arch/z80/include/z180/io.h85
-rw-r--r--nuttx/arch/z80/include/z180/irq.h152
-rw-r--r--nuttx/arch/z80/include/z180/limits.h82
-rw-r--r--nuttx/arch/z80/include/z180/types.h99
-rw-r--r--nuttx/configs/pjrc-8051/README.txt3
-rw-r--r--nuttx/net/net_poll.c2
9 files changed, 929 insertions, 1 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index ffa2e719f..128738373 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -3773,4 +3773,6 @@
* drivers/serial/Kconfig and sched/Kconfig: Two names for same configuration:
CONFIG_LOWLEVEL_CONSOLE is bogus and CONFIG_DEV_LOWCONSOLE is in the wrong
Kconfig file. Moved to drivers/serial/Kconfig replacing CONFIG_LOWLEVEL_CONSOLE.
+ * arch/z80/include/z180: Add header files for z180 chips. Initial versions
+ are just clones of z80 header files.
diff --git a/nuttx/arch/z80/include/z180/arch.h b/nuttx/arch/z80/include/z180/arch.h
new file mode 100644
index 000000000..9e2197522
--- /dev/null
+++ b/nuttx/arch/z80/include/z180/arch.h
@@ -0,0 +1,77 @@
+/****************************************************************************
+ * arch/z80/arch.h
+ * arch/chip/arch.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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather, only indirectly
+ * through nuttx/arch.h (via arch/arch.h)
+ */
+
+#ifndef __ARCH_Z80_INCLUDE_Z180_ARCH_H
+#define __ARCH_Z80_INCLUDE_Z180_ARCH_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __ARCH_Z80_INCLUDE_Z180_ARCH_H */
+
diff --git a/nuttx/arch/z80/include/z180/chip.h b/nuttx/arch/z80/include/z180/chip.h
new file mode 100644
index 000000000..b31c69bcf
--- /dev/null
+++ b/nuttx/arch/z80/include/z180/chip.h
@@ -0,0 +1,428 @@
+/****************************************************************************
+ * arch/z80/include/z180/chip.h
+ * arch/chip/io.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_INCLUDE_Z180_CHIP_H
+#define __ARCH_Z80_INCLUDE_Z180_CHIP_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Z800180
+ *
+ * The 8-bit Z80180 MPU provides the benefits of reduced system costs and
+ * also provides full backward compatibility with existing ZiLOG Z80 devices.
+ * Reduced system costs are obtained by incorporating several key system
+ * functions on-chip with the CPU. These key functions include I/O devices
+ * such as DMA, UART, and timer channels. Also included on-chip are wait-
+ * state generators, a clock oscillator, and an interrupt controller. The
+ * Z80180 MPU is housed in 80-pin QFP, 68-pin PLCC, and 64-pin DIP packages.
+ *
+ * Z80180 Features
+ *
+ * Enhanced Z80 CPU
+ * 1 MB MMU
+ * 2 DMA channels*
+ * 2 UARTs* (up to 512 Kbps)
+ * Two 16-Bit Timers
+ * Clock Serial I/O
+ * On-Chip Oscillator
+ * Power-Down Mode*
+ * Divide-by-One/Divide-by-Two/Multiply-by-Two Clock Options*
+ * Programmable Driver Strength for EMI Tuning
+ *
+ * * Enhanced on the Z8S180 and Z8L180 MPUs
+ */
+
+#if defined(CONFIG_Z180_CHIP_Z8018006VSG) || /* 68-pin PLCC */ \
+ defined(CONFIG_Z180_CHIP_Z8018010VSG) || /* 68-pin PLCC */ \
+ defined(CONFIG_Z180_CHIP_Z8018008VSG) || /* 68-pin PLCC */ \
+ defined(CONFIG_Z180_CHIP_Z8018010FSG) || /* 80-pin QFP (11 pins N/C) */ \
+ defined(CONFIG_Z180_CHIP_Z8018008VEG) || /* 68-pin PLCC */ \
+ defined(CONFIG_Z180_CHIP_Z8018006VEG) /* 68-pin PLCC */
+
+# undef HAVE_Z8S180 /* Not Z8S180 (5V) or Z8L180 (3.3V) core */
+# define HAVE ROM 0 /* No on-chip ROM */
+# define HAVE_SERIALIO 1 /* Have clocked serial I/O */
+# undef HAVE_WDT /* No Watchdog timer */
+# define HAVE_NTIMERS16 2 /* Two (2) 16-bit timers */
+# define HAVE_NCTCS 0 /* No Counter/Timers (CTCs) */
+# define HAVE_NDMA 2 /* Two (2) DMA channels */
+# define HAVE_NUARTS 2 /* Two (2) UARTs (up to 512 Kbps) */
+# define HAVE_NSCC 0 /* No serial communication controller */
+# define HAVE_NESCC 0 /* No Enhanced Serial Communication Controllers */
+# undef HAVE_16550 /* No 16550 MIMIC */
+# define HAVE_NIOLINES 0 /* No I/O lines */
+# define HAVE_NPAR8 0 /* No 8-bit parallel ports */
+# undef HAVE_IEEE1284 /* No bidirectional centronics interface (IEEE 1284) */
+
+#elif defined(CONFIG_Z180_CHIP_Z8018006PSG) || /* 64-pin DIP 6 MHz 5V */ \
+ defined(CONFIG_Z180_CHIP_Z8018008FSG) || /* 80-pin QFP (11 pins N/C) 8MHz 5V */ \
+ defined(CONFIG_Z180_CHIP_Z8018010PSG) || /* 64-pin DIP 10MHz 5V */ \
+ defined(CONFIG_Z180_CHIP_Z8018006PEG) || /* 64-pin DIP 6MHz 5V */ \
+ defined(CONFIG_Z180_CHIP_Z8018010VEG) || /* 68-pin PLCC 10MHz 5V*/ \
+ defined(CONFIG_Z180_CHIP_Z8018010PEG) || /* 64-pin DIP 10MHz 5V*/ \
+ defined(CONFIG_Z180_CHIP_Z8018008PSG) || /* 64-pin DIP 8MHz 5V */ \
+ defined(CONFIG_Z180_CHIP_Z8018006FSG) /* 80-pin QFP (11 pins N/C) 6MHz 5V */
+
+# undef HAVE_Z8S180 /* Not Z8S180 (5V) or Z8L180 (3.3V) core */
+# define HAVE ROM 0 /* No on-chip ROM */
+# undef HAVE_SERIALIO /* No clocked serial I/O ? */
+# undef HAVE_WDT /* No Watchdog timer */
+# define HAVE_NTIMERS16 2 /* Two (2) 16-bit timers */
+# define HAVE_NCTCS 0 /* No Counter/Timers (CTCs) */
+# define HAVE_NDMA 2 /* Two (2) DMA channels */
+# define HAVE_NUARTS 2 /* Two (2) UARTs (up to 512 Kbps) */
+# define HAVE_NSCC 0 /* No serial communication controller */
+# define HAVE_NESCC 0 /* No Enhanced Serial Communication Controllers */
+# undef HAVE_16550 /* No 16550 MIMIC */
+# define HAVE_NIOLINES 0 /* No I/O lines */
+# define HAVE_NPAR8 0 /* No 8-bit parallel ports */
+# undef HAVE_IEEE1284 /* No bidirectional centronics interface (IEEE 1284) */
+
+#elif defined(CONFIG_Z180_CHIP_Z8018000XSO)
+ defined(CONFIG_Z180_CHIP_Z8018010FEG)
+ defined(CONFIG_Z180_CHIP_Z8018000WSO)
+ defined(CONFIG_Z180_CHIP_Z8018008PEG)
+
+# undef HAVE_Z8S180 /* Not Z8S180 (5V) or Z8L180 (3.3V) core */
+# define HAVE ROM 0 /* No on-chip ROM */
+# define HAVE_SERIALIO 1 /* Have clocked serial I/O */
+# undef HAVE_WDT /* No Watchdog timer */
+# define HAVE_NTIMERS16 2 /* Two (2) 16-bit timers */
+# define HAVE_NCTCS 0 /* No Counter/Timers (CTCs) */
+# define HAVE_NDMA 2 /* Two (2) DMA channels */
+# define HAVE_NUARTS 2 /* Two (2) UARTs (up to 512 Kbps) */
+# define HAVE_NSCC 0 /* No serial communication controller */
+# define HAVE_NESCC 0 /* No Enhanced Serial Communication Controllers */
+# undef HAVE_16550 /* No 16550 MIMIC */
+# define HAVE_NIOLINES 0 /* No I/O lines */
+# define HAVE_NPAR8 0 /* No 8-bit parallel ports */
+# undef HAVE_IEEE1284 /* No bidirectional centronics interface (IEEE 1284) */
+
+/* Z80181
+ *
+ * The Z80181 SAC Smart Access Controller is an 8-bit CMOS microprocessor that
+ * combines a Z180-compatible MPU, one channel of the Z85C30 Serial Communications
+ * Controller, a Z80 CTC, two 8-bit general-purpose parallel ports, and two Chip
+ * Select signals, into a single 100-pin Quad Flat Pack package.
+ *
+ * Z80181 Features
+ *
+ * Enhanced Z80 CPU
+ * 1 MB MMU
+ * 2 DMAs
+ * 2 UARTs
+ * Two 16-Bit Timers
+ * Clock Serial I/O
+ * 1 Channel SCC
+ * 1 8-Bit Counter/Timer
+ * 16 I/O Lines
+ * Emulation Mode
+ */
+
+#elif defined(CONFIG_Z180_CHIP_Z8018110FEG) /* 100 QFP */
+
+# undef HAVE_Z8S180 /* Not Z8S180 (5V) or Z8L180 (3.3V) core */
+# define HAVE ROM 0 /* No on-chip ROM */
+# define HAVE_SERIALIO 1 /* Have clocked serial I/O */
+# undef HAVE_WDT /* No Watchdog timer */
+# define HAVE_NTIMERS16 2 /* Two (2) 16-bit timers */
+# define HAVE_NCTCS 1 /* One (1) 8-bit counter/timer */
+# define HAVE_NDMA 2 /* Two (2) DMA channels */
+# define HAVE_NUARTS 2 /* Two (2) UARTs (up to 512 Kbps) */
+# define HAVE_NSCC 1 /* One (1) Z85C30 serial communication controller */
+# define HAVE_NESCC 0 /* No Enhanced Serial Communication Controllers */
+# undef HAVE_16550 /* No 16550 MIMIC */
+# define HAVE_NIOLINES 16 /* Sixteen (16) I/O lines */
+# define HAVE_NPAR8 0 /* No 8-bit parallel ports */
+# undef HAVE_IEEE1284 /* No bidirectional centronics interface (IEEE 1284) */
+
+/* Z80182
+ *
+ * The Z80182 and Z8L182 MPUs are smart peripheral controller ICs for modems, fax,
+ * voice messaging, and other communications applications. It uses the Z80180
+ * microprocessor linked with two channels of the industry-standard Z85230 ESCC,
+ * 24 bits of parallel I/O, and a 16550 MIMIC for direct connection to the IBM PC,
+ * XT, or AT bus
+ *
+ * Z80182 Features
+ *
+ * Enhanced Z80 CPU
+ * 1 MB MMU
+ * 2 DMAs
+ * 2 UARTs (up to 512 Kbps)
+ * Two 16-Bit Timers
+ * Clock Serial I/O
+ * Power-Down Mode
+ * Divide-by-One/Divide-by-Two/Multiply-by-Two Clock Options
+ * Enhanced Serial Communication Controller (ESCC) (2 Channels) with 32-Bit CRC
+ * 16550 MIMIC
+ * 24 Parallel I/O
+ * 3.3 V and 5 V Version
+ */
+
+#elif defined(CONFIG_Z180_CHIP_Z8018233FSG) || /* 100-pin QFP */ \
+ defined(CONFIG_Z180_CHIP_Z8018220AEG) || /* 100-pin LQFP 20MHz 5V */ \
+ defined(CONFIG_Z180_CHIP_Z8018216FSG) || /* 100-pin QFP 16MHz 5V */ \
+ defined(CONFIG_Z180_CHIP_Z8018216ASG) || /* 100-pin LQFP */ \
+ defined(CONFIG_Z180_CHIP_Z8018233ASG) /* 100-pin LQFP 33MHz 5V */
+
+# undef HAVE_Z8S180 /* Not Z8S180 (5V) or Z8L180 (3.3V) core */
+# define HAVE ROM 0 /* No on-chip ROM */
+# define HAVE_SERIALIO 1 /* Have clocked serial I/O */
+# undef HAVE_WDT /* No Watchdog timer */
+# define HAVE_NTIMERS16 2 /* Two (2) 16-bit timers ? */
+# define HAVE_NCTCS 0 /* No Counter/Timers (CTCs) */
+# define HAVE_NDMA 2 /* Two (2) DMA channels */
+# define HAVE_NUARTS 2 /* Two (2) UARTs (up to 512 Kbps) */
+# define HAVE_NSCC 0 /* No Z85C30 serial communication controller */
+# define HAVE_NESCC 2 /* Two (2) Z85230 Enhanced Serial Communication Controllers */
+# define HAVE_16550 1 /* Have 16550 MIMIC */
+# define HAVE_NIOLINES 0 /* No I/O lines */
+# define HAVE_NPAR8 3 /* Three (3) 8-bit parallel ports (24-bit) */
+# undef HAVE_IEEE1284 /* No bidirectional centronics interface (IEEE 1284) */
+
+/* Z80195
+ *
+ * The Z80195 MPU is a smart peripheral controller device designed for general data
+ * communications applications, and architected specifically to accommodate all
+ * input and output (I/O) requirements for serial and parallel connectivity.
+ * Combining a high-performance CPU core with a variety of system and I/O
+ * resources, the Z80195 is useful in a broad range of applications.
+ *
+ * Z80195 Features
+ *
+ * Enhanced Z80 CPU
+ * 1 MB MMU
+ * 2 DMAs
+ * 2 UARTs (up to 512 Kbps)
+ * Two 16-Bit Timers
+ * 4 Counter/Timers
+ * Clock Serial I/O
+ * Power-Down Mode
+ * 32 K ROM (185)
+ * 1 Ch ESCC
+ * IEEE 1284 Bi-Directional Centronics Parallel Port
+ * 7 or 24 Bits of I/O
+ */
+
+#elif defined(CONFIG_Z180_CHIP_Z8019520FSG) || /* 100-pin QFP 20MHz 5V */ \
+ defined(CONFIG_Z180_CHIP_Z8019533FSG) /* 100-pin QFP 33MHz 5V */
+
+# undef HAVE_Z8S180 /* No Z8S180 (5V) or Z8L180 (3.3V) core */
+# undef HAVE ROM 0 /* No 32KB on-chip ROM (z80185 only) */
+# define HAVE_SERIALIO 1 /* Have clocked serial I/O */
+# defube HAVE_WDT 1 /* Have Watchdog timer */
+# define HAVE_NTIMERS16 2 /* Two (2) 16-bit counter/timers */
+# define HAVE_NCTCS 4 /* Four (4) Counter/Timers (CTCs) */
+# define HAVE_NDMA 2 /* Two (2) DMA channels */
+# define HAVE_NUARTS 2 /* Two (2) UARTs (up to 512 Kbps) */
+# define HAVE_NSCC 0 /* No Z85C30 serial communication controller */
+# define HAVE_NESCC 1 /* One (1) Enhanced Serial Communication Controllers (EMSCC) */
+# undef HAVE_16550 /* No 16550 MIMIC */
+# define HAVE_NIOLINES 0 /* No I/O lines */
+# define HAVE_NPAR8 2 /* Two (s) 8-bit parallel ports (or 17-bit IEEE 1284) */
+# define HAVE_IEEE1284 1 /* Have bidirectional centronics interface (IEEE 1284) */
+
+/* Z8L180
+ *
+ * The enhanced Z8S180/Z8L180 significantly improves on previous Z80180 models,
+ * while still providing full backward compatibility with existing ZiLOG Z80
+ * devices. The Z8S180/Z8L180 now offers faster execution speeds, power-saving
+ * modes, and EMI noise reduction.
+ *
+ * Z8L180 Features
+ *
+ * Enhanced Z80 CPU
+ * 1 MB MMU
+ * 2 DMAs*
+ * 2 UARTs* (up to 512 Kbps)
+ * Two 16-Bit Timers
+ * Clock Serial I/O
+ * On-Chip Oscillator
+ * Power-Down Mode*
+ * Divide-by-One/Divide-by-Two/Multiply-by-Two Clock Options*
+ * Programmable Driver Strength for EMI Tuning
+ *
+ * * Enhanced on the Z8S180 and Z8L180 MPUs.
+ */
+
+#elif defined(CONFIG_Z180_CHIP_Z8L18020VSG) || /* 69-pin PLCC */ \
+ defined(CONFIG_Z180_CHIP_Z8L18020FSG) || /* 80-pin GFP 20MHz 3.3V */ \
+ defined(CONFIG_Z180_CHIP_Z8L18020PSG)
+
+# define HAVE_Z8S180 1 /* Uses Z8S180 (5V) or Z8L180 (3.3V) core */
+# define HAVE ROM 0 /* No on-chip ROM */
+# define HAVE_SERIALIO 1 /* Have clocked serial I/O */
+# undef HAVE_WDT /* No Watchdog timer */
+# define HAVE_NTIMERS16 2 /* Two (2) 16-bit timers */
+# define HAVE_NCTCS 0 /* No Counter/Timers (CTCs) */
+# define HAVE_NDMA 2 /* Two (2) DMA channels */
+# define HAVE_NUARTS 2 /* Two (2) UARTs (up to 512 Kbps) */
+# define HAVE_NSCC 0 /* No serial communication controller */
+# define HAVE_NESCC 0 /* No Enhanced Serial Communication Controllers */
+# undef HAVE_16550 /* No 16550 MIMIC */
+# define HAVE_NIOLINES 0 /* No I/O lines */
+# define HAVE_NPAR8 0 /* No 8-bit parallel ports */
+# undef HAVE_IEEE1284 /* No bidirectional centronics interface (IEEE 1284) */
+
+/* Z8L182
+ *
+ * The Z80182/Z8L182 is a smart peripheral controller IC for modem (in particular
+ * V. Fast applications), fax, voice messaging and other communications
+ * applications. It uses the Z80180 microprocessor (Z8S180 MPU core) linked with
+ * two channels of the industry standard Z85230 ESCC (Enhanced Serial
+ * Communications Controller), 24 bits of parallel I/O, and a 16550 MIMIC for
+ * direct connection to the IBM PC, XT, AT bus.
+ *
+ * Z8L182 Features
+ *
+ * Enhanced Z80 CPU
+ * 1 MB MMU
+ * 2 DMAs
+ * 2 UARTs (up to 512 Kbps)
+ * Two 16-Bit Timers
+ * Clock Serial I/O
+ * Power-Down Mode
+ * Divide-by-One/Divide-by-Two/Multiply-by-Two Clock Options
+ * ESCC (2 Channels) with 32-Bit CRC
+ * 16550 MIMIC
+ * 24 Parallel I/O
+ * 3.3 V and 5 V Version
+ */
+
+#elif defined(CONFIG_Z180_CHIP_Z8L18220ASG) || /* 100-pin LQFP */ \
+ defined(CONFIG_Z180_CHIP_Z8L18220FSG) || /* 100-pin QFP 20MHz 3.3V */ \
+ defined(CONFIG_Z180_CHIP_Z8L18220AEG)
+
+# define HAVE_Z8S180 1 /* Uses Z8S180 (5V) or Z8L180 (3.3V) core */
+# define HAVE ROM 0 /* No on-chip ROM */
+# define HAVE_SERIALIO 1 /* Have clocked serial I/O */
+# undef HAVE_WDT /* No Watchdog timer */
+# define HAVE_NTIMERS16 2 /* Two (2) 16-bit timers ? */
+# define HAVE_NCTCS 0 /* No Counter/Timers (CTCs) */
+# define HAVE_NDMA 2 /* Two (2) DMA channels */
+# define HAVE_NUARTS 2 /* Two (2) UARTs (up to 512 Kbps) */
+# define HAVE_NSCC 0 /* No Z85C30 serial communication controller */
+# define HAVE_NESCC 2 /* Two (2) Z85230 Enhanced Serial Communication Controllers */
+# define HAVE_16550 1 /* Have 16550 MIMIC */
+# define HAVE_NIOLINES 0 /* No I/O lines */
+# define HAVE_NPAR8 3 /* Three (3) 8-bit parallel ports (24-bit) */
+# undef HAVE_IEEE1284 /* No bidirectional centronics interface (IEEE 1284) */
+
+/* Z8SL180
+ *
+ * The enhanced Z8S180/Z8L180 significantly improves on previous Z80180 models,
+ * while still providing full backward compatibility with existing ZiLOG Z80
+ * devices. The Z8S180/Z8L180 now offers faster execution speeds, power-saving
+ * modes, and EMI noise reduction.This enhanced Z180 design also incorporates
+ * additional feature enhancements to the ASCIs, DMAs, and STANDBY mode power
+ * consumption. With the addition of ESCC-like Baud Rate Generators (BRGs), the
+ * two ASCIs offer the flexibility and capability to transfer data
+ * asynchronously at rates of up to 512 Kbps.
+ *
+ * Z8S180 Features
+ *
+ * External Memory - 1
+ * Voltage Range - 5.0V
+ * Communications Controller - CSIO, UART
+ * Other Features - 1MB MMU, 2xDMA’s, 2xUARTs
+ * Speed (MHz) - 20, 10, 33
+ * Core / CPU Used - Z180
+ * Pin Count - 64, 68, 80
+ * Timers - 2
+ * I/O - Clock Serial
+ * Package - DIP, PLCC, QFP
+ */
+
+#elif defined(CONFIG_Z180_CHIP_Z8S18020VSG) || /* 68-pin PLCC */ \
+ defined(CONFIG_Z180_CHIP_Z8S18020VSG1960) || /* 68-pin PLCC */ \
+ defined(CONFIG_Z180_CHIP_Z8S18033VSG) || /* 68-pin PLCC */ \
+ defined(CONFIG_Z180_CHIP_Z8S18010FSG) || /* 80-pin QFP */ \
+ defined(CONFIG_Z180_CHIP_Z8S18010VEG) || /* 68-pin PLCC */ \
+ defined(CONFIG_Z180_CHIP_Z8S18020VEG) || /* 68-pin PLCC */ \
+ defined(CONFIG_Z180_CHIP_Z8S18010VSG) || /* 68-pin PLCC */ \
+ defined(CONFIG_Z180_CHIP_Z8S18020PSG) || /* 64-pin DIP 10Mhz 5V */ \
+ defined(CONFIG_Z180_CHIP_Z8S18033FSG) || /* 80-pin QFP 33MHz 5V */ \
+ defined(CONFIG_Z180_CHIP_Z8S18033FEG) || /* 80-pin QFP 33MHz 5V */ \
+ defined(CONFIG_Z180_CHIP_Z8S18020FSG) || /* 80-pin QFP 20MHz 5V */ \
+ defined(CONFIG_Z180_CHIP_Z8S18033VEG) || /* 68-pin PLCC 33MHz 5V */ \
+ defined(CONFIG_Z180_CHIP_Z8S18010PSG) || /* 64-pin DIP 10MHz 5V */ \
+ defined(CONFIG_Z180_CHIP_Z8S18020FEG) || \
+ defined(CONFIG_Z180_CHIP_Z8S18010PEG) || \
+ defined(CONFIG_Z180_CHIP_Z8S18010FEG
+
+# define HAVE_Z8S180 1 /* Uses Z8S180 (5V) or Z8L180 (3.3V) core */
+# define HAVE ROM 0 /* No on-chip ROM */
+# define HAVE_SERIALIO 1 /* Have clocked serial I/O */
+# undef HAVE_WDT /* No Watchdog timer */
+# define HAVE_NTIMERS16 2 /* Two (2) 16-bit timers */
+# define HAVE_NCTCS 0 /* No Counter/Timers (CTCs) */
+# define HAVE_NDMA 2 /* Two (2) DMA channels */
+# define HAVE_NUARTS 2 /* Two (2) UARTs (up to 512 Kbps) */
+# define HAVE_NSCC 0 /* No serial communication controller */
+# define HAVE_NESCC 0 /* No Enhanced Serial Communication Controllers */
+# undef HAVE_16550 /* No 16550 MIMIC */
+# define HAVE_NIOLINES 0 /* No I/O lines */
+# define HAVE_NPAR8 0 /* No 8-bit parallel ports */
+# undef HAVE_IEEE1284 /* No bidirectional centronics interface (IEEE 1284) */
+
+#else
+# error "Unrecognized/undefined Z180 chip"
+#endif
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Inline functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#endif /* __ARCH_Z80_INCLUDE_Z180_CHIP_H */
diff --git a/nuttx/arch/z80/include/z180/io.h b/nuttx/arch/z80/include/z180/io.h
new file mode 100644
index 000000000..a80a6b420
--- /dev/null
+++ b/nuttx/arch/z80/include/z180/io.h
@@ -0,0 +1,85 @@
+/****************************************************************************
+ * arch/z80/include/z80/io.h
+ * arch/chip/io.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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather, only indirectly
+ * through arch/io.h
+ */
+
+#ifndef __ARCH_Z80_INCLUDE_Z180_IO_H
+#define __ARCH_Z80_INCLUDE_Z180_IO_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Inline functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+EXTERN void outp(char p, char c);
+EXTERN char inp(char p);
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif /* __ARCH_Z80_INCLUDE_Z180_IO_H */
diff --git a/nuttx/arch/z80/include/z180/irq.h b/nuttx/arch/z80/include/z180/irq.h
new file mode 100644
index 000000000..3f058591f
--- /dev/null
+++ b/nuttx/arch/z80/include/z180/irq.h
@@ -0,0 +1,152 @@
+/****************************************************************************
+ * arch/z80/include/z180/irq.h
+ * arch/chip/irq.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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather, only indirectly
+ * through nuttx/irq.h (via arch/irq.h)
+ */
+
+#ifndef __ARCH_Z80_INCLUDE_Z180_IRQ_H
+#define __ARCH_Z80_INCLUDE_Z180_IRQ_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+#endif
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Z180 Interrupts */
+
+#define Z180_RST0 (0)
+#define Z180_RST1 (1)
+#define Z180_RST2 (2)
+#define Z180_RST3 (3)
+#define Z180_RST4 (4)
+#define Z180_RST5 (5)
+#define Z180_RST6 (6)
+#define Z180_RST7 (7)
+
+#define Z180_IRQ_SYSTIMER Z180_RST7
+#define NR_IRQS (8)
+
+/* IRQ Stack Frame Format
+ *
+ * This stack frame is created on each interrupt. These registers are stored
+ * in the TCB to many context switches.
+ */
+
+#define XCPT_I (0) /* Offset 0: Saved I w/interrupt state in carry */
+#define XCPT_BC (1) /* Offset 1: Saved BC register */
+#define XCPT_DE (2) /* Offset 2: Saved DE register */
+#define XCPT_IX (3) /* Offset 3: Saved IX register */
+#define XCPT_IY (4) /* Offset 4: Saved IY register */
+#define XCPT_SP (5) /* Offset 5: Offset to SP at time of interrupt */
+#define XCPT_HL (6) /* Offset 6: Saved HL register */
+#define XCPT_AF (7) /* Offset 7: Saved AF register */
+#define XCPT_PC (8) /* Offset 8: Offset to PC at time of interrupt */
+
+#define XCPTCONTEXT_REGS (9)
+#define XCPTCONTEXT_SIZE (2 * XCPTCONTEXT_REGS)
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/* This is the type of the register save array */
+
+typedef uint16_t chipreg_t;
+
+/* This struct defines the way the registers are stored. */
+
+struct xcptcontext
+{
+ /* Register save area */
+
+ chipreg_t regs[XCPTCONTEXT_REGS];
+
+ /* The following function pointer is non-zero if there
+ * are pending signals to be processed.
+ */
+
+#ifndef CONFIG_DISABLE_SIGNALS
+ CODE void *sigdeliver; /* Actual type is sig_deliver_t */
+
+ /* The following retains that state during signal execution */
+
+ uint16_t saved_pc; /* Saved return address */
+ uint16_t saved_i; /* Saved interrupt state */
+#endif
+};
+#endif
+
+/****************************************************************************
+ * Inline functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+EXTERN irqstate_t irqsave(void) __naked;
+EXTERN void irqrestore(irqstate_t flags) __naked;
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif /* __ARCH_Z80_INCLUDE_Z180_IRQ_H */
+
diff --git a/nuttx/arch/z80/include/z180/limits.h b/nuttx/arch/z80/include/z180/limits.h
new file mode 100644
index 000000000..a70118448
--- /dev/null
+++ b/nuttx/arch/z80/include/z180/limits.h
@@ -0,0 +1,82 @@
+/****************************************************************************
+ * arch/z80/include/z180/limits.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_INCLUDE_Z180_LIMITS_H
+#define __ARCH_Z80_INCLUDE_Z180_LIMITS_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define CHAR_BIT 8
+#define SCHAR_MIN (-SCHAR_MAX - 1)
+#define SCHAR_MAX 127
+#define UCHAR_MAX 255
+
+/* These could be different on machines where char is unsigned */
+
+#ifdef __CHAR_UNSIGNED__
+#define CHAR_MIN 0
+#define CHAR_MAX UCHAR_MAX
+#else
+#define CHAR_MIN SCHAR_MIN
+#define CHAR_MAX SCHAR_MAX
+#endif
+
+#define SHRT_MIN (-SHRT_MAX - 1)
+#define SHRT_MAX 32767
+#define USHRT_MAX 65535U
+
+#define INT_MIN (-INT_MAX - 1)
+#define INT_MAX 32767
+#define UINT_MAX 65535U
+
+/* These change on 32-bit and 64-bit platforms */
+
+#define LONG_MIN (-LONG_MAX - 1)
+#define LONG_MAX 2147483647L
+#define ULONG_MAX 4294967295UL
+
+/* A pointer is 2 bytes */
+
+#define PTR_MIN (-PTR_MAX - 1)
+#define PTR_MAX 32767
+#define UPTR_MAX 65535U
+
+#endif /* __ARCH_Z80_INCLUDE_Z180_LIMITS_H */
diff --git a/nuttx/arch/z80/include/z180/types.h b/nuttx/arch/z80/include/z180/types.h
new file mode 100644
index 000000000..0de51cab1
--- /dev/null
+++ b/nuttx/arch/z80/include/z180/types.h
@@ -0,0 +1,99 @@
+/****************************************************************************
+ * arch/z80/include/z180/types.h
+ * include/arch/chip/types.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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather, only indirectly
+ * through sys/types.h
+ */
+
+#ifndef __ARC_Z80_INCLUDE_Z180_TYPES_H
+#define __ARC_Z80_INCLUDE_Z180_TYPES_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Type Declarations
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/* These are the sizes of the standard integer types. NOTE that these type
+ * names have a leading underscore character. This file will be included
+ * (indirectly) by include/stdint.h and typedef'ed to the final name without
+ * the underscore character. This roundabout way of doings things allows
+ * the stdint.h to be removed from the include/ directory in the event that
+ * the user prefers to use the definitions provided by their toolchain header
+ * files
+ *
+ * These are the sizes of the standard SDCC types
+ *
+ * For SDCC, sizeof(int) is 16 and sizeof(long) is 32. long long and double
+ * are not supported.
+ *
+ * Generic pointers are 3 bytes in length with the first byte holding data
+ * space information.
+ */
+
+typedef signed char _int8_t;
+typedef unsigned char _uint8_t;
+
+typedef signed int _int16_t;
+typedef unsigned int _uint16_t;
+
+typedef signed long _int32_t;
+typedef unsigned long _uint32_t;
+
+/* A pointer is 2 bytes */
+
+typedef signed int _intptr_t;
+typedef unsigned int _uintptr_t;
+
+/* This is the size of the interrupt state save returned by irqsave() */
+
+typedef _uint16_t irqstate_t;
+
+#endif /* __ASSEMBLY__ */
+
+/****************************************************************************
+ * Global Function Prototypes
+ ****************************************************************************/
+
+#endif /* __ARC_Z80_INCLUDE_Z180_TYPES_H */
diff --git a/nuttx/configs/pjrc-8051/README.txt b/nuttx/configs/pjrc-8051/README.txt
index 46084f5d3..c9c44327e 100644
--- a/nuttx/configs/pjrc-8051/README.txt
+++ b/nuttx/configs/pjrc-8051/README.txt
@@ -41,7 +41,8 @@ Status
On December 9, 2012, I made updates so that the 8051 port could use the
newest SDCC toolchain (a pre-3.2.1 at that time). However, when I attempted
to build the PJRC-8051 configuration, I got type incompatibility errors
-from sched/os_bringup.c.
+from sched/os_bringup.c. From what I gather by googling, this is a compiler
+bug related to the --stack-auto option.
I have not been successful working around those bugs and I believe that
these are 8051-related bugs in the SDCC toolchain. This needs to be
diff --git a/nuttx/net/net_poll.c b/nuttx/net/net_poll.c
index ca594c10f..815c6a71d 100644
--- a/nuttx/net/net_poll.c
+++ b/nuttx/net/net_poll.c
@@ -141,6 +141,7 @@ static uint16_t poll_interrupt(struct uip_driver_s *dev, FAR void *conn,
sem_post(fds->sem);
}
}
+
return flags;
}
#endif /* HAVE_NETPOLL */
@@ -219,6 +220,7 @@ static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds)
sem_post(fds->sem);
}
}
+
uip_unlock(flags);
return OK;