summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/arch/README.txt40
-rw-r--r--nuttx/arch/z80/include/z8/irq.h23
-rw-r--r--nuttx/arch/z80/src/common/up_schedulesigaction.c2
-rw-r--r--nuttx/arch/z80/src/z8/Make.defs4
-rw-r--r--nuttx/arch/z80/src/z8/switch.h168
-rw-r--r--nuttx/arch/z80/src/z8/z8_initialstate.c93
-rw-r--r--nuttx/arch/z80/src/z8/z8_registerdump.c94
-rwxr-xr-xnuttx/arch/z80/src/z8/z8_restorecontext.S166
-rwxr-xr-xnuttx/arch/z80/src/z8/z8_saveusercontext.S165
-rw-r--r--nuttx/arch/z80/src/z80/z80_initialstate.c6
-rw-r--r--nuttx/configs/z8encore000zco/ostest/Make.defs5
11 files changed, 737 insertions, 29 deletions
diff --git a/nuttx/arch/README.txt b/nuttx/arch/README.txt
index 0e5581cc4..f0829273c 100644
--- a/nuttx/arch/README.txt
+++ b/nuttx/arch/README.txt
@@ -123,13 +123,13 @@ src/Makefile
Supported Architectures
^^^^^^^^^^^^^^^^^^^^^^^
-arch/sim
+arch/sim - Linux simulation
A user-mode port of NuttX to the x86 Linux platform is available.
The purpose of this port is primarily to support OS feature development.
This port does not support interrupts or a real timer (and hence no
round robin scheduler) Otherwise, it is complete.
-arch/arm
+arch/arm - ARM-based micro-controllers
This directory holds common ARM architectures. At present, this includes
the following subdirectories:
@@ -156,18 +156,36 @@ arch/m68322
A work in progress.
STATUS: Stalled for the moment.
-arch/pjrc-8051
+arch/pjrc-8051 - 8051/52 microcontrollers
8051 Microcontroller. This port is not quite ready for prime time.
-arch/z16
- ZiLOG z16f Microcontroller.
- STATUS: Released in nuttx-0.3.7. Fully functional other than issues
- addressed in ${TOPDIR}/TODO.
+arch/z16 - ZiLOG 16-bit processors
+ This directory holds related, 16-bit architectures from ZiLOG. At
+ present, this includes the following subdirectories:
-arch/z80
- ZiLOG z80 Microcontroller.
- STATUS: Functional with no known defects. There are still several
- OS features that have not yet been tested (e.g., networking).
+ arch/z16/include and arch/z16/common
+ Common microcontroller logic.
+
+ arch/z16/include/z16f and arch/z16/src/z16f
+ ZiLOG z16f Microcontroller.
+ STATUS: Released in nuttx-0.3.7. Fully functional other than issues
+ addressed in ${TOPDIR}/TODO.
+
+arch/z80 - ZiLOG 8-bit microcontrollers
+ This directory holds related, 8-bit architectures from ZiLOG. At
+ present, this includes the following subdirectories:
+
+ arch/z80/include and arch/z80/common
+ Common microcontroller logic.
+
+ arch/z80/include/z80 and arch/z80/src/z80
+ Classic ZiLOG z80 Microcontroller.
+ STATUS: Functional with no known defects. There are still several
+ OS features that have not yet been tested (e.g., networking).
+
+ arch/z80/include/z8 and arch/z80/src/z8
+ ZiLOG Z8Encore! Microcontroller
+ This is a work in progress.
The following architecture directories are deprecated. They have been
replaced by the logic in arm/arm and will deleted at some point in the
diff --git a/nuttx/arch/z80/include/z8/irq.h b/nuttx/arch/z80/include/z8/irq.h
index 15979c0a6..25d6d3ef4 100644
--- a/nuttx/arch/z80/include/z8/irq.h
+++ b/nuttx/arch/z80/include/z8/irq.h
@@ -236,11 +236,12 @@
#define XCPT_RR10 (5)
#define XCPT_RR12 (6)
#define XCPT_R1R4 (7)
-#define XCPT_SP (8) /* Index 8: SP[8:15] */
-#define XCPT_I (9) /* Index 9: FLAGS */
-#define XCPT_PC (10) /* Index 10: PC[8:15] */
+#define XCPT_IRQCTL (8) /* Index 8: IRQCTL register */
+#define XCPT_SP (9) /* Index 9: SP[8:15] */
+#define XCPT_RPFLAGS (10) /* Index 10: RP (MS) and FLAGS (LS) */
+#define XCPT_PC (11) /* Index 11: PC[8:15] */
-#define XCPTCONTEXT_REGS (11)
+#define XCPTCONTEXT_REGS (12)
/* Byte offsets: */
@@ -260,12 +261,14 @@
#define XCPT_R13_OFFS (2*XCPT_RR12+1)
#define XCPT_R14_OFFS (2*XCPT_R1R4)
#define XCPT_R15_OFFS (2*XCPT_R1R4+1)
-#define XCPT_SPH_OFFS (2*XCPT_SP) /* Offset 16: SP[8:15] */
-#define XCPT_SPL_OFFS (2*XCPT_SP+1) /* Offset 17: SP[0:7] */
-#define XCPT_RP_OFFS (2*XCPT_I) /* Offset 18: Register pointer */
-#define XCPT_FLAGS_OFFS (2*XCPT_I+1) /* Offset 19: FLAGS */
-#define XCPT_PCH_OFFS (2*XCPT_PC) /* Offset 20: PC[8:15] */
-#define XCPT_PCL_OFFS (2*XCPT_PC+1) /* Offset 21: PC[0:7] */
+#define XCPT_UNUSED_OFFS (2*XCPT_IRQCTL) /* Offset 16: Unused (zero) */
+#define XCPT_IRQCTL_OFFS (2*XCPT_IRQCTL+1) /* offset 17: IRQCTL register */
+#define XCPT_SPH_OFFS (2*XCPT_SP) /* Offset 18: SP[8:15] */
+#define XCPT_SPL_OFFS (2*XCPT_SP+1) /* Offset 19: SP[0:7] */
+#define XCPT_RP_OFFS (2*XCPT_I) /* Offset 20: Register pointer */
+#define XCPT_FLAGS_OFFS (2*XCPT_I+1) /* Offset 21: FLAGS */
+#define XCPT_PCH_OFFS (2*XCPT_PC) /* Offset 22: PC[8:15] */
+#define XCPT_PCL_OFFS (2*XCPT_PC+1) /* Offset 23: PC[0:7] */
#define XCPTCONTEXT_SIZE (2*XCPTCONTEXT_REGS)
diff --git a/nuttx/arch/z80/src/common/up_schedulesigaction.c b/nuttx/arch/z80/src/common/up_schedulesigaction.c
index bad83e551..2c4d4294d 100644
--- a/nuttx/arch/z80/src/common/up_schedulesigaction.c
+++ b/nuttx/arch/z80/src/common/up_schedulesigaction.c
@@ -161,7 +161,7 @@ void up_schedule_sigaction(FAR _TCB *tcb, sig_deliver_t sigdeliver)
{
/* Set up to vector to the trampoline with interrupts disabled. */
- SIGNAL_SETUP(tcb, sigdeliver, tcb->xcp.regs)
+ SIGNAL_SETUP(tcb, sigdeliver, tcb->xcp.regs);
}
irqrestore(flags);
diff --git a/nuttx/arch/z80/src/z8/Make.defs b/nuttx/arch/z80/src/z8/Make.defs
index da6d78a9e..9bff5da61 100644
--- a/nuttx/arch/z80/src/z8/Make.defs
+++ b/nuttx/arch/z80/src/z8/Make.defs
@@ -43,6 +43,6 @@ CMN_CSRCS = up_initialize.c up_allocateheap.c up_createstack.c \
up_mdelay.c up_udelay.c up_schedulesigaction.c \
up_sigdeliver.c up_usestack.c
-CHIP_SSRCS = z8_vector.S #z8_saveusercontext.S z8_restoreusercontext.S
-CHIP_CSRCS = #z8_initialstate.c z8_irq.c z8_copystate.c z8_registerdump.c
+CHIP_SSRCS = z8_vector.S z8_saveusercontext.S z8_restorecontext.S
+CHIP_CSRCS = z8_initialstate.c z8_copystate.c #z8_irq.c z8_registerdump.c
diff --git a/nuttx/arch/z80/src/z8/switch.h b/nuttx/arch/z80/src/z8/switch.h
new file mode 100644
index 000000000..d0ab4db13
--- /dev/null
+++ b/nuttx/arch/z80/src/z8/switch.h
@@ -0,0 +1,168 @@
+/************************************************************************************
+ * arch/z80/src/z8/switch.h
+ * arch/z80/src/chip/switch.h
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __Z80_SWITCH_H
+#define __Z80_SWITCH_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <sys/types.h>
+#include <nuttx/sched.h>
+#include <nuttx/arch.h>
+#include "up_internal.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Macros for portability */
+
+/* Initialize the IRQ state */
+
+#define INIT_IRQCONTEXT() current_regs = NULL
+
+/* IN_INTERRUPT returns TRUE if the system is current operating in the interrupt
+ * context. IN_INTERRUPT is the inline equivalent of up_interrupt_context().
+ */
+
+#define IN_INTERRUPT() (current_regs != NULL)
+
+/* The following macro is used when the system enters interrupt handling logic */
+
+#define IRQ_ENTER(irq, regs) current_regs = (regs)
+
+/* The following macro is used when the system exits interrupt handling logic */
+
+#define IRQ_LEAVE(irq) current_regs = NULL
+
+/* The following macro is used to sample the interrupt state (as a opaque handle) */
+
+#define IRQ_STATE() (current_regs)
+
+/* Copy a register state save structure to another location */
+
+#define COPYSTATE(r1,r2) z8_copystate(r1,r2)
+
+/* Save the current IRQ context in the specified TCB */
+
+#define SAVE_IRQCONTEXT(tcb) COPYSTATE((tcb)->xcp.regs, current_regs)
+
+/* Set the current IRQ context to the state specified in the TCB */
+
+#define SET_IRQCONTEXT(tcb) COPYSTATE(current_regs, (tcb)->xcp.regs)
+
+/* Save the user context in the specified TCB. User context saves can be simpler
+ * because only those registers normally saved in a C called need be stored.
+ */
+
+#define SAVE_USERCONTEXT(tcb) z8_saveusercontext((tcb)->xcp.regs)
+
+/* Restore the full context -- either a simple user state save or the full,
+ * IRQ state save.
+ */
+
+#define RESTORE_USERCONTEXT(tcb) z8_restorecontext((tcb)->xcp.regs)
+
+/* Verify that we have a signal handler */
+
+#define SIGNAL_DELIVERING(tcb) (tcb->xcp.sigdeliver != NULL)
+
+/* Setup the signal handler trampoline */
+
+#define SIGNAL_SETUP(tcb, sigdeliver, regs) z8_sigsetup(tcb, sigdeliver, regs)
+
+/* Return from a signal handler using the provided register context */
+
+#define SIGNAL_RETURN(regs) z8_restorecontext(regs)
+
+/* Dump the current machine registers */
+
+#define _REGISTER_DUMP() z8_registerdump()
+
+/************************************************************************************
+ * 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 chipreg_t *current_regs;
+#endif
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/* Defined in z8_copystate.c */
+
+EXTERN void z8_copystate(FAR chipreg_t *dest, FAR const chipreg_t *src);
+
+/* Defined in z8_saveusercontext.asm */
+
+EXTERN int z8_saveusercontext(FAR chipreg_t *regs);
+
+/* Defined in z8_restorecontext.asm */
+
+EXTERN int z8_restorecontext(FAR chipreg_t *regs);
+
+/* Defined in z8_sigsetup.c */
+
+EXTERN void z8_sigsetup(FAR _TCB *tcb, sig_deliver_t sigdeliver, FAR chipreg_t *regs);
+
+/* Defined in z8_registerdump.c */
+
+EXTERN void z8_registerdump(void);
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif /* __Z80_SWITCH_H */
diff --git a/nuttx/arch/z80/src/z8/z8_initialstate.c b/nuttx/arch/z80/src/z8/z8_initialstate.c
new file mode 100644
index 000000000..4d7ef4c17
--- /dev/null
+++ b/nuttx/arch/z80/src/z8/z8_initialstate.c
@@ -0,0 +1,93 @@
+/****************************************************************************
+ * arch/z80/src/z8/z8_initialstate.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <string.h>
+#include <nuttx/arch.h>
+
+#include "chip/chip.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * 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_IRQCTL] = %0080; /* IRQE bit will enable interrupts */
+#endif
+ xcp->regs[XCPT_RPFLAGS] = %e000; /* RP=%e0 */
+ xcp->regs[XCPT_SP] = (chipreg_t)tcb->adj_stack_ptr;
+ xcp->regs[XCPT_PC] = (chipreg_t)tcb->start;
+}
diff --git a/nuttx/arch/z80/src/z8/z8_registerdump.c b/nuttx/arch/z80/src/z8/z8_registerdump.c
new file mode 100644
index 000000000..8e789b88f
--- /dev/null
+++ b/nuttx/arch/z80/src/z8/z8_registerdump.c
@@ -0,0 +1,94 @@
+/****************************************************************************
+ * arch/z80/src/z8/z8_registerdump.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+
+#include "chip/switch.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: z80_registerdump
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_STACKDUMP
+static void z8_registerdump(void)
+{
+ if (current_regs)
+ {
+ lldbg("REGS: %04x %04x %04x %04x %04x %04x %04x %04x\n",
+ current_regs[XCPT_RR0], current_regs[XCPT_RR2],
+ current_regs[XCPT_RR4], current_regs[XCPT_RR6],
+ current_regs[XCPT_RR8], current_regs[XCPT_RR10],
+ current_regs[XCPT_RR12], current_regs[XCPT_RR14]);
+ lldbg("SP: %04x PC: %04x IRQCTL: %02x RP: %02x FLAGS: %02x\n",
+ current_regs[XCPT_SP], current_regs[XCPT_PC],
+ current_regs[XCPT_IRQCTL] & 0xff,
+ current_regs[XCPT_RPFLAGS] >> 8,
+ current_regs[XCPT_RPFLAGS] & 0xff);
+ }
+}
+#endif
diff --git a/nuttx/arch/z80/src/z8/z8_restorecontext.S b/nuttx/arch/z80/src/z8/z8_restorecontext.S
new file mode 100755
index 000000000..2f614556e
--- /dev/null
+++ b/nuttx/arch/z80/src/z8/z8_restorecontext.S
@@ -0,0 +1,166 @@
+/**************************************************************************
+ * arch/z80/src/z8/z8_saveusercontext.S
+ * Save the state of the current user thread
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS or IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER or CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, or CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS or SERVICES; LOSS
+ * OF USE, DATA, or PROFITS; or BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, or TORT (INCLUDING NEGLIGENCE or OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ **************************************************************************/
+
+/**************************************************************************
+ * Included Files
+ **************************************************************************/
+
+#include <nuttx/config.h>
+#include <arch/irq.h>
+#include <ez8.inc>
+
+/**************************************************************************
+ * Definitions
+ **************************************************************************/
+
+ xdef _z8_restorecontext
+
+/**************************************************************************
+ * Code
+ **************************************************************************/
+
+ segment CODE
+
+/****************************************************************************
+ * Name: _z8_restorecontext
+ *
+ * Description:
+ * Restore the task context that was previously saved via
+ * _z8_saveusercontext() or by interrupt handling. Unlike the
+ * _z8_saveusercontext() counterpart, we do not know the context of the
+ * restored task and, hence, we must handle the worst case -- restore
+ * everythihng.
+ *
+ * Parameters:
+ * On entry, the following stack organization is assumed:
+ *
+ * Pointer to the context save structure
+ * TOS -> Return address (2)
+ *
+ * Assumptions:
+ * Large model, dynamic frames
+ *
+ **************************************************************************/
+
+_z8_restorecontext:
+ /* Disable all interrupts because we are going to be using
+ * the IRQ register set.
+ */
+
+ di
+
+ /* Switch to IRQ register set */
+
+ srp #%f0
+
+ /* Get the rr0 = the current value of the stack pointer */
+
+ ldx r0, sph /* rr0 = stack pointer */
+ ldx r1, spl
+
+ /* Get rr6 = the pointer to the context save structure */
+
+ ldx r6, 2(rr0) /* rr6 = pointer to context structure */
+ ldx r7, 3(rr0)
+
+ /* Copy all registers into the user register area. NOTE: we
+ * should use the saved RP value to determine the destination
+ * address
+ */
+
+ ld r1, #%e0 /* r1 = destination address */
+ ld r2, r6 /* rr2 = source address */
+ ld r3, r7
+ ld r4, #16 /* r4 = number of bytes to copy */
+ cp r2, #0
+ jr z, _z8_restore2
+
+_z8_restore1:
+ ldx r0, @rr2
+ ld @r1, r0
+ inc r1
+ incw rr2
+ djnz r4, _z8_restore1
+
+ /* Set the new stack pointer */
+
+_z8_restore2:
+ ldx r0, XCPT_SPH_OFFS(rr6)
+ ldx r1, XCPT_SPL_OFFS(rr6)
+ ldx sph, r0
+ ldx spl, r1
+
+ /* Push the return address onto the stack */
+
+ ldx r0, XCPT_PCH_OFFS(rr6)
+ ldx r1, XCPT_PCL_OFFS(rr6)
+ push r1
+ push r0
+
+ /* Recover the flags settings.. but don't restore the flags yet */
+
+ ldx r1, XCPT_FLAGS_OFFS(rr6)
+
+ /* Determine whether interrupts must be enabled on return. This
+ * would be nicer to do below, but later we will need to preserve
+ * the condition codes in the flags.
+ */
+
+ ldx r0, XCPT_IRQCTL_OFFS(rr6)
+ tm r0, #%80
+ jr nz, _z8_returnenabled
+
+ /* Restore the flag settings */
+
+ ldx flags, r1
+
+ /* Restore the user register page and return with interrupts disabled */
+
+ srp #%e0 /* Does not effect flags */
+ ret /* Does not effect flags */
+
+_z8_returnenabled:
+ /* Restore the flag settings */
+
+ ldx flags, r1
+
+ /* Restore the user register page, re-enable interrupts and return */
+
+ srp #%e0 /* Does not effect flags */
+ ei /* Does not effect flags */
+ ret /* Does not effect flags */
+
+ end
diff --git a/nuttx/arch/z80/src/z8/z8_saveusercontext.S b/nuttx/arch/z80/src/z8/z8_saveusercontext.S
new file mode 100755
index 000000000..314cf3e77
--- /dev/null
+++ b/nuttx/arch/z80/src/z8/z8_saveusercontext.S
@@ -0,0 +1,165 @@
+/**************************************************************************
+ * arch/z80/src/z8/z8_saveusercontext.S
+ * Save the state of the current user thread
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS or IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER or CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, or CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS or SERVICES; LOSS
+ * OF USE, DATA, or PROFITS; or BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, or TORT (INCLUDING NEGLIGENCE or OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ **************************************************************************/
+
+/**************************************************************************
+ * Included Files
+ **************************************************************************/
+
+#include <nuttx/config.h>
+#include <arch/irq.h>
+#include <ez8.inc>
+
+/**************************************************************************
+ * Definitions
+ **************************************************************************/
+
+ xdef _z8_saveusercontext
+
+/**************************************************************************
+ * Code
+ **************************************************************************/
+
+ segment CODE
+
+/****************************************************************************
+ * Name: _z8_saveusercontext
+ *
+ * Description:
+ * Save the current state of the user thread. Since this function is
+ * called from user code, it is only necessary to save the parts of the
+ * context that must be preserved between function calls. This includes
+ *
+ * - Frame pointer (r14, r15)
+ * - Register pointer (RP)
+ * - Interrupt state (flags)
+ * - Stack pointer (sph, spl)
+ * - Return address
+ *
+ * Parameters:
+ * On entry, the following stack organization is assumed:
+ *
+ * Pointer to the context save structure
+ * TOS -> Return address (2)
+ *
+ * Assumptions:
+ * Large model, dynamic frames
+ *
+ **************************************************************************/
+
+_z8_saveusercontext:
+ /* Get the rr6 = the current value of the stack pointer */
+
+ ldx r6, sph /* rr6 = stack pointer */
+ ldx r7, spl
+
+ /* Get rr2 = the pointer to the context save structure */
+
+ ldx r2, 2(rr6) /* rr2 = pointer to context structure */
+ ldx r3, 3(rr6)
+
+ /* Get the value currently in the interrupt control register.
+ * Bit 7 (IRQE) determines whether or not interrupts are
+ * currently enabled (0:disabled, 1:enabled)
+ */
+
+ ldx r4, IRQCTL /* r4 = IRQCTL value */
+
+ /* Disable all interrupts so that there can be no concurrent
+ * modification of the TCB state save area.
+ */
+
+ di
+
+ /* Fetch and save the return address from the stack */
+
+ ldx r0, @rr6 /* rr0 = return address */
+ ldx r1, 1(rr6)
+ ldx XCPT_PCH_OFFS(rr2), r0
+ ldx XCPT_PCL_OFFS(rr2), r1
+
+ /* Fetch and save the register pointer */
+
+ ldx r0, rp /* r0 = register pointer */
+ ldx XCPT_RP_OFFS(rr2), r0
+
+ /* Calculate the value of the stack pointer on return
+ * from this function
+ */
+
+ ld r1, #3 /* rr0 = 3 */
+ clr r0
+ add r1, r7 /* rr0 = SP + 3 */
+ adc r0, r6
+ ldx XCPT_SPH_OFFS(rr2), r0
+ ldx XCPT_SPL_OFFS(rr2), r1
+
+ /* Save the IRQCTL register value */
+
+ clr r0
+ ldx XCPT_UNUSED_OFFS(rr2), r0
+ ldx XCPT_IRQCTL_OFFS(rr2), r4
+
+ /* Save the frame pointer (rr14) in the context structure */
+
+ ldx XCPT_R14_OFFS(rr2), r14
+ ldx XCPT_R15_OFFS(rr2), r15
+
+ /* Set the return value of 1 in the context structure. When the
+ * state is restored (via z8_restorecontext() or an interrupt
+ * return), the return value of 1 distinguishes the no-context-
+ * switch case.
+ */
+
+ /* clr r0 */
+ ld r1, #1
+ ldx XCPT_R0_OFFS(rr2), r0
+ ldx XCPT_R1_OFFS(rr2), r1
+
+ /* Setup to return zero for the no-context-switch case */
+
+ /* clr r0 */
+ clr r1
+
+ /* Now decide if we need to re-enable interrupts or not */
+
+ tm r4, #%80
+ jr z, _z8_noenable
+ ei
+_z8_noenable:
+ ret
+
+ end
+
diff --git a/nuttx/arch/z80/src/z80/z80_initialstate.c b/nuttx/arch/z80/src/z80/z80_initialstate.c
index 767c7b605..c63baa021 100644
--- a/nuttx/arch/z80/src/z80/z80_initialstate.c
+++ b/nuttx/arch/z80/src/z80/z80_initialstate.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * arch/z80/src/z80/up_initialstate.c
+ * arch/z80/src/z80/z80_initialstate.c
*
* Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
@@ -87,6 +87,6 @@ void up_initial_state(_TCB *tcb)
#ifndef CONFIG_SUPPRESS_INTERRUPTS
xcp->regs[XCPT_I] = Z80_C_FLAG; /* Carry flag will enable interrupts */
#endif
- xcp->regs[XCPT_SP] = (uint16)tcb->adj_stack_ptr;
- xcp->regs[XCPT_PC] = (uint16)tcb->start;
+ xcp->regs[XCPT_SP] = (chipreg_t)tcb->adj_stack_ptr;
+ xcp->regs[XCPT_PC] = (chipreg_t)tcb->start;
}
diff --git a/nuttx/configs/z8encore000zco/ostest/Make.defs b/nuttx/configs/z8encore000zco/ostest/Make.defs
index 030478e3d..ad5d6fda8 100644
--- a/nuttx/configs/z8encore000zco/ostest/Make.defs
+++ b/nuttx/configs/z8encore000zco/ostest/Make.defs
@@ -73,7 +73,8 @@ ARCHASMCPUFLAGS = -cpu:Z8F6423 -NOigcase -NOrevaa
ARCHASMLIST = -list -NOlistmac -name -pagelen:56 -pagewidth:80 -quiet
ARCHASMWARNINGS = -warn
ARCHASMDEFINES = -define:_Z8F6423=1 -define:_Z8ENCORE_64K_SERIES=1 -define:_Z8ENCORE_F642X=1 \ -define:__ASSEMBLY__
-ARCHASMINCLUDES = -include:'$(ETOPDIR)\include;$(EZDSSTDINCDIR);$(EZDSZILOGINCDIR)'
+ARCHASMINCLUDES = -include:'$(WTOPDIR)\include;$(WZDSSTDINCDIR);$(WZDSZILOGINCDIR)'
+EARCHASMINCLUDES = -include:'$(ETOPDIR)\include;$(EZDSSTDINCDIR);$(EZDSZILOGINCDIR)'
AFLAGS = $(ARCHASMCPUFLAGS) $(ARCHASMINCLUDES) $(ARCHASMLIST) \
$(ARCHASMWARNINGS) $(ARCHASMOPTIMIZATION)
@@ -86,7 +87,7 @@ else
endif
ARCHCPUFLAGS = -chartype:S -model:L -const:RAM -NOoptlink -promote -cpu:Z8F6423 -NOgenprintf \
- -asmsw:" $(ARCHASMCPUFLAGS) $(ARCHASMINCLUDES) $(ARCHASMWARNINGS) $(ARCHASMOPTIMIZATION)"
+ -asmsw:" $(ARCHASMCPUFLAGS) $(EARCHASMINCLUDES) $(ARCHASMWARNINGS) $(ARCHASMOPTIMIZATION)"
ARCHLIST = -keeplst -NOlist -NOlistinc -keepasm
ARCHPICFLAGS =
ARCHWARNINGS = -warn