summaryrefslogtreecommitdiff
path: root/nuttx/arch/z80
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/arch/z80')
-rw-r--r--nuttx/arch/z80/include/arch.h82
-rw-r--r--nuttx/arch/z80/include/irq.h81
-rw-r--r--nuttx/arch/z80/include/limits.h71
-rw-r--r--nuttx/arch/z80/include/serial.h61
-rw-r--r--nuttx/arch/z80/include/types.h87
-rw-r--r--nuttx/arch/z80/include/z80/arch.h77
-rw-r--r--nuttx/arch/z80/include/z80/irq.h133
-rw-r--r--nuttx/arch/z80/src/Makefile220
-rw-r--r--nuttx/arch/z80/src/common/up_allocateheap.c79
-rw-r--r--nuttx/arch/z80/src/common/up_arch.h70
-rw-r--r--nuttx/arch/z80/src/common/up_assert.c156
-rw-r--r--nuttx/arch/z80/src/common/up_blocktask.c173
-rw-r--r--nuttx/arch/z80/src/common/up_copystate.c78
-rw-r--r--nuttx/arch/z80/src/common/up_createstack.c128
-rw-r--r--nuttx/arch/z80/src/common/up_doirq.c104
-rw-r--r--nuttx/arch/z80/src/common/up_exit.c200
-rw-r--r--nuttx/arch/z80/src/common/up_head.asm157
-rw-r--r--nuttx/arch/z80/src/common/up_idle.c107
-rw-r--r--nuttx/arch/z80/src/common/up_initialize.c158
-rw-r--r--nuttx/arch/z80/src/common/up_initialstate.c91
-rw-r--r--nuttx/arch/z80/src/common/up_internal.h184
-rw-r--r--nuttx/arch/z80/src/common/up_interruptcontext.c68
-rw-r--r--nuttx/arch/z80/src/common/up_mdelay.c94
-rw-r--r--nuttx/arch/z80/src/common/up_registerdump.c91
-rw-r--r--nuttx/arch/z80/src/common/up_releasepending.c137
-rw-r--r--nuttx/arch/z80/src/common/up_releasestack.c78
-rw-r--r--nuttx/arch/z80/src/common/up_reprioritizertr.c185
-rw-r--r--nuttx/arch/z80/src/common/up_restoreusercontext.asm99
-rw-r--r--nuttx/arch/z80/src/common/up_saveusercontext.asm143
-rw-r--r--nuttx/arch/z80/src/common/up_schedulesigaction.c190
-rw-r--r--nuttx/arch/z80/src/common/up_sigdeliver.c137
-rw-r--r--nuttx/arch/z80/src/common/up_stackdump.c109
-rw-r--r--nuttx/arch/z80/src/common/up_udelay.c132
-rw-r--r--nuttx/arch/z80/src/common/up_unblocktask.c168
-rw-r--r--nuttx/arch/z80/src/common/up_usestack.c118
-rw-r--r--nuttx/arch/z80/src/z80/Make.defs48
-rw-r--r--nuttx/arch/z80/src/z80/chip.h66
37 files changed, 4360 insertions, 0 deletions
diff --git a/nuttx/arch/z80/include/arch.h b/nuttx/arch/z80/include/arch.h
new file mode 100644
index 000000000..ff3a059e0
--- /dev/null
+++ b/nuttx/arch/z80/include/arch.h
@@ -0,0 +1,82 @@
+/****************************************************************************
+ * arch/arch.h
+ *
+ * Copyright (C) 2007, 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
+ */
+
+#ifndef __ARCH_ARCH_H
+#define __ARCH_ARCH_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <arch/chip/arch.h>
+
+/****************************************************************************
+ * 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/z80/include/irq.h b/nuttx/arch/z80/include/irq.h
new file mode 100644
index 000000000..6ef0188ac
--- /dev/null
+++ b/nuttx/arch/z80/include/irq.h
@@ -0,0 +1,81 @@
+/****************************************************************************
+ * arch/irq.h
+ *
+ * Copyright (C) 2007, 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/z80/include/limits.h b/nuttx/arch/z80/include/limits.h
new file mode 100644
index 000000000..31a94a547
--- /dev/null
+++ b/nuttx/arch/z80/include/limits.h
@@ -0,0 +1,71 @@
+/****************************************************************************
+ * arch/limits.h
+ *
+ * Copyright (C) 2007, 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 0x8000
+#define INT_MAX 0x7fff
+#define UINT_MAX 0xffff
+
+/* These change on 32-bit and 64-bit platforms */
+
+#define LONG_MAX 0x80000000
+#define LONG_MIN 0x7fffffff
+#define ULONG_MAX 0xffffffff
+
+#endif /* __ARCH_LIMITS_H */
diff --git a/nuttx/arch/z80/include/serial.h b/nuttx/arch/z80/include/serial.h
new file mode 100644
index 000000000..dc3c4948b
--- /dev/null
+++ b/nuttx/arch/z80/include/serial.h
@@ -0,0 +1,61 @@
+/****************************************************************************
+ * arch/serial.h
+ *
+ * Copyright (C) 2007, 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_SERIAL_H
+#define __ARCH_SERIAL_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* IOCTL commands supported by the z80 serial driver */
+
+#define TIOCSBRK 0x5401 /* BSD compatibility */
+#define TIOCCBRK 0x5402 /* " " " " */
+#define TIOCSERGSTRUCT 0x5403 /* Get up_dev_t for port */
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+#endif /* __ARCH_SERIAL_H */
diff --git a/nuttx/arch/z80/include/types.h b/nuttx/arch/z80/include/types.h
new file mode 100644
index 000000000..d650e5a01
--- /dev/null
+++ b/nuttx/arch/z80/include/types.h
@@ -0,0 +1,87 @@
+/****************************************************************************
+ * arch/types.h
+ *
+ * Copyright (C) 2007, 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 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 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 the
+ * first byte holding data space intformation.
+ */
+
+typedef char sbyte;
+typedef unsigned char ubyte;
+typedef unsigned char uint8;
+typedef unsigned char boolean;
+typedef int sint16;
+typedef unsigned int uint16;
+typedef long sint32;
+typedef unsigned long uint32;
+
+/* This is the size of the interrupt state save returned by
+ * irqsave()
+ */
+
+typedef unsigned char irqstate_t;
+
+#endif /* __ASSEMBLY__ */
+
+/****************************************************************************
+ * Global Function Prototypes
+ ****************************************************************************/
+
+#endif /* __ARCH_TYPES_H */
diff --git a/nuttx/arch/z80/include/z80/arch.h b/nuttx/arch/z80/include/z80/arch.h
new file mode 100644
index 000000000..e9033596c
--- /dev/null
+++ b/nuttx/arch/z80/include/z80/arch.h
@@ -0,0 +1,77 @@
+/****************************************************************************
+ * arch/z80/arch.h
+ * arch/chip/arch.h
+ *
+ * Copyright (C) 2007, 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_Z80_ARCH_H
+#define __ARCH_Z80_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_Z80_ARCH_H */
+
diff --git a/nuttx/arch/z80/include/z80/irq.h b/nuttx/arch/z80/include/z80/irq.h
new file mode 100644
index 000000000..c68dd76f9
--- /dev/null
+++ b/nuttx/arch/z80/include/z80/irq.h
@@ -0,0 +1,133 @@
+/****************************************************************************
+ * arch/z80/irq.h
+ * arch/chip/irq.h
+ *
+ * Copyright (C) 2007, 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_Z80_IRQ_H
+#define __ARCH_Z80_IRQ_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Z80 Interrupts */
+
+#define Z80_IRQ_SYSTIMER (1)
+#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) /* Saved I w/interrupt state in carry */
+#define XCPT_AF (1) /* Saved AF register */
+#define XCPT_BC (2) /* Saved BC register */
+#define XCPT_DE (3) /* Saved DE register */
+#define XCPT_HL (4) /* Saved HL register */
+#define XCPT_IX (5) /* Saved IX register */
+#define XCPT_IY (6) /* Saved IY register */
+#define XCPT_SP (7) /* Offset to SP at time of interrupt */
+#define XCPT_PC (8) /* Offset to PC at time of interrupt */
+
+#define XCPTCONTEXT_REGS (9)
+#define XCPTCONTEXT_SIZE (2 * XCPTCONTEXT_REGS)
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/* This is the the type of the register save array */
+
+typedef uint16 chipreg_t;
+
+/* This struct defines the way the registers are stored. */
+
+#ifndef __ASSEMBLY__
+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 */
+#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_Z80_IRQ_H */
+
diff --git a/nuttx/arch/z80/src/Makefile b/nuttx/arch/z80/src/Makefile
new file mode 100644
index 000000000..0aabc09bb
--- /dev/null
+++ b/nuttx/arch/z80/src/Makefile
@@ -0,0 +1,220 @@
+############################################################################
+# arch/z80/src/Makefile
+#
+# Copyright (C) 2007, 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.
+#
+############################################################################
+
+############################################################################
+# Makefile fragments
+
+-include $(TOPDIR)/Make.defs
+-include chip/Make.defs
+
+############################################################################
+# Tools
+
+MKDEP = $(TOPDIR)/tools/mkdeps.sh
+
+CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(TOPDIR)/sched
+LDFLAGS = $(ARCHSCRIPT)
+
+LDPATHES = $(addprefix -L$(TOPDIR)/,$(dir $(LINKLIBS)))
+LDLIBS = $(patsubst lib%,-l%,$(basename $(notdir $(LINKLIBS))))
+
+CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) -D__ASSEMBLY__
+
+############################################################################
+# Files and directories
+
+# There should be one head source (.asm file)
+
+HEAD_AOBJ = $(HEAD_ASRC:$(ASMEXT)=$(OBJEXT))
+
+# Assembly sources and objects
+
+ASRCS = $(CHIP_ASRCS) $(CMN_ASRCS)
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+
+# C sources and objects
+
+CSRCS = $(CHIP_CSRCS) $(CMN_CSRCS)
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+# All sources and objcts
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+# Sources and objects for the test target (plus HEAD_AOBJ
+
+TEST_AOBJS = $(TEST_ASRCS:$(ASMEXT)=$(OBJEXT))
+TEST_COBJS = $(TEST_CSRCS:.c=$(OBJEXT))
+
+TESTSRCS = up_irqtest.c
+TESTOBJS = $(TESTSRCS:.c=$(OBJEXT))
+TESTEXTRAOBJS = up_savecontext$(OBJEXT) up_restorecontext$(OBJEXT)
+
+# Sources that can have dependencies (no .asm files)
+
+DEPSRCS = $(SRCS)
+
+# Directories
+
+ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
+BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
+
+VPATH = chip:common
+
+# Libraries
+
+LIBGCC = ${shell $(CC) -print-libgcc-file-name}
+
+# Supports dynamic sizing of HEAP
+
+HEAP_BASE = ${shell \
+ if [ -e pass1.mem ]; then \
+ cat pass1.mem | grep "ROM/EPROM/FLASH" | \
+ sed -e "s/[ ][ ]*/ /g" | cut -d' ' -f4 ; \
+ else \
+ echo $(DEF_HEAP_BASE) ; \
+ fi \
+ }
+
+STACK_BASE = ${shell \
+ if [ -e pass1.mem ]; then \
+ cat pass1.mem | grep "Stack starts" | \
+ cut -d' ' -f4 ; \
+ else \
+ echo $(DEF_STACK_BASE) ; \
+ fi \
+ }
+
+############################################################################
+# Targets
+
+all: $(HEAD_AOBJ) libarch$(LIBEXT)
+
+$(AOBJS) $(HEAD_AOBJ) $(TEST_AOBJS): %$(OBJEXT): %$(ASMEXT)
+ $(AS) $(ASFLAGS) $@ $<
+
+$(COBJS) $(TEST_COBJS): %$(OBJEXT): %.c
+ $(CC) -c $(CFLAGS) $< -o $@
+
+# Create a header file that contains addressing information needed by the code
+
+pass1.mem:
+
+up_mem.h: pass1.mem
+ @echo "#ifndef __ARCH_MEM_H" >up_mem.h
+ @echo "#define __ARCH_MEM_H" >>up_mem.h
+ @echo "" >>up_mem.h
+ @echo "#define UP_DEFAULT_STACK_BASE $(DEF_STACK_BASE)" >>up_mem.h
+ @echo "#define UP_DEFAULT_HEAP_BASE $(DEF_HEAP_BASE)" >> up_mem.h
+ @echo "" >>up_mem.h
+ @echo "#define UP_STACK_BASE $(STACK_BASE)" >>up_mem.h
+ @echo "#if UP_STACK_BASE > UP_DEFAULT_STACK_BASE" >>up_mem.h
+ @echo "# error \"Stack overlap: $(DEF_STACK_BASE) < $(STACK_BASE)\"" >>up_mem.h
+ @echo "#elif UP_STACK_BASE < UP_DEFAULT_STACK_BASE" >>up_mem.h
+ @echo "# warning \"Wasted stack: $(DEF_STACK_BASE) > $(STACK_BASE)\"" >>up_mem.h
+ @echo "#endif" >>up_mem.h
+ @echo "" >>up_mem.h
+ @echo "#define UP_HEAP_BASE $(HEAP_BASE)" >> up_mem.h
+ @echo "#define UP_HEAP_END $(CONFIG_DRAM_END)" >> up_mem.h
+ @echo "" >>up_mem.h
+ @echo "#endif /* __ARCH_MEM_H */" >>up_mem.h
+
+# Combine all objects in this directory into a library
+
+libarch$(LIBEXT): up_mem.h $(OBJS)
+ @( for obj in $(OBJS) ; do \
+ $(AR) $@ $${obj} || \
+ { echo "$(AR) $@ $${obj} FAILED!" ; exit 1 ; } ; \
+ done ; )
+
+# This builds the libboard library in the board/ subdirectory
+
+board/libboard$(LIBEXT):
+ $(MAKE) -C board TOPDIR=$(TOPDIR) libboard$(LIBEXT)
+
+# This target builds the final executable
+
+pass1.ihx: up_mem.h $(HEAD_AOBJ) board/libboard$(LIBEXT)
+ $(CC) $(LDFLAGS) -L$(BOARDDIR) $(SDCCPATH) $(HEAD_AOBJ) \
+ -llibboard$(LIBEXT) $(SDCCLIBS) -o $@
+ @rm -f up_mem.h
+ @rm -f up_allocateheap$(OBJEXT) libarch$(LIBEXT)
+ @$(MAKE) TOPDIR=$(TOPDIR) libarch$(LIBEXT)
+
+nuttx.ihx: up_mem.h $(HEAD_AOBJ)
+ $(CC) $(LDFLAGS) -L$(BOARDDIR) $(SDCCPATH) $(HEAD_AOBJ) \
+ -llibboard$(LIBEXT) $(SDCCLIBS) -o $@
+
+nuttx$(EXEEXT): pass1.ihx nuttx.ihx
+ @rm -f pass1.*
+ packihx nuttx.ihx > $(TOPDIR)/nuttx$(EXEEXT)
+ @cp -f nuttx.map $(TOPDIR)/.
+
+# This target builds a test program to verify interrupt context switching. irqtest is
+# a PHONY target that just sets upt the up_irqtest build correctly
+
+up_irqtest.ihx: $(TEST_COBJS)
+ $(CC) $(LDFLAGS) -L. $(SDCCPATH) $(HEAD_AOBJ) $(TEST_COBJS) $(TESTEXTRAOBJS) $(SDCCLIBS) -o $@
+
+irqtest:
+ $(MAKE) TOPDIR=../../.. up_irqtest.ihx
+
+# Build dependencies
+
+.depend: Makefile up_mem.h chip/Make.defs $(DEPSRCS)
+ @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) up_mem.h
+ rm -f *.asm *.rel *.lst *.rst *.sym *.adb *.lnk *.map *.mem *.ihx *.hex *~
+ 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/z80/src/common/up_allocateheap.c b/nuttx/arch/z80/src/common/up_allocateheap.c
new file mode 100644
index 000000000..04e5f2d99
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_allocateheap.c
@@ -0,0 +1,79 @@
+/****************************************************************************
+ * common/up_allocateheap.c
+ *
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+#include "up_arch.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_allocate_heap
+ *
+ * Description:
+ * The heap may be statically allocated by
+ * defining CONFIG_HEAP_BASE and CONFIG_HEAP_SIZE. If these
+ * are not defined, then this function will be called to
+ * dynamically set aside the heap region.
+ *
+ ****************************************************************************/
+
+void up_allocate_heap(FAR void **heap_start, size_t *heap_size)
+{
+ up_ledon(LED_HEAPALLOCATE);
+ *heap_start = (void*)(CONFIG_DRAM_SIZE - CONFIG_HEAP_SIZE);
+ *heap_size = CONFIG_HEAP_SIZE;
+}
diff --git a/nuttx/arch/z80/src/common/up_arch.h b/nuttx/arch/z80/src/common/up_arch.h
new file mode 100644
index 000000000..b0158325a
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_arch.h
@@ -0,0 +1,70 @@
+/************************************************************************************
+ * common/up_arch.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 __UP_ARCH_H
+#define __UP_ARCH_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#ifndef __ASSEMBLY__
+# include <sys/types.h>
+#endif
+
+#include <arch/board/board.h>
+#include "chip.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Inline Functions
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+# define getreg8(a) (*(volatile ubyte *)(a))
+# define putreg8(v,a) (*(volatile ubyte *)(a) = (v))
+# define getreg32(a) (*(volatile uint32 *)(a))
+# define putreg32(v,a) (*(volatile uint32 *)(a) = (v))
+# define getreg(a) getreg16(1)
+# define putreg(v,a) putreg16(v,a)
+
+#endif
+
+#endif /* __UP_ARCH_H */
diff --git a/nuttx/arch/z80/src/common/up_assert.c b/nuttx/arch/z80/src/common/up_assert.c
new file mode 100644
index 000000000..f226c9431
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_assert.c
@@ -0,0 +1,156 @@
+/****************************************************************************
+ * common/up_assert.c
+ *
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdlib.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include <chip/chip.h>
+
+#include "up_arch.h"
+#include "os_internal.h"
+#include "up_internal.h"
+#include "up_mem.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Output debug info if stack dump is selected -- even if
+ * debug is not selected.
+ */
+
+#ifdef CONFIG_ARCH_STACKDUMP
+# undef lldbg
+# define lldbg lib_lowprintf
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: _up_assert
+ ****************************************************************************/
+
+static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
+{
+ /* Are we in an interrupt handler or the idle task? */
+
+ if (up_interrupt_context() || ((FAR _TCB*)g_readytorun.head)->pid == 0)
+ {
+ (void)irqsave();
+ for(;;)
+ {
+#ifdef CONFIG_ARCH_LEDS
+ up_ledon(LED_PANIC);
+ up_mdelay(250);
+ up_ledoff(LED_PANIC);
+ up_mdelay(250);
+#endif
+ }
+ }
+ else
+ {
+ exit(errorcode);
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_assert
+ ****************************************************************************/
+
+void up_assert(const ubyte *filename, int lineno)
+{
+#if CONFIG_TASK_NAME_SIZE > 0
+ _TCB *rtcb = (_TCB*)g_readytorun.head;
+#endif
+
+ up_ledon(LED_ASSERTION);
+
+#if CONFIG_TASK_NAME_SIZE > 0
+ lldbg("Assertion failed at file:%s line: %d task: %s\n",
+ filename, lineno, rtcb->name);
+#else
+ lldbg("Assertion failed at file:%s line: %d\n",
+ filename, lineno);
+#endif
+
+ up_stackdump();
+ up_registerdump();
+ _up_assert(EXIT_FAILURE);
+}
+
+/****************************************************************************
+ * Name: up_assert_code
+ ****************************************************************************/
+
+void up_assert_code(const ubyte *filename, int lineno, int errorcode)
+{
+#if CONFIG_TASK_NAME_SIZE > 0
+ _TCB *rtcb = (_TCB*)g_readytorun.head;
+#endif
+
+ up_ledon(LED_ASSERTION);
+
+#if CONFIG_TASK_NAME_SIZE > 0
+ lldbg("Assertion failed at file:%s line: %d task: %s error code: %d\n",
+ filename, lineno, rtcb->name, errorcode);
+#else
+ lldbg("Assertion failed at file:%s line: %d error code: %d\n",
+ filename, lineno, errorcode);
+#endif
+
+ up_stackdump();
+ up_registerdump();
+ _up_assert(errorcode);
+}
diff --git a/nuttx/arch/z80/src/common/up_blocktask.c b/nuttx/arch/z80/src/common/up_blocktask.c
new file mode 100644
index 000000000..b2d014bca
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_blocktask.c
@@ -0,0 +1,173 @@
+/****************************************************************************
+ * common/up_blocktask.c
+ *
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Funtions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Funtions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_block_task
+ *
+ * Description:
+ * The currently executing task at the head of
+ * the ready to run list must be stopped. Save its context
+ * and move it to the inactive list specified by task_state.
+ *
+ * Inputs:
+ * tcb: Refers to a task in the ready-to-run list (normally
+ * the task at the the head of the list). It most be
+ * stopped, its context saved and moved into one of the
+ * waiting task lists. It it was the task at the head
+ * of the ready-to-run list, then a context to the new
+ * ready to run task must be performed.
+ * task_state: Specifies which waiting task list should be
+ * hold the blocked task TCB.
+ *
+ ****************************************************************************/
+
+void up_block_task(FAR _TCB *tcb, tstate_t task_state)
+{
+ /* Verify that the context switch can be performed */
+
+ if ((tcb->task_state < FIRST_READY_TO_RUN_STATE) ||
+ (tcb->task_state > LAST_READY_TO_RUN_STATE))
+ {
+ PANIC(OSERR_BADBLOCKSTATE);
+ }
+ else
+ {
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+ boolean switch_needed;
+
+ /* dbg("Blocking TCB=%p\n", tcb); */
+
+ /* Remove the tcb task from the ready-to-run list. If we
+ * are blocking the task at the head of the task list (the
+ * most likely case), then a context switch to the next
+ * ready-to-run task is needed. In this case, it should
+ * also be true that rtcb == tcb.
+ */
+
+ switch_needed = sched_removereadytorun(tcb);
+
+ /* Add the task to the specified blocked task list */
+
+ sched_addblocked(tcb, (tstate_t)task_state);
+
+ /* If there are any pending tasks, then add them to the g_readytorun
+ * task list now
+ */
+
+ if (g_pendingtasks.head)
+ {
+ switch_needed |= sched_mergepending();
+ }
+
+ /* Now, perform the context switch if one is needed */
+
+ if (switch_needed)
+ {
+ /* Are we in an interrupt handler? */
+
+ if (IN_INTERRUPT)
+ {
+ /* Yes, then we have to do things differently.
+ * Just copy the current registers into the OLD rtcb.
+ */
+
+ SAVE_IRQCONTEXT(rtcb);
+
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (FAR _TCB*)g_readytorun.head;
+ /* dbg("New Active Task TCB=%p\n", rtcb); */
+
+ /* Then setup so that the context will be performed on exit
+ * from the interrupt.
+ */
+
+ SET_IRQCONTEXT(rtcb);
+ }
+
+ /* Copy the user C context into the TCB at the (old) head of the
+ * g_readytorun Task list. if SAVE_USERCONTEXT returns a non-zero
+ * value, then this is really the previously running task restarting!
+ */
+
+ else if (!SAVE_USERCONTEXT(rtcb))
+ {
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (FAR _TCB*)g_readytorun.head;
+ /* dbg("New Active Task TCB=%p\n", rtcb); */
+
+ /* Then switch contexts */
+
+ RESTORE_USERCONTEXT(rtcb);
+ }
+ }
+ }
+}
diff --git a/nuttx/arch/z80/src/common/up_copystate.c b/nuttx/arch/z80/src/common/up_copystate.c
new file mode 100644
index 000000000..8a4915181
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_copystate.c
@@ -0,0 +1,78 @@
+/****************************************************************************
+ * common/up_copystate.c
+ *
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <arch/irq.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Funtions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_undefinedinsn
+ ****************************************************************************/
+
+/* Maybe a little faster than most memcpy's */
+
+void up_copystate(FAR chipreg_t *dest, FAR const chipreg_t *src)
+{
+ int i;
+ for (i = 0; i < XCPTCONTEXT_REGS; i++)
+ {
+ *dest++ = *src++;
+ }
+}
+
diff --git a/nuttx/arch/z80/src/common/up_createstack.c b/nuttx/arch/z80/src/common/up_createstack.c
new file mode 100644
index 000000000..dc3f715c9
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_createstack.c
@@ -0,0 +1,128 @@
+/****************************************************************************
+ * common/up_createstack.c
+ *
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+#include <nuttx/kmalloc.h>
+#include <nuttx/arch.h>
+#include "up_arch.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_create_stack
+ *
+ * Description:
+ * Allocate a stack for a new thread and setup
+ * up stack-related information in the TCB.
+ *
+ * The following TCB fields must be initialized:
+ * adj_stack_size: Stack size after adjustment for hardware,
+ * processor, etc. This value is retained only for debug
+ * purposes.
+ * stack_alloc_ptr: Pointer to allocated stack
+ * adj_stack_ptr: Adjusted stack_alloc_ptr for HW. The
+ * initial value of the stack pointer.
+ *
+ * Inputs:
+ * tcb: The TCB of new task
+ * stack_size: The requested stack size. At least this much
+ * must be allocated.
+ ****************************************************************************/
+
+STATUS up_create_stack(_TCB *tcb, size_t stack_size)
+{
+ if (tcb->stack_alloc_ptr &&
+ tcb->adj_stack_size != stack_size)
+ {
+ sched_free(tcb->stack_alloc_ptr);
+ tcb->stack_alloc_ptr = NULL;
+ }
+
+ if (!tcb->stack_alloc_ptr)
+ {
+ tcb->stack_alloc_ptr = (uint32 *)kzmalloc(stack_size);
+ }
+
+ if (tcb->stack_alloc_ptr)
+ {
+ size_t top_of_stack;
+ size_t size_of_stack;
+
+ /* The Arm7Tdmi uses a push-down stack: the stack grows
+ * toward loweraddresses in memory. The stack pointer
+ * register, points to the lowest, valid work address
+ * (the "top" of the stack). Items on the stack are
+ * referenced as positive word offsets from sp.
+ */
+
+ top_of_stack = (uint32)tcb->stack_alloc_ptr + stack_size - 4;
+
+ /* The Arm7Tdmi stack must be aligned at word (4 byte)
+ * boundaries. If necessary top_of_stack must be rounded
+ * down to the next boundary
+ */
+
+ top_of_stack &= ~3;
+ size_of_stack = top_of_stack - (uint32)tcb->stack_alloc_ptr + 4;
+
+ /* Save the adjusted stack values in the _TCB */
+
+ tcb->adj_stack_ptr = (uint32*)top_of_stack;
+ tcb->adj_stack_size = size_of_stack;
+
+ up_ledon(LED_STACKCREATED);
+ return OK;
+ }
+
+ return ERROR;
+}
diff --git a/nuttx/arch/z80/src/common/up_doirq.c b/nuttx/arch/z80/src/common/up_doirq.c
new file mode 100644
index 000000000..d21cefabb
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_doirq.c
@@ -0,0 +1,104 @@
+/****************************************************************************
+ * common/up_doirq.c
+ *
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include <assert.h>
+#include "up_arch.h"
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Funtions
+ ****************************************************************************/
+
+void up_doirq(int irq, chipreg_t *regs)
+{
+ up_ledon(LED_INIRQ);
+#ifdef CONFIG_SUPPRESS_INTERRUPTS
+ PANIC(OSERR_ERREXCEPTION);
+#else
+ if ((unsigned)irq < NR_IRQS)
+ {
+ /* Current regs non-zero indicates that we are processing
+ * an interrupt; current_regs is also used to manage
+ * interrupt level context switches.
+ */
+
+ current_regs = regs;
+
+ /* Mask and acknowledge the interrupt */
+
+ up_maskack_irq(irq);
+
+ /* Deliver the IRQ */
+
+ irq_dispatch(irq, regs);
+
+ /* Indicate that we are no long in an interrupt handler */
+
+ current_regs = NULL;
+
+ /* Unmask the last interrupt (global interrupts are still
+ * disabled.
+ */
+
+ up_enable_irq(irq);
+ }
+ up_ledoff(LED_INIRQ);
+#endif
+}
diff --git a/nuttx/arch/z80/src/common/up_exit.c b/nuttx/arch/z80/src/common/up_exit.c
new file mode 100644
index 000000000..8784f2f78
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_exit.c
@@ -0,0 +1,200 @@
+/****************************************************************************
+ * common/up_exit.c
+ *
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <chip/chip.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+#ifdef CONFIG_DUMP_ON_EXIT
+#include <nuttx/fs.h>
+#endif
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Funtions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: _up_dumponexit
+ *
+ * Description:
+ * Dump the state of all tasks whenever on task exits. This
+ * is debug instrumentation that was added to check file-
+ * related reference counting but could be useful again
+ * sometime in the future.
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG)
+static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg)
+{
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0
+ int i;
+#endif
+
+ dbg(" TCB=%p name=%s\n", tcb, tcb->argv[0]);
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+ if (tcb->filelist)
+ {
+ lldbg(" filelist refcount=%d\n",
+ tcb->filelist->fl_crefs);
+
+ for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++)
+ {
+ struct inode *inode = tcb->filelist->fl_files[i].f_inode;
+ if (inode)
+ {
+ lldbg(" fd=%d refcount=%d\n",
+ i, inode->i_crefs);
+ }
+ }
+ }
+#endif
+
+#if CONFIG_NFILE_STREAMS > 0
+ if (tcb->streams)
+ {
+ lldbg(" streamlist refcount=%d\n",
+ tcb->streams->sl_crefs);
+
+ for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
+ {
+ struct file_struct *filep = &tcb->streams->sl_streams[i];
+ if (filep->fs_filedes >= 0)
+ {
+ lldbg(" fd=%d nbytes=%d\n",
+ filep->fs_filedes,
+ filep->fs_bufpos - filep->fs_bufstart);
+ }
+ }
+ }
+#endif
+}
+#endif
+
+/****************************************************************************
+ * Public Funtions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: _exit
+ *
+ * Description:
+ * This function causes the currently executing task to cease
+ * to exist. This is a special case of task_delete().
+ *
+ ****************************************************************************/
+
+void _exit(int status)
+{
+ FAR _TCB* tcb = (FAR _TCB*)g_readytorun.head;
+
+ /* Disable interrupts. Interrupts will remain disabled until
+ * the new task is resumed below.
+ */
+
+ (void)irqsave();
+
+ lldbg("TCB=%p exitting\n", tcb);
+
+#if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG)
+ lldbg("Other tasks:\n");
+ sched_foreach(_up_dumponexit, NULL);
+#endif
+
+ /* Remove the tcb task from the ready-to-run list. We can
+ * ignore the return value because we know that a context
+ * switch is needed.
+ */
+
+ (void)sched_removereadytorun(tcb);
+
+ /* We are not in a bad stack-- the head of the ready to run task list
+ * does not correspond to the thread that is running. Disabling pre-
+ * emption on this TCB should be enough to keep things stable.
+ */
+
+ sched_lock();
+
+ /* Move the TCB to the specified blocked task list and delete it */
+
+ sched_addblocked(tcb, TSTATE_TASK_INACTIVE);
+ task_delete(tcb->pid);
+
+ /* If there are any pending tasks, then add them to the g_readytorun
+ * task list now
+ */
+
+ if (g_pendingtasks.head)
+ {
+ (void)sched_mergepending();
+ }
+
+ /* Now calling sched_unlock() should have no effect */
+
+ sched_unlock();
+
+ /* Now, perform the context switch to the new ready-to-run task at the
+ * head of the list.
+ */
+
+ tcb = (FAR _TCB*)g_readytorun.head;
+ lldbg("New Active Task TCB=%p\n", tcb);
+
+ /* Then switch contexts */
+
+ RESTORE_USERCONTEXT(tcb);
+}
+
diff --git a/nuttx/arch/z80/src/common/up_head.asm b/nuttx/arch/z80/src/common/up_head.asm
new file mode 100644
index 000000000..272754e05
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_head.asm
@@ -0,0 +1,157 @@
+;**************************************************************************
+; arch/z80/src/common/up_head.S
+;
+; Copyright (C) 2007, 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.
+;
+;**************************************************************************
+
+ .title NuttX for the Z80
+ .module z80_head
+
+;**************************************************************************
+; Constants
+;**************************************************************************
+
+ ; Register save area layout
+
+ XCPT_PC == 0 ; Offset to PC at time of interrupt
+ XCPT_AF == 2 ; Saved AF register
+ XCPT_HL == 4 ; Saved HL register
+ XCPT_SP == 6 ; Offset to SP at time of interrupt
+ XCPT_IY == 8 ; Saved IY register
+ XCPT_IX == 10 ; Saved IX register
+ XCPT_DE == 12 ; Saved DE register
+ XCPT_BC == 14 ; Saved BC register
+ XCPT_I == 16 ; Saved I w/interrupt state in carry
+
+;**************************************************************************
+; Global symbols used
+;**************************************************************************
+
+ .globl _os_start ; OS entry point
+ .globl _idle_stack ; Top of allocated stack region
+ .globl _up_irqdecode ; Interrupt decoding logic
+
+;**************************************************************************
+; Reset entry point
+;**************************************************************************
+
+ .area TEXT (ABS,OVR)
+ .org 0x0000
+
+ .globl _os_start
+ di ; Disable interrupts
+ ld SP, #_idle_stack ; Set stack pointer
+ im 1 ; Set interrupt mode 1
+ jp _os_start ; jump to the OS entry point
+forever:
+ jp forever
+
+;**************************************************************************
+; Interrupt handler
+;
+; Interrupt mode 1 behavior:
+;
+; 1. M1 cycle: 7 ticks
+; Acknowledge interrupt and decrements SP
+; 2. M2 cycle: 3 ticks
+; Writes the MS byte of the PC onto the stack and decrements SP
+; 3. M3 cycle: 3 ticks
+; Writes the LS byte of the PC onto the stack and sets the PC to 0x0038.
+;
+;**************************************************************************
+
+ .org 0x0038 ; Int mode 1
+
+ ; Create a register frame. SP points to top of frame + 2, pushes
+ ; decrement the stack pointer.
+ ; Offset 8: Return PC is already on the stack
+ push af ; Offset 7: AF (retaining flags)
+ push hl ; Offset 6: HL
+ ld hl, #-(3*2) ; HL is the value of the stack pointer before
+ add hl, sp ; the interrupt occurred
+ push hl ; Offset 5: Stack pointer
+ push iy ; Offset 4: IY
+ push ix ; Offset 3: IX
+ push de ; Offset 2: DE
+ push bc ; Offset 1: BC
+
+ ld a, i ; Carry bit holds interrupt state
+ push af ; Offset 0: I with interrupt state in carry
+ di
+
+ ; Call the interrupt decode logic
+ ; SP points to the beggining of the reg structure
+ ld hl, #0 ; Argument is the beginning of the reg structure
+ add hl, sp
+ push hl
+ call _up_irqdecode ; Decode the IRQ
+
+ ; Restore registers. HL points to the beginning of the reg structure to restore
+
+ ld sp, hl ; Use the temp stack pointer
+ ex af, af' ; Select alternate AF
+ pop af ; Offset 0: AF' = I with interrupt state in carry
+ pop bc ; Offset 1: BC
+ pop de ; Offset 2: DE
+ pop ix ; Offset 3: IX
+ pop iy ; Offset 4: IY
+ exx ; Use alternate BC/DE/HL
+ pop hl ; Offset 5: HL' = Stack pointer at time of interrupt
+ exx
+ pop hl ; Offset 6: HL
+ pop af ; Offset 7: AF
+
+ ; Restore the stack pointer
+
+ exx
+ ld sp, hl
+ exx
+
+ ; Restore interrupt state
+
+ ex af, af' ; Recover interrupt state
+ jr nc, nointenable ; No carry, IFF2=0, means disabled
+ ex af, af' ; Restore AF (before enabling interrupts)
+ ei ; yes
+ reti
+nointenable:
+ ex af, af' ; Restore AF
+ reti
+
+;**************************************************************************
+; NMI interrupt handler
+;**************************************************************************
+
+ .org 0x0066
+ retn
+
+
diff --git a/nuttx/arch/z80/src/common/up_idle.c b/nuttx/arch/z80/src/common/up_idle.c
new file mode 100644
index 000000000..e2fb1e00f
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_idle.c
@@ -0,0 +1,107 @@
+/****************************************************************************
+ * common/up_idle.c
+ *
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+
+#include <nuttx/arch.h>
+#include <arch/board/board.h>
+
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+#if defined(CONFIG_ARCH_LEDS) && defined(CONFIG_ARCH_BRINGUP)
+static ubyte g_ledtoggle = 0;
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_idle
+ *
+ * Description:
+ * up_idle() is the logic that will be executed when their
+ * is no other ready-to-run task. This is processor idle
+ * time and will continue until some interrupt occurs to
+ * cause a context switch from the idle task.
+ *
+ * Processing in this state may be processor-specific. e.g.,
+ * this is where power management operations might be
+ * performed.
+ *
+ ****************************************************************************/
+
+void up_idle(void)
+{
+#if defined(CONFIG_ARCH_LEDS) && defined(CONFIG_ARCH_BRINGUP)
+ g_ledtoggle++;
+ if (g_ledtoggle == 0x80)
+ {
+ up_ledon(LED_IDLE);
+ }
+ else if (g_ledtoggle == 0x00)
+ {
+ up_ledoff(LED_IDLE);
+ }
+#endif
+
+#if defined(CONFIG_SUPPRESS_INTERRUPTS) || defined(CONFIG_SUPPRESS_TIMER_INTS)
+ /* If the system is idle and there are no timer interrupts,
+ * then process "fake" timer interrupts. Hopefully, something
+ * will wake up.
+ */
+
+ sched_process_timer();
+#endif
+}
+
diff --git a/nuttx/arch/z80/src/common/up_initialize.c b/nuttx/arch/z80/src/common/up_initialize.c
new file mode 100644
index 000000000..a24d814dc
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_initialize.c
@@ -0,0 +1,158 @@
+/****************************************************************************
+ * common/up_initialize.c
+ *
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/fs.h>
+#include <nuttx/mm.h>
+#include <arch/board/board.h>
+
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Define to enable timing loop calibration */
+
+#undef CONFIG_ARCH_CALIBRATION
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_calibratedelay
+ *
+ * Description:
+ * Delay loops are provided for short timing loops. This function, if
+ * enabled, will just wait for 100 seconds. Using a stopwatch, you can
+ * can then determine if the timing loops are properly calibrated.
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_ARCH_CALIBRATION) & defined(CONFIG_DEBUG)
+static void up_calibratedelay(void)
+{
+ int i;
+ lldbg("Beginning 100s delay\n");
+ for (i = 0; i < 100; i++)
+ {
+ up_mdelay(1000);
+ }
+ lldbg("End 100s delay\n");
+}
+#else
+# define up_calibratedelay()
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_initialize
+ *
+ * Description:
+ * up_initialize will be called once during OS initialization after the
+ * basic OS services have been initialized. The architecture specific
+ * details of initializing the OS will be handled here. Such things as
+ * setting up interrupt service routines, starting the clock, and
+ * registering device drivers are some of the things that are different
+ * for each processor and hardware platform.
+ *
+ * up_initialize is called after the OS initialized but before the user
+ * initialization logic has been started and before the libraries have
+ * been initialized. OS services and driver services are available.
+ *
+ ****************************************************************************/
+
+void up_initialize(void)
+{
+ /* Initialize global variables */
+
+ current_regs = NULL;
+
+ /* Calibrate the timing loop */
+
+ up_calibratedelay();
+
+ /* Add extra memory fragments to the memory manager */
+
+#if CONFIG_MM_REGIONS > 1
+ up_addregion();
+#endif
+
+ /* Initialize the interrupt subsystem */
+
+ up_irqinitialize();
+
+ /* Initialize the system timer interrupt */
+
+#if !defined(CONFIG_SUPPRESS_INTERRUPTS) && !defined(CONFIG_SUPPRESS_TIMER_INTS)
+ up_timerinit();
+#endif
+
+ /* Register devices */
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+ devnull_register(); /* Standard /dev/null */
+#endif
+
+ /* Initialize the serial device driver */
+
+ up_serialinit();
+
+ /* Initialize the netwok */
+
+ up_netinitialize();
+ up_ledon(LED_IRQSENABLED);
+}
diff --git a/nuttx/arch/z80/src/common/up_initialstate.c b/nuttx/arch/z80/src/common/up_initialstate.c
new file mode 100644
index 000000000..0c87aa51d
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_initialstate.c
@@ -0,0 +1,91 @@
+/****************************************************************************
+ * common/up_initialstate.c
+ *
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <string.h>
+#include <nuttx/arch.h>
+
+#include "up_internal.h"
+#include "up_arch.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Funtions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Funtions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_initial_state
+ *
+ * Description:
+ * A new thread is being started and a new TCB
+ * has been created. This function is called to initialize
+ * the processor specific portions of the new TCB.
+ *
+ * This function must setup the intial architecture registers
+ * and/or stack so that execution will begin at tcb->start
+ * on the next context switch.
+ *
+ ****************************************************************************/
+
+void up_initial_state(_TCB *tcb)
+{
+ struct xcptcontext *xcp = &tcb->xcp;
+
+ /* Initialize the initial exception register context structure */
+
+ memset(xcp, 0, sizeof(struct xcptcontext));
+#ifndef CONFIG_SUPPRESS_INTERRUPTS
+ xcp->regs[XCPT_I] = 0x0001; /* Carry flag will enable interrupts */
+#endif
+ xcp->regs[XCPT_SP] = (uint16)tcb->adj_stack_ptr;
+ xcp->regs[XCPT_PC] = (uint16)tcb->start;
+}
diff --git a/nuttx/arch/z80/src/common/up_internal.h b/nuttx/arch/z80/src/common/up_internal.h
new file mode 100644
index 000000000..e3da89213
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_internal.h
@@ -0,0 +1,184 @@
+/****************************************************************************
+ * common/up_internal.h
+ *
+ * Copyright (C) 2007, 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 __UP_INTERNAL_H
+#define __UP_INTERNAL_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <arch/irq.h>
+#include <chip/chip.h>
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Bring-up debug configurations. These are here (vs defconfig)
+ * because these should only be controlled during low level
+ * board bring-up and not part of normal platform configuration.
+ */
+
+#undef CONFIG_SUPPRESS_INTERRUPTS /* Do not enable interrupts */
+#undef CONFIG_SUPPRESS_TIMER_INTS /* No timer */
+#undef CONFIG_SUPPRESS_SERIAL_INTS /* Console will poll */
+#undef CONFIG_SUPPRESS_UART_CONFIG /* Do not reconfig UART */
+#define CONFIG_DUMP_ON_EXIT 1 /* Dump task state on exit */
+
+/* Macros for portability */
+
+#define IN_INTERRUPT (current_regs != NULL)
+#define SAVE_IRQCONTEXT(tcb) up_copystate((tcb)->xcp.regs, current_regs)
+#define SET_IRQCONTEXT(tcb) up_copystate(current_regs, (tcb)->xcp.regs)
+#define SAVE_USERCONTEXT(tcb) up_saveusercontext((tcb)->xcp.regs)
+#define RESTORE_USERCONTEXT(tcb) up_restoreusercontext((tcb)->xcp.regs)
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+typedef void (*up_vector_t)(void);
+#endif
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+/* This holds a references to the current interrupt level
+ * register storage structure. If is non-NULL only during
+ * interrupt processing.
+ */
+
+extern uint16 *current_regs;
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/* Defined in up_copystate.c */
+
+extern void up_copystate(FAR chipreg_t *dest, FAR const chipreg_t *src);
+
+/* Defined in up_saveusercontext.asm */
+
+extern int up_saveusercontext(chipreg_t *regs);
+
+/* Defined in up_restoreusercontext.asm */
+
+extern int up_restoreusercontext(chipreg_t *regs);
+
+/* Supplied by board-specific logic */
+
+extern FAR chipreg_t *up_decodeirq(FAR chipreg_t *regs);
+extern void up_irqinitialize(void);
+extern int up_timerisr(int irq, FAR chipreg_t *regs);
+
+/* Defined in up_doirq.c */
+
+extern void up_doirq(int irq, FAR chipreg_t *regs);
+
+/* Define in up_sigdeliver */
+
+extern void up_sigdeliver(void);
+
+#ifdef CONFIG_DEBUG
+extern void up_lowputc(char ch);
+#else
+# define up_lowputc(ch)
+#endif
+
+/* Defined in up_allocateheap.c */
+
+#if CONFIG_MM_REGIONS > 1
+void up_addregion(void);
+#endif
+
+/* Defined in up_serial.c */
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+extern void up_earlyserialinit(void);
+extern void up_serialinit(void);
+#else
+# define up_earlyserialinit()
+# define up_serialinit()
+#endif
+
+/* Defined in up_timerisr.c */
+
+extern void up_timerinit(void);
+
+/* Defined in board/up_leds.c */
+
+#ifdef CONFIG_ARCH_LEDS
+extern void up_ledinit(void);
+extern void up_ledon(int led);
+extern void up_ledoff(int led);
+#else
+# define up_ledinit()
+# define up_ledon(led)
+# define up_ledoff(led)
+#endif
+
+/* Defined in board/up_network.c */
+
+#ifdef CONFIG_NET
+extern void up_netinitialize(void);
+#else
+# define up_netinitialize()
+#endif
+
+/* Return the current value of the stack pointer (used in stack dump logic) */
+
+extern uint16 up_getsp(void);
+
+/* Dump stack and registers */
+
+#ifdef CONFIG_ARCH_STACKDUMP
+extern void up_stackdump(void);
+extern void up_registerdump(void);
+#else
+# define up_stackdump()
+# define up_registerdump()
+#endif
+
+#endif /* __ASSEMBLY__ */
+
+#endif /* __UP_INTERNAL_H */
diff --git a/nuttx/arch/z80/src/common/up_interruptcontext.c b/nuttx/arch/z80/src/common/up_interruptcontext.c
new file mode 100644
index 000000000..6e9e752c9
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_interruptcontext.c
@@ -0,0 +1,68 @@
+/****************************************************************************
+ * common/up_interruptcontext.c
+ *
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <nuttx/arch.h>
+#include <nuttx/irq.h>
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_interrupt_context
+ *
+ * Description: Return TRUE is we are currently executing in
+ * the interrupt handler context.
+ ****************************************************************************/
+
+boolean up_interrupt_context(void)
+{
+ return current_regs != NULL;
+}
diff --git a/nuttx/arch/z80/src/common/up_mdelay.c b/nuttx/arch/z80/src/common/up_mdelay.c
new file mode 100644
index 000000000..33a813063
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_mdelay.c
@@ -0,0 +1,94 @@
+/****************************************************************************
+ * common/up_mdelay.c
+ *
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/arch.h>
+
+#ifdef CONFIG_BOARD_LOOPSPERMSEC
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_mdelay
+ *
+ * Description:
+ * Delay inline for the requested number of milliseconds.
+ * *** NOT multi-tasking friendly ***
+ *
+ * ASSUMPTIONS:
+ * The setting CONFIG_BOARD_LOOPSPERMSEC has been calibrated
+ *
+ ****************************************************************************/
+
+void up_mdelay(unsigned int milliseconds)
+{
+ volatile int i;
+ volatile int j;
+
+ for (i = 0; i < milliseconds; i++)
+ {
+ for (j = 0; j < CONFIG_BOARD_LOOPSPERMSEC; j++)
+ {
+ }
+ }
+}
+#endif /* CONFIG_BOARD_LOOPSPERMSEC */
+
diff --git a/nuttx/arch/z80/src/common/up_registerdump.c b/nuttx/arch/z80/src/common/up_registerdump.c
new file mode 100644
index 000000000..05761bf85
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_registerdump.c
@@ -0,0 +1,91 @@
+/****************************************************************************
+ * common/up_registerdump.c
+ *
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Output debug info if stack dump is selected -- even if
+ * debug is not selected.
+ */
+
+#ifdef CONFIG_ARCH_STACKDUMP
+# undef lldbg
+# define lldbg lib_lowprintf
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_registerdump
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_STACKDUMP
+static void up_registerdump(void)
+{
+ if (current_regs)
+ {
+ lldbg("AF: %04x I: %04x\n",
+ current_regs[XCPT_AF], current_regs[XCPT_I]);
+ lldbg("BC: %04x DE: %04x HL: %04x\n",
+ current_regs[XCPT_BC], current_regs[XCPT_DE], current_regs[XCPT_HL]);
+ lldbg("IX: %04x IY: %04x\n",
+ current_regs[XCPT_IX], current_regs[XCPT_IY]);
+ lldbg("SP: %04x PC: $04x\n"
+ current_regs[XCPT_SP], current_regs[XCPT_PC]);
+ }
+}
+#endif
diff --git a/nuttx/arch/z80/src/common/up_releasepending.c b/nuttx/arch/z80/src/common/up_releasepending.c
new file mode 100644
index 000000000..8bf0bf798
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_releasepending.c
@@ -0,0 +1,137 @@
+/****************************************************************************
+ * common/up_releasepending.c
+ *
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <chip/chip.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Funtions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Funtions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_release_pending
+ *
+ * Description:
+ * Release and ready-to-run tasks that have
+ * collected in the pending task list. This can call a
+ * context switch if a new task is placed at the head of
+ * the ready to run list.
+ *
+ ****************************************************************************/
+
+void up_release_pending(void)
+{
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+
+ lldbg("From TCB=%p\n", rtcb);
+
+ /* Merge the g_pendingtasks list into the g_readytorun task list */
+
+ /* sched_lock(); */
+ if (sched_mergepending())
+ {
+ /* The currently active task has changed! We will need to
+ * switch contexts. First check if we are operating in
+ * interrupt context:
+ */
+
+ if (IN_INTERRUPT)
+ {
+ /* Yes, then we have to do things differently.
+ * Just copy the current context into the OLD rtcb.
+ */
+
+ SAVE_IRQCONTEXT(rtcb);
+
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (FAR _TCB*)g_readytorun.head;
+ lldbg("New Active Task TCB=%p\n", rtcb);
+
+ /* Then setup so that the context will be performed on exit
+ * from the interrupt.
+ */
+
+ SET_IRQCONTEXT(rtcb);
+ }
+
+ /* Copy the exception context into the TCB of the task that
+ * was currently active. if SAVE_USERCONTEXT returns a non-zero
+ * value, then this is really the previously running task
+ * restarting!
+ */
+
+ else if (!SAVE_USERCONTEXT(rtcb))
+ {
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (FAR _TCB*)g_readytorun.head;
+ lldbg("New Active Task TCB=%p\n", rtcb);
+
+ /* Then switch contexts */
+
+ RESTORE_USERCONTEXT(rtcb);
+ }
+ }
+}
diff --git a/nuttx/arch/z80/src/common/up_releasestack.c b/nuttx/arch/z80/src/common/up_releasestack.c
new file mode 100644
index 000000000..b00b9ab0c
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_releasestack.c
@@ -0,0 +1,78 @@
+/************************************************************
+ * common/up_releasestack.c
+ *
+ * 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.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+#include "os_internal.h"
+#include "up_internal.h"
+
+/************************************************************
+ * Private Types
+ ************************************************************/
+
+/************************************************************
+ * Private Function Prototypes
+ ************************************************************/
+
+/************************************************************
+ * Global Functions
+ ************************************************************/
+
+/************************************************************
+ * Name: up_release_stack
+ *
+ * Description:
+ * A task has been stopped. Free all stack
+ * related resources retained int the defunct TCB.
+ *
+ ************************************************************/
+
+void up_release_stack(_TCB *dtcb)
+{
+ if (dtcb->stack_alloc_ptr)
+ {
+ sched_free(dtcb->stack_alloc_ptr);
+ dtcb->stack_alloc_ptr = NULL;
+ }
+
+ dtcb->adj_stack_size = 0;
+}
diff --git a/nuttx/arch/z80/src/common/up_reprioritizertr.c b/nuttx/arch/z80/src/common/up_reprioritizertr.c
new file mode 100644
index 000000000..e90bd7186
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_reprioritizertr.c
@@ -0,0 +1,185 @@
+/****************************************************************************
+ * common/up_reprioritizertr.c
+ *
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <chip/chip.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Funtions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Funtions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_reprioritize_rtr
+ *
+ * Description:
+ * Called when the priority of a running or
+ * ready-to-run task changes and the reprioritization will
+ * cause a context switch. Two cases:
+ *
+ * 1) The priority of the currently running task drops and the next
+ * task in the ready to run list has priority.
+ * 2) An idle, ready to run task's priority has been raised above the
+ * the priority of the current, running task and it now has the
+ * priority.
+ *
+ * Inputs:
+ * tcb: The TCB of the task that has been reprioritized
+ * priority: The new task priority
+ *
+ ****************************************************************************/
+
+void up_reprioritize_rtr(FAR _TCB *tcb, ubyte priority)
+{
+ /* Verify that the caller is sane */
+
+ if (tcb->task_state < FIRST_READY_TO_RUN_STATE ||
+ tcb->task_state > LAST_READY_TO_RUN_STATE ||
+ priority < SCHED_PRIORITY_MIN ||
+ priority > SCHED_PRIORITY_MAX)
+ {
+ PANIC(OSERR_BADREPRIORITIZESTATE);
+ }
+ else
+ {
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+ boolean switch_needed;
+
+ lldbg("TCB=%p PRI=%d\n", tcb, priority);
+
+ /* Remove the tcb task from the ready-to-run list.
+ * sched_removereadytorun will return TRUE if we just
+ * remove the head of the ready to run list.
+ */
+
+ switch_needed = sched_removereadytorun(tcb);
+
+ /* Setup up the new task priority */
+
+ tcb->sched_priority = (ubyte)priority;
+
+ /* Return the task to the specified blocked task list.
+ * sched_addreadytorun will return TRUE if the task was
+ * added to the new list. We will need to perform a context
+ * switch only if the EXCLUSIVE or of the two calls is non-zero
+ * (i.e., one and only one the calls changes the head of the
+ * ready-to-run list).
+ */
+
+ switch_needed ^= sched_addreadytorun(tcb);
+
+ /* Now, perform the context switch if one is needed */
+
+ if (switch_needed)
+ {
+ /* If we are going to do a context switch, then now is the right
+ * time to add any pending tasks back into the ready-to-run list.
+ * task list now
+ */
+
+ if (g_pendingtasks.head)
+ {
+ sched_mergepending();
+ }
+
+ /* Are we in an interrupt handler? */
+
+ if (IN_INTERRUPT)
+ {
+ /* Yes, then we have to do things differently.
+ * Just copy the current context into the OLD rtcb.
+ */
+
+ SAVE_IRQCONTEXT(rtcb);
+
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (FAR _TCB*)g_readytorun.head;
+ lldbg("New Active Task TCB=%p\n", rtcb);
+
+ /* Then setup so that the context will be performed on exit
+ * from the interrupt.
+ */
+
+ SET_IRQCONTEXT(rtcb);
+ }
+
+ /* Copy the exception context into the TCB at the (old) head of the
+ * g_readytorun Task list. if SAVE_USERCONTEXT returns a non-zero
+ * value, then this is really the previously running task restarting!
+ */
+
+ else if (!SAVE_USERCONTEXT(rtcb))
+ {
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (FAR _TCB*)g_readytorun.head;
+ lldbg("New Active Task TCB=%p\n", rtcb);
+
+ /* Then switch contexts */
+
+ RESTORE_USERCONTEXT(rtcb);
+ }
+ }
+ }
+}
diff --git a/nuttx/arch/z80/src/common/up_restoreusercontext.asm b/nuttx/arch/z80/src/common/up_restoreusercontext.asm
new file mode 100644
index 000000000..093d18b7c
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_restoreusercontext.asm
@@ -0,0 +1,99 @@
+;**************************************************************************
+; arch/z80/src/common/up_restoreusercontext.asm
+;
+; Copyright (C) 2007, 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.
+;
+;**************************************************************************
+
+ ; Register save area layout
+
+ XCPT_I == 0 ; Saved I w/interrupt state in carry
+ XCPT_AF == 2 ; Saved AF register
+ XCPT_BC == 4 ; Saved BC register
+ XCPT_DE == 6 ; Saved DE register
+ XCPT_HL == 8 ; Saved HL register
+ XCPT_IX == 10 ; Saved IX register
+ XCPT_IY == 12 ; Saved IY register
+ XCPT_SP == 14 ; Offset to SP at time of interrupt
+ XCPT_PC == 16 ; Offset to PC at time of interrupt
+
+;**************************************************************************
+; up_restoreusercontext
+;**************************************************************************
+
+ .org 0x0038 ; Int mode 1
+ .area TEXT (ABS,OVR)
+up_restoreusercontext:
+ ; On entry, stack contains return address (not used), then address
+ ; of the register save structure
+
+ ; Discard the return address, we won't be returning
+
+ pop hl
+
+ ; Get the address of the beginning of the state save area. Each
+ ; pop will increment to the next element of the structure
+
+ pop hl ; BC = Address of save structure
+ ld sp, hl ; SP points to top of storage area
+
+ ; Disable interrupts while we muck with the alternative registers
+
+ ; Restore registers. HL points to the beginning of the reg structure to restore
+
+ ex af, af' ; Select alternate AF
+ pop af ; Offset 0: AF' = I with interrupt state in carry
+ pop bc ; Offset 1: BC
+ pop de ; Offset 2: DE
+ pop ix ; Offset 3: IX
+ pop iy ; Offset 4: IY
+ exx ; Use alternate BC/DE/HL
+ pop hl ; Offset 5: HL' = Stack pointer at time of interrupt
+ exx
+ pop hl ; Offset 6: HL
+ pop af ; Offset 7: AF
+
+ ; Restore the stack pointer
+
+ exx
+ ld sp, hl
+ exx
+
+ ; Restore interrupt state
+
+ ex af, af' ; Recover interrupt state
+ jnc noinrestore ; No carry, IFF2=0, means disabled
+ ex af, af' ; Restore AF (before enabling interrupts)
+ ei ; yes
+ ret
+noinrestore:
+ ex af, af' ; Restore AF
+ ret
diff --git a/nuttx/arch/z80/src/common/up_saveusercontext.asm b/nuttx/arch/z80/src/common/up_saveusercontext.asm
new file mode 100644
index 000000000..9d25a7800
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_saveusercontext.asm
@@ -0,0 +1,143 @@
+;*************************************************************************
+; common/up_saveusercontext.S
+;
+; 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.
+;
+;*************************************************************************
+
+;*************************************************************************
+; Constants
+;*************************************************************************
+
+ ; Register save area layout
+
+ XCPT_I == 0 ; Saved I w/interrupt state in carry
+ XCPT_AF == 2 ; Saved AF register
+ XCPT_BC == 4 ; Saved BC register
+ XCPT_DE == 6 ; Saved DE register
+ XCPT_HL == 8 ; Saved HL register
+ XCPT_IX == 10 ; Saved IX register
+ XCPT_IY == 12 ; Saved IY register
+ XCPT_SP == 14 ; Offset to SP at time of interrupt
+ XCPT_PC == 16 ; Offset to PC at time of interrupt
+
+ ; Stack frame
+
+ FRAME_IY == 0 ; Location of IY on the stack
+ FRAME_IX == 2 ; Location of IX on the stack
+ FRAME_RET == 4 ; Location of return address on the stack
+ FRAME_REGS == 6 ; Location of reg save area on stack
+
+ SP_OFFSET == -6
+
+;*************************************************************************
+; Name: up_saveusercontext
+;*************************************************************************
+
+ .area TEXT (ABS,OVR)
+up_saveusercontext:
+ ; Set up a stack frame
+
+ push ix ; Save IX and IY
+ push iy
+ ld ix, #0
+ add ix, sp ; IX = stack frame
+
+ ; Fetch the address of the save area
+
+ ld l, FRAME_REGS(ix) ; HL = save area address
+ ld h, FRAME_REGS+1(ix) ;
+ ld iy, #0
+ add iy, hl ; IY = save area address
+
+ ; Then save the registers
+
+ ; Save the current interrupt state at offset 0
+
+ ld a, i ; Get interrupt state
+ push af
+ pop hl
+ ld (iy+XCPT_I), l ; Offset 0: I w/interrupt state in carry
+ ld (iy+XCPT_I+1), h
+
+ ; Save BC at offset 1
+
+ ld (iy+XCPT_BC), c ; Offset 1: BC
+ ld (iy+XCPT_BC+1), b
+
+ ; DE is not preserved (offset 2)
+
+ ; Save IX at offset 3
+
+ ld l, FRAME_IX(ix) ; HL = Saved alue of IX
+ ld h, FRAME_IX+1(ix) ;
+ ld (iy+XCPT_IX), l ; Offset 3: IX
+ ld (iy+XCPT_IX+1), h ;
+
+ ; Save IY at offset 4
+
+ ld l, FRAME_IY(ix) ; HL = Saved value of IY
+ ld h, FRAME_IY+1(ix) ;
+ ld (iy+XCPT_IY), l ; Offset 4: IY
+ ld (iy+XCPT_IY+1), h
+
+ ; Save that stack pointer as it would be upon return in offset 5
+
+ ld hl, #SP_OFFSET ; Value of stack pointer on return
+ add hl, sp
+ ld (iy+XCPT_SP), l ; Offset 5 SP
+ ld (iy+XCPT_SP+1), h
+
+ ; HL is saved as the value 1 at offset 6
+
+ xor a ; A = 0
+ ld (iy+XCPT_HL+1), a ; Offset 2: HL on return (=1)
+ inc a ; A = 1
+ ld (iy+XCPT_HL), a ;
+
+ ; AF is not preserved (offset 7)
+
+ ; Save the return address in offset 8
+
+ ld l, FRAME_RET(ix) ; HL = Saved return address
+ ld h, FRAME_RET+1(ix) ;
+ ld (iy+XCPT_PC), l ; Offset 8: PC
+ ld (iy+XCPT_PC+1), h
+
+ ; Return the value 0
+
+ xor a ; HL = return value of zero
+ ld l, a
+ ld h, a
+
+ pop iy
+ pop ix
+ ret
diff --git a/nuttx/arch/z80/src/common/up_schedulesigaction.c b/nuttx/arch/z80/src/common/up_schedulesigaction.c
new file mode 100644
index 000000000..90039df17
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_schedulesigaction.c
@@ -0,0 +1,190 @@
+/************************************************************
+ * common/up_schedulesigaction.c
+ *
+ * Copyright (C) 2007,2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+#include "os_internal.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+/************************************************************
+ * Private Definitions
+ ************************************************************/
+
+/************************************************************
+ * Private Data
+ ************************************************************/
+
+/************************************************************
+ * Private Funtions
+ ************************************************************/
+
+/************************************************************
+ * Public Funtions
+ ************************************************************/
+
+/************************************************************
+ * Name: up_schedule_sigaction
+ *
+ * Description:
+ * This function is called by the OS when one or more
+ * signal handling actions have been queued for execution.
+ * The architecture specific code must configure things so
+ * that the 'igdeliver' callback is executed on the thread
+ * specified by 'tcb' as soon as possible.
+ *
+ * This function may be called from interrupt handling logic.
+ *
+ * This operation should not cause the task to be unblocked
+ * nor should it cause any immediate execution of sigdeliver.
+ * Typically, a few cases need to be considered:
+ *
+ * (1) This function may be called from an interrupt handler
+ * During interrupt processing, all xcptcontext structures
+ * should be valid for all tasks. That structure should
+ * be modified to invoke sigdeliver() either on return
+ * from (this) interrupt or on some subsequent context
+ * switch to the recipient task.
+ * (2) If not in an interrupt handler and the tcb is NOT
+ * the currently executing task, then again just modify
+ * the saved xcptcontext structure for the recipient
+ * task so it will invoke sigdeliver when that task is
+ * later resumed.
+ * (3) If not in an interrupt handler and the tcb IS the
+ * currently executing task -- just call the signal
+ * handler now.
+ *
+ ************************************************************/
+
+void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
+{
+ /* Refuse to handle nested signal actions */
+
+ dbg("tcb=0x%p sigdeliver=0x%p\n", tcb, sigdeliver);
+
+ if (!tcb->xcp.sigdeliver)
+ {
+ irqstate_t flags;
+
+ /* Make sure that interrupts are disabled */
+
+ flags = irqsave();
+
+ /* First, handle some special cases when the signal is
+ * being delivered to the currently executing task.
+ */
+
+ dbg("rtcb=0x%p current_regs=0x%p\n", g_readytorun.head, current_regs);
+
+ if (tcb == (_TCB*)g_readytorun.head)
+ {
+ /* CASE 1: We are not in an interrupt handler and
+ * a task is signalling itself for some reason.
+ */
+
+ if (!current_regs)
+ {
+ /* In this case just deliver the signal now. */
+
+ sigdeliver(tcb);
+ }
+
+ /* CASE 2: We are in an interrupt handler AND the
+ * interrupted task is the same as the one that
+ * must receive the signal, then we will have to modify
+ * the return state as well as the state in the TCB.
+ */
+
+ else
+ {
+ /* Save the return lr and cpsr and one scratch register
+ * These will be restored by the signal trampoline after
+ * the signals have been delivered.
+ */
+
+ tcb->xcp.sigdeliver = sigdeliver;
+ tcb->xcp.saved_pc = current_regs[REG_PC];
+ tcb->xcp.saved_cpsr = current_regs[REG_CPSR];
+
+ /* Then set up to vector to the trampoline with interrupts
+ * disabled
+ */
+
+ current_regs[REG_PC] = (uint32)up_sigdeliver;
+ current_regs[REG_CPSR] = SVC_MODE | PSR_I_BIT | PSR_F_BIT;
+
+ /* And make sure that the saved context in the TCB
+ * is the same as the interrupt return context.
+ */
+
+ up_copystate(tcb->xcp.regs, current_regs);
+ }
+ }
+
+ /* Otherwise, we are (1) signaling a task is not running
+ * from an interrupt handler or (2) we are not in an
+ * interrupt handler and the running task is signalling
+ * some non-running task.
+ */
+
+ else
+ {
+ /* Save the return lr and cpsr and one scratch register
+ * These will be restored by the signal trampoline after
+ * the signals have been delivered.
+ */
+
+ tcb->xcp.sigdeliver = sigdeliver;
+ tcb->xcp.saved_pc = tcb->xcp.regs[REG_PC];
+ tcb->xcp.saved_cpsr = tcb->xcp.regs[REG_CPSR];
+
+ /* Then set up to vector to the trampoline with interrupts
+ * disabled
+ */
+
+ tcb->xcp.regs[REG_PC] = (uint32)up_sigdeliver;
+ tcb->xcp.regs[REG_CPSR] = SVC_MODE | PSR_I_BIT | PSR_F_BIT;
+ }
+
+ irqrestore(flags);
+ }
+}
diff --git a/nuttx/arch/z80/src/common/up_sigdeliver.c b/nuttx/arch/z80/src/common/up_sigdeliver.c
new file mode 100644
index 000000000..f8f0c79de
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_sigdeliver.c
@@ -0,0 +1,137 @@
+/************************************************************
+ * common/up_sigdeliver.c
+ *
+ * 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.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include "os_internal.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+/************************************************************
+ * Private Data
+ ************************************************************/
+
+/************************************************************
+ * Private Functions
+ ************************************************************/
+
+/************************************************************
+ * Public Funtions
+ ************************************************************/
+
+/************************************************************
+ * Name: up_sigdeliver
+ *
+ * Description:
+ * This is the a signal handling trampoline. When a
+ * signal action was posted. The task context was mucked
+ * with and forced to branch to this location with interrupts
+ * disabled.
+ *
+ ************************************************************/
+
+void up_sigdeliver(void)
+{
+#ifndef CONFIG_DISABLE_SIGNALS
+ _TCB *rtcb = (_TCB*)g_readytorun.head;
+ uint32 regs[XCPTCONTEXT_REGS];
+ sig_deliver_t sigdeliver;
+
+ /* Save the errno. This must be preserved throughout the
+ * signal handling so that the the user code final gets
+ * the correct errno value (probably EINTR).
+ */
+
+ int saved_errno = rtcb->errno;
+
+ up_ledon(LED_SIGNAL);
+
+ dbg("rtcb=%p sigdeliver=%p sigpendactionq.head=%p\n",
+ rtcb, rtcb->xcp.sigdeliver, rtcb->sigpendactionq.head);
+ ASSERT(rtcb->xcp.sigdeliver != NULL);
+
+ /* Save the real return state on the stack. */
+
+ up_copystate(regs, rtcb->xcp.regs);
+ regs[REG_PC] = rtcb->xcp.saved_pc;
+ regs[REG_CPSR] = rtcb->xcp.saved_cpsr;
+
+ /* Get a local copy of the sigdeliver function pointer.
+ * we do this so that we can nullify the sigdeliver
+ * function point in the TCB and accept more signal
+ * deliveries while processing the current pending
+ * signals.
+ */
+
+ sigdeliver = rtcb->xcp.sigdeliver;
+ rtcb->xcp.sigdeliver = NULL;
+
+ /* Then restore the task interrupt state. */
+
+ irqrestore(regs[REG_CPSR]);
+
+ /* Deliver the signals */
+
+ sigdeliver(rtcb);
+
+ /* Output any debug messaged BEFORE restoring errno
+ * (because they may alter errno), then restore the
+ * original errno that is needed by the user logic
+ * (it is probably EINTR).
+ */
+
+ dbg("Resuming\n");
+ rtcb->errno = saved_errno;
+
+ /* Then restore the correct state for this thread of
+ * execution.
+ */
+
+ up_ledoff(LED_SIGNAL);
+ up_fullcontextrestore(regs);
+#endif
+}
diff --git a/nuttx/arch/z80/src/common/up_stackdump.c b/nuttx/arch/z80/src/common/up_stackdump.c
new file mode 100644
index 000000000..00c923aa9
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_stackdump.c
@@ -0,0 +1,109 @@
+/****************************************************************************
+ * common/up_stackdump.c
+ *
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <debug.h>
+
+#include "up_arch.h"
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Output debug info if stack dump is selected -- even if
+ * debug is not selected.
+ */
+
+#ifdef CONFIG_ARCH_STACKDUMP
+# undef lldbg
+# define lldbg lib_lowprintf
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_getsp
+ ****************************************************************************/
+#warning TO BE PROVIDED
+
+/****************************************************************************
+ * Name: up_stackdump
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_STACKDUMP
+static void up_stackdump(void)
+{
+ _TCB *rtcb = (_TCB*)g_readytorun.head;
+ uint16 sp = up_getsp();
+ uint16 stack_base = (uint16)rtcb->adj_stack_ptr;
+ uint16 stack_size = (uint16)rtcb->adj_stack_size;
+
+ lldbg("stack_base: %04x\n", stack_base);
+ lldbg("stack_size: %04x\n", stack_size);
+ lldbg("sp: %04x\n", sp);
+
+ if (sp >= stack_base || sp < stack_base - stack_size)
+ {
+ lldbg("ERROR: Stack pointer is not within allocated stack\n");
+ return;
+ }
+ else
+ {
+ uint16 stack = sp & ~0x0f;
+
+ for (stack = sp & ~0x0f; stack < stack_base; stack += 8*sizeof(uint16))
+ {
+ uint16 *ptr = (uint16*)stack;
+ lldbg("%04x: %04x %04x %04x %04x %04x %04x %04x %04x\n",
+ stack, ptr[0], ptr[1], ptr[2], ptr[3],
+ ptr[4], ptr[5], ptr[6], ptr[7]);
+ }
+ }
+}
+#endif
diff --git a/nuttx/arch/z80/src/common/up_udelay.c b/nuttx/arch/z80/src/common/up_udelay.c
new file mode 100644
index 000000000..9982644ea
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_udelay.c
@@ -0,0 +1,132 @@
+/****************************************************************************
+ * common/up_udelay.c
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/arch.h>
+
+#ifdef CONFIG_BOARD_LOOPSPERMSEC
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#define CONFIG_BOARD_LOOPSPER100USEC ((CONFIG_BOARD_LOOPSPERMSEC+5)/10)
+#define CONFIG_BOARD_LOOPSPER10USEC ((CONFIG_BOARD_LOOPSPERMSEC+50)/100)
+#define CONFIG_BOARD_LOOPSPERUSEC ((CONFIG_BOARD_LOOPSPERMSEC+500)/1000)
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_udelay
+ *
+ * Description:
+ * Delay inline for the requested number of microseconds. NOTE: Because
+ * of all of the setup, several microseconds will be lost before the actual
+ * timing looop begins. Thus, the delay will always be a few microseconds
+ * longer than requested.
+ *
+ * *** NOT multi-tasking friendly ***
+ *
+ * ASSUMPTIONS:
+ * The setting CONFIG_BOARD_LOOPSPERMSEC has been calibrated
+ *
+ ****************************************************************************/
+
+void up_udelay(unsigned int microseconds)
+{
+ volatile int i;
+
+ /* We'll do this a little at a time because we expect that the
+ * CONFIG_BOARD_LOOPSPERUSEC is very inaccurate during to truncation in
+ * the divisions of its calculation. We'll use the largest values that
+ * we can in order to prevent significant error buildup in the loops.
+ */
+
+ while (microseconds > 1000)
+ {
+ for (i = 0; i < CONFIG_BOARD_LOOPSPERMSEC; i++)
+ {
+ }
+ microseconds -= 1000;
+ }
+
+ while (microseconds > 100)
+ {
+ for (i = 0; i < CONFIG_BOARD_LOOPSPER100USEC; i++)
+ {
+ }
+ microseconds -= 100;
+ }
+
+ while (microseconds > 10)
+ {
+ for (i = 0; i < CONFIG_BOARD_LOOPSPER10USEC; i++)
+ {
+ }
+ microseconds -= 10;
+ }
+
+ while (microseconds > 0)
+ {
+ for (i = 0; i < CONFIG_BOARD_LOOPSPERUSEC; i++)
+ {
+ }
+ microseconds--;
+ }
+}
+#endif /* CONFIG_BOARD_LOOPSPERMSEC */
+
diff --git a/nuttx/arch/z80/src/common/up_unblocktask.c b/nuttx/arch/z80/src/common/up_unblocktask.c
new file mode 100644
index 000000000..8934c700c
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_unblocktask.c
@@ -0,0 +1,168 @@
+/****************************************************************************
+ * common/up_unblocktask.c
+ *
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <chip/chip.h>
+
+#include "os_internal.h"
+#include "clock_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Funtions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Funtions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_unblock_task
+ *
+ * Description:
+ * A task is currently in an inactive task list
+ * but has been prepped to execute. Move the TCB to the
+ * ready-to-run list, restore its context, and start execution.
+ *
+ * Inputs:
+ * tcb: Refers to the tcb to be unblocked. This tcb is
+ * in one of the waiting tasks lists. It must be moved to
+ * the ready-to-run list and, if it is the highest priority
+ * ready to run taks, executed.
+ *
+ ****************************************************************************/
+
+void up_unblock_task(FAR _TCB *tcb)
+{
+ /* Verify that the context switch can be performed */
+
+ if ((tcb->task_state < FIRST_BLOCKED_STATE) ||
+ (tcb->task_state > LAST_BLOCKED_STATE))
+ {
+ PANIC(OSERR_BADUNBLOCKSTATE);
+ }
+ else
+ {
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+
+ /* dbg("Unblocking TCB=%p\n", tcb); */
+
+ /* Remove the task from the blocked task list */
+
+ sched_removeblocked(tcb);
+
+ /* Reset its timeslice. This is only meaningful for round
+ * robin tasks but it doesn't here to do it for everything
+ */
+
+#if CONFIG_RR_INTERVAL > 0
+ tcb->timeslice = CONFIG_RR_INTERVAL / MSEC_PER_TICK;
+#endif
+
+ /* Add the task in the correct location in the prioritized
+ * g_readytorun task list
+ */
+
+ if (sched_addreadytorun(tcb))
+ {
+ /* The currently active task has changed! We need to do
+ * a context switch to the new task.
+ *
+ * Are we in an interrupt handler?
+ */
+
+ if (IN_INTERRUPT)
+ {
+ /* Yes, then we have to do things differently.
+ * Just copy the current context into the OLD rtcb.
+ */
+
+ SAVE_IRQCONTEXT(rtcb);
+
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (FAR _TCB*)g_readytorun.head;
+ /* dbg("New Active Task TCB=%p\n", rtcb); */
+
+ /* Then setup so that the context will be performed on exit
+ * from the interrupt.
+ */
+
+ SET_IRQCONTEXT(rtcb);
+ }
+
+ /* We are not in an interrupt handler. Copy the user C context
+ * into the TCB of the task that was previously active. if
+ * SAVE_USERCONTEXT returns a non-zero value, then this is really the
+ * previously running task restarting!
+ */
+
+ else if (!SAVE_USERCONTEXT(rtcb))
+ {
+ /* Restore the exception context of the new task that is ready to
+ * run (probably tcb). This is the new rtcb at the head of the
+ * g_readytorun task list.
+ */
+
+ rtcb = (FAR _TCB*)g_readytorun.head;
+ /* dbg("New Active Task TCB=%p\n", rtcb); */
+
+ /* Then switch contexts */
+
+ RESTORE_USERCONTEXT(rtcb);
+ }
+ }
+ }
+}
diff --git a/nuttx/arch/z80/src/common/up_usestack.c b/nuttx/arch/z80/src/common/up_usestack.c
new file mode 100644
index 000000000..2da044182
--- /dev/null
+++ b/nuttx/arch/z80/src/common/up_usestack.c
@@ -0,0 +1,118 @@
+/************************************************************
+ * common/up_usestack.c
+ *
+ * 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.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+#include <nuttx/kmalloc.h>
+#include <nuttx/arch.h>
+#include "up_internal.h"
+
+/************************************************************
+ * Private Types
+ ************************************************************/
+
+/************************************************************
+ * Private Function Prototypes
+ ************************************************************/
+
+/************************************************************
+ * Global Functions
+ ************************************************************/
+
+/************************************************************
+ * Name: up_use_stack
+ *
+ * Description:
+ * Setup up stack-related information in the TCB
+ * using pre-allocated stack memory
+ *
+ * The following TCB fields must be initialized:
+ * adj_stack_size: Stack size after adjustment for hardware,
+ * processor, etc. This value is retained only for debug
+ * purposes.
+ * stack_alloc_ptr: Pointer to allocated stack
+ * adj_stack_ptr: Adjusted stack_alloc_ptr for HW. The
+ * initial value of the stack pointer.
+ *
+ * Inputs:
+ * tcb: The TCB of new task
+ * stack_size: The allocated stack size.
+ *
+ ************************************************************/
+
+STATUS up_use_stack(_TCB *tcb, void *stack, size_t stack_size)
+{
+ size_t top_of_stack;
+ size_t size_of_stack;
+
+ if (tcb->stack_alloc_ptr)
+ {
+ sched_free(tcb->stack_alloc_ptr);
+ }
+
+ /* Save the stack allocation */
+
+ tcb->stack_alloc_ptr = stack;
+
+ /* The Arm7Tdmi uses a push-down stack: the stack grows
+ * toward loweraddresses in memory. The stack pointer
+ * register, points to the lowest, valid work address
+ * (the "top" of the stack). Items on the stack are
+ * referenced as positive word offsets from sp.
+ */
+
+ top_of_stack = (uint32)tcb->stack_alloc_ptr + stack_size - 4;
+
+ /* The Arm7Tdmi stack must be aligned at word (4 byte)
+ * boundaries. If necessary top_of_stack must be rounded
+ * down to the next boundary
+ */
+
+ top_of_stack &= ~3;
+ size_of_stack = top_of_stack - (uint32)tcb->stack_alloc_ptr + 4;
+
+ /* Save the adjusted stack values in the _TCB */
+
+ tcb->adj_stack_size = top_of_stack;
+ tcb->adj_stack_size = size_of_stack;
+
+ return OK;
+}
diff --git a/nuttx/arch/z80/src/z80/Make.defs b/nuttx/arch/z80/src/z80/Make.defs
new file mode 100644
index 000000000..80d5c7c0b
--- /dev/null
+++ b/nuttx/arch/z80/src/z80/Make.defs
@@ -0,0 +1,48 @@
+############################################################################
+# sdcc/src/z80/Make.defs
+#
+# 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.
+#
+############################################################################
+
+HEAD_ASRC = up_head.asm
+
+CMN_ASRCS = up_saveusercontext.asm up_restoreusercontext.asm
+CMN_CSRCS = up_initialize.c up_allocateheap.c up_initialstate.c \
+ up_createstack.c up_releasestack.c up_interruptcontext.c \
+ up_blocktask.c up_unblocktask.c up_exit.c up_releasepending.c \
+ up_reprioritizertr.c up_copystate.c up_idle.c \
+ up_assert.c up_mdelay.c up_udelay.c \
+ up_registerdump.c up_usestack.c \
+
+CHIP_ASRCS =
+CHIP_CSRCS =
+
diff --git a/nuttx/arch/z80/src/z80/chip.h b/nuttx/arch/z80/src/z80/chip.h
new file mode 100644
index 000000000..9f85f1475
--- /dev/null
+++ b/nuttx/arch/z80/src/z80/chip.h
@@ -0,0 +1,66 @@
+/************************************************************************************
+ * z80/chip.h
+ * chip/chip.h
+ *
+ * Copyright (C) 2007, 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 __Z80_CHIP_H
+#define __Z80_CHIP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * 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 /* __Z80_CHIP_H */