summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-01-07 23:19:24 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-01-07 23:19:24 +0000
commit1e947541beca40e9dba0455d3019e42fa8c08a27 (patch)
tree160a27befbd7fcaed78251146998ea761233acbb /nuttx/arch
parent5462062fb673e26e07678b8c5087888eb405898e (diff)
downloadpx4-nuttx-1e947541beca40e9dba0455d3019e42fa8c08a27.tar.gz
px4-nuttx-1e947541beca40e9dba0455d3019e42fa8c08a27.tar.bz2
px4-nuttx-1e947541beca40e9dba0455d3019e42fa8c08a27.zip
Adding support for Z16F
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@521 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/z16/include/arch.h80
-rw-r--r--nuttx/arch/z16/include/irq.h81
-rw-r--r--nuttx/arch/z16/include/limits.h73
-rw-r--r--nuttx/arch/z16/include/serial.h55
-rw-r--r--nuttx/arch/z16/include/types.h82
-rw-r--r--nuttx/arch/z16/include/z16f/arch.h77
-rw-r--r--nuttx/arch/z16/include/z16f/irq.h137
-rw-r--r--nuttx/arch/z16/src/Makefile110
-rw-r--r--nuttx/arch/z16/src/z16f/Make.defs42
9 files changed, 737 insertions, 0 deletions
diff --git a/nuttx/arch/z16/include/arch.h b/nuttx/arch/z16/include/arch.h
new file mode 100644
index 000000000..f32e2a998
--- /dev/null
+++ b/nuttx/arch/z16/include/arch.h
@@ -0,0 +1,80 @@
+/****************************************************************************
+ * arch/arch.h
+ *
+ * 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 nameNuttX 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
+ */
+
+#ifndef __ARCH_ARCH_H
+#define __ARCH_ARCH_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Inline functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * 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_ARCH_H */
+
diff --git a/nuttx/arch/z16/include/irq.h b/nuttx/arch/z16/include/irq.h
new file mode 100644
index 000000000..116cba8fa
--- /dev/null
+++ b/nuttx/arch/z16/include/irq.h
@@ -0,0 +1,81 @@
+/****************************************************************************
+ * arch/irq.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather,
+ * only indirectly through nuttx/irq.h
+ */
+
+#ifndef __ARCH_IRQ_H
+#define __ARCH_IRQ_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/irq.h>
+#include <arch/chip/irq.h>
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif /* __ARCH_IRQ_H */
+
diff --git a/nuttx/arch/z16/include/limits.h b/nuttx/arch/z16/include/limits.h
new file mode 100644
index 000000000..f1e17f073
--- /dev/null
+++ b/nuttx/arch/z16/include/limits.h
@@ -0,0 +1,73 @@
+/****************************************************************************
+ * arch/limits.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_LIMITS_H
+#define __ARCH_LIMITS_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#define CHAR_BIT 8
+#define SCHAR_MIN 0x80
+#define SCHAR_MAX 0x7f
+#define UCHAR_MAX 0xff
+
+/* These could be different on machines where char is unsigned */
+
+#define CHAR_MIN SCHAR_MIN
+#define CHAR_MAX SCHAR_MAX
+
+#define SHRT_MIN 0x8000
+#define SHRT_MAX 0x7fff
+#define USHRT_MAX 0xffff
+
+#define INT_MIN 0x80000000
+#define INT_MAX 0x7fffffff
+#define UINT_MAX 0xffffffff
+
+#define LONG_MAX 0x80000000
+#define LONG_MIN 0x7fffffff
+#define ULONG_MAX 0xffffffff
+
+#define LLONG_MAX 0x80000000
+#define LLONG_MIN 0x7fffffff
+#define ULLONG_MAX 0xffffffff
+
+#endif /* __ARCH_LIMITS_H */
diff --git a/nuttx/arch/z16/include/serial.h b/nuttx/arch/z16/include/serial.h
new file mode 100644
index 000000000..c46a8c35d
--- /dev/null
+++ b/nuttx/arch/z16/include/serial.h
@@ -0,0 +1,55 @@
+/************************************************************
+ * arch/serial.h
+ *
+ * Copyright (C) 2007 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 Gregory Nutt 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_SERIAL_H
+#define __ARCH_SERIAL_H
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+/************************************************************
+ * Public Data
+ ************************************************************/
+
+/************************************************************
+ * Public Functions
+ ************************************************************/
+
+#endif /* __ARCH_SERIAL_H */
diff --git a/nuttx/arch/z16/include/types.h b/nuttx/arch/z16/include/types.h
new file mode 100644
index 000000000..760790327
--- /dev/null
+++ b/nuttx/arch/z16/include/types.h
@@ -0,0 +1,82 @@
+/************************************************************
+ * arch/types.h
+ *
+ * Copyright (C) 2007 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 Gregory Nutt 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 __ARCH_TYPES_H
+#define __ARCH_TYPES_H
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+/************************************************************
+ * Type Declarations
+ ************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/* These are the sizes of the standard GNU types */
+
+typedef char sbyte;
+typedef unsigned char ubyte;
+typedef unsigned char uint8;
+typedef unsigned char boolean;
+typedef short sint16;
+typedef unsigned short uint16;
+typedef int sint32;
+typedef unsigned int uint32;
+typedef long long sint64;
+typedef unsigned long long uint64;
+
+/* This is the size of the interrupt state save returned by
+ * irqsave()
+ */
+
+typedef unsigned int irqstate_t;
+
+#endif /* __ASSEMBLY__ */
+
+/************************************************************
+ * Global Function Prototypes
+ ************************************************************/
+
+#endif /* __ARCH_TYPES_H */
diff --git a/nuttx/arch/z16/include/z16f/arch.h b/nuttx/arch/z16/include/z16f/arch.h
new file mode 100644
index 000000000..3d0e02c20
--- /dev/null
+++ b/nuttx/arch/z16/include/z16f/arch.h
@@ -0,0 +1,77 @@
+/****************************************************************************
+ * arch/z26f/arch.h
+ * arch/chip/arch.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather,
+ * only indirectly through nuttx/arch.h (via arch/arch.h)
+ */
+
+#ifndef __ARCH_Z16F_ARCH_H
+#define __ARCH_Z16F_ARCH_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * 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_Z16F_ARCH_H */
+
diff --git a/nuttx/arch/z16/include/z16f/irq.h b/nuttx/arch/z16/include/z16f/irq.h
new file mode 100644
index 000000000..8b718cf74
--- /dev/null
+++ b/nuttx/arch/z16/include/z16f/irq.h
@@ -0,0 +1,137 @@
+/****************************************************************************
+ * arch/z16f/irq.h
+ * arch/chip/irq.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather,
+ * only indirectly through nuttx/irq.h (via arch/irq.h)
+ */
+
+#ifndef __ARCH_Z16F_IRQ_H
+#define __ARCH_Z16F_IRQ_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#define Z80_IRQ_SYSTIMER 0
+#define NR_IRQS (1)
+
+/* 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 the type of the register save array */
+
+typedef uint16 chipreg_t;
+
+/* This struct defines the way the registers are stored. */
+
+struct xcptcontext
+{
+ /* Register save area */
+
+ uint16 regs[XCPTCONTEXT_REGS];
+
+ /* The following function pointer is non-zero if there
+ * are pending signals to be processed.
+ */
+
+#ifndef CONFIG_DISABLE_SIGNALS
+ void *sigdeliver; /* Actual type is sig_deliver_t */
+
+ /* The following retains that state during signal execution */
+
+ uint16 saved_pc; /* Saved return address */
+ uint16 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;
+EXTERN void irqrestore(irqstate_t flags;
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif /* __ARCH_Z16F_IRQ_H */
+
diff --git a/nuttx/arch/z16/src/Makefile b/nuttx/arch/z16/src/Makefile
new file mode 100644
index 000000000..225ed3b29
--- /dev/null
+++ b/nuttx/arch/z16/src/Makefile
@@ -0,0 +1,110 @@
+############################################################################
+# arch/z16/src/Makefile
+#
+# 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.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+-include chip/Make.defs
+
+MKDEP = $(TOPDIR)/tools/mkdeps.sh
+ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
+CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(TOPDIR)/sched
+
+HEAD_AOBJ = $(HEAD_ASRC:.S=$(OBJEXT))
+
+ASRCS = $(CHIP_ASRCS) $(CMN_ASRCS)
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+
+CSRCS = $(CHIP_CSRCS) $(CMN_CSRCS)
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+LDFLAGS = $(ARCHSCRIPT)
+EXTRA_LIBS =
+
+LINKLIBS =
+LDPATHES = $(addprefix -L$(TOPDIR)/,$(dir $(LINKLIBS)))
+LDLIBS = $(patsubst lib%,-l%,$(basename $(notdir $(LINKLIBS))))
+
+BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
+
+LIBGCC = ${shell $(CC) -print-libgcc-file-name}
+
+VPATH = chip:common
+
+all: $(HEAD_OBJ) libarch$(LIBEXT)
+
+$(AOBJS) $(HEAD_AOBJ): %$(OBJEXT): %.S
+ $(CC) -c $(CFLAGS) -D__ASSEMBLY__ $< -o $@
+
+$(COBJS): %$(OBJEXT): %.c
+ $(CC) -c $(CFLAGS) $< -o $@
+
+libarch$(LIBEXT): $(OBJS)
+ @( for obj in $(OBJS) ; do \
+ $(AR) $@ $${obj} || \
+ { echo "$(AR) $@ $obj FAILED!" ; exit 1 ; } ; \
+ done ; )
+
+board/libboard$(LIBEXT):
+ $(MAKE) -C board TOPDIR=$(TOPDIR) libboard$(LIBEXT)
+
+nuttx: $(HEAD_AOBJ) board/libboard$(LIBEXT)
+ $(LD) --entry=__start $(LDFLAGS) $(LDPATHES) -L$(BOARDDIR) -o $(TOPDIR)/$@ $(HEAD_AOBJ) \
+ --start-group $(LDLIBS) -lboard --end-group $(EXTRA_LIBS) $(LIBGCC)
+
+.depend: Makefile chip/Make.defs $(SRCS)
+ @if [ -e board/Makefile ]; then \
+ $(MAKE) -C board TOPDIR=$(TOPDIR) depend ; \
+ fi
+ $(MKDEP) --dep-path chip --dep-path common $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ @touch $@
+
+depend: .depend
+
+clean:
+ @if [ -e board/Makefile ]; then \
+ $(MAKE) -C board TOPDIR=$(TOPDIR) clean ; \
+ fi
+ @rm -f libarch$(LIBEXT) *~
+ @if [ ! -z "$(OBJEXT)" ]; then rm -f *$(OBJEXT); fi
+
+distclean: clean
+ @if [ -e board/Makefile ]; then \
+ $(MAKE) -C board TOPDIR=$(TOPDIR) distclean ; \
+ fi
+ @rm -f Make.dep .depend
+
+-include Make.dep
diff --git a/nuttx/arch/z16/src/z16f/Make.defs b/nuttx/arch/z16/src/z16f/Make.defs
new file mode 100644
index 000000000..dcd2381ac
--- /dev/null
+++ b/nuttx/arch/z16/src/z16f/Make.defs
@@ -0,0 +1,42 @@
+############################################################################
+# arch/z16/src/z16f/Make.defs
+#
+# 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.
+#
+############################################################################
+
+HEAD_ASRC =
+
+CMN_ASRCS =
+CMN_CSRCS =
+
+CHIP_ASRCS =
+CHIP_CSRCS =