From 739f1170b4d8b8f02e33c9f46ae933454ddf3078 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 23 Mar 2008 16:05:22 +0000 Subject: First clean ez80 compile & link git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@746 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/z80/src/ez80/Make.defs | 8 +- nuttx/arch/z80/src/ez80/ez80_copystate.c | 79 +++++++++++++ nuttx/arch/z80/src/ez80/ez80_irq.c | 6 + nuttx/arch/z80/src/ez80/ez80_registerdump.c | 102 +++++++++++++++++ nuttx/arch/z80/src/ez80/ez80_startup.asm | 4 +- nuttx/arch/z80/src/ez80/ez80f91_init.asm | 4 + nuttx/arch/z80/src/ez80/switch.h | 136 ++++------------------- nuttx/arch/z80/src/z80/z80_irq.c | 2 +- nuttx/arch/z80/src/z80/z80_registerdump.c | 2 +- nuttx/configs/ez80f910200kitg/src/ez80_lowinit.c | 6 +- 10 files changed, 226 insertions(+), 123 deletions(-) create mode 100644 nuttx/arch/z80/src/ez80/ez80_copystate.c create mode 100644 nuttx/arch/z80/src/ez80/ez80_registerdump.c (limited to 'nuttx') diff --git a/nuttx/arch/z80/src/ez80/Make.defs b/nuttx/arch/z80/src/ez80/Make.defs index b1deb49b4..1d9eba434 100644 --- a/nuttx/arch/z80/src/ez80/Make.defs +++ b/nuttx/arch/z80/src/ez80/Make.defs @@ -44,10 +44,10 @@ CMN_CSRCS = up_initialize.c up_allocateheap.c up_createstack.c \ up_mdelay.c up_udelay.c up_usestack.c CHIP_ASRCS = ez80_startup.asm ez80_saveusercontext.asm ez80_restorecontext.asm -ifeq ($(_EZ80F91),y) +ifeq ($(CONFIG_ARCH_CHIP_EZ80F91),y) CHIP_ASRCS += ez80f91_init.asm endif CHIP_SSRCS = -CHIP_CSRCS = ez80_initialstate.c ez80_irq.c ez80_schedulesigaction.c \ - ez80_sigdeliver.c ez80_timerisr.c ez80_lowuart.c ez80_serial.c \ - ez80_registerdump.c +CHIP_CSRCS = ez80_initialstate.c ez80_irq.c ez80_copystate.c \ + ez80_schedulesigaction.c ez80_sigdeliver.c ez80_timerisr.c \ + ez80_lowuart.c ez80_serial.c ez80_registerdump.c diff --git a/nuttx/arch/z80/src/ez80/ez80_copystate.c b/nuttx/arch/z80/src/ez80/ez80_copystate.c new file mode 100644 index 000000000..842457982 --- /dev/null +++ b/nuttx/arch/z80/src/ez80/ez80_copystate.c @@ -0,0 +1,79 @@ +/**************************************************************************** + * arch/z80/src/ez80/ez80_copystate.c + * + * Copyright (C) 2008 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include + +#include "chip/switch.h" +#include "os_internal.h" +#include "up_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: ez80_copystate + ****************************************************************************/ + +/* Maybe a little faster than most memcpy's */ + +void ez80_copystate(chipreg_t *dest, const chipreg_t *src) +{ + int i; + for (i = 0; i < XCPTCONTEXT_REGS; i++) + { + *dest++ = *src++; + } +} + diff --git a/nuttx/arch/z80/src/ez80/ez80_irq.c b/nuttx/arch/z80/src/ez80/ez80_irq.c index 29cb39f50..7702be3a6 100644 --- a/nuttx/arch/z80/src/ez80/ez80_irq.c +++ b/nuttx/arch/z80/src/ez80/ez80_irq.c @@ -54,6 +54,12 @@ * Public Data ****************************************************************************/ +/* This holds a references to the current interrupt level register storage + * structure. If is non-NULL only during interrupt processing. + */ + +chipreg_t *current_regs; + /**************************************************************************** * Private Data ****************************************************************************/ diff --git a/nuttx/arch/z80/src/ez80/ez80_registerdump.c b/nuttx/arch/z80/src/ez80/ez80_registerdump.c new file mode 100644 index 000000000..dace6ad65 --- /dev/null +++ b/nuttx/arch/z80/src/ez80/ez80_registerdump.c @@ -0,0 +1,102 @@ +/**************************************************************************** + * arch/z80/src/ez80/ez80_registerdump.c + * + * Copyright (C) 2008 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include + +#include +#include + +#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 ez80_registerdump(void) +{ + if (current_regs) + { + lldbg("AF: %02x|%02x I: %02x|%02x\n", + (ubyte*)current_regs)[XCPT_A_OFFSET], (ubyte*)current_regs)[XCPT_F_OFFSET], + (ubyte*)current_regs)[XCPT_IA_OFFSET], (ubyte*)current_regs)[XCPT_IF_OFFSET]); +#ifdef CONFIG_EZ80_Z80MODE + 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]); +#else + lldbg("BC: %06x DE: %06x HL: %06x\n", + current_regs[XCPT_BC], current_regs[XCPT_DE], current_regs[XCPT_HL]); + lldbg("IX: %06x IY: %06x\n", + current_regs[XCPT_IX], current_regs[XCPT_IY]); + lldbg("SP: %06x PC: %06x\n" + current_regs[XCPT_SP], current_regs[XCPT_PC]); +#endif + } +} +#endif diff --git a/nuttx/arch/z80/src/ez80/ez80_startup.asm b/nuttx/arch/z80/src/ez80/ez80_startup.asm index d3f5e6705..2173f80a4 100644 --- a/nuttx/arch/z80/src/ez80/ez80_startup.asm +++ b/nuttx/arch/z80/src/ez80/ez80_startup.asm @@ -49,7 +49,7 @@ xref _ez80_init xref _ez80_initvectors xref _ez80_initsysclk - xref _up_lowinit + xref _ez80_lowinit xref __low_bss ; Low address of bss segment xref __len_bss ; Length of bss segment @@ -141,7 +141,7 @@ _ez80_codedone: ; Perform board-specific intialization - call _up_lowinit + call _ez80_lowinit ; Then start NuttX diff --git a/nuttx/arch/z80/src/ez80/ez80f91_init.asm b/nuttx/arch/z80/src/ez80/ez80f91_init.asm index fa208882f..422c14f2d 100644 --- a/nuttx/arch/z80/src/ez80/ez80f91_init.asm +++ b/nuttx/arch/z80/src/ez80/ez80f91_init.asm @@ -77,7 +77,11 @@ PLL_ENABLE EQU %01 ; Global symbols used ;************************************************************************** +; Exported symbols xdef _ez80_init + xdef _ez80_initsysclk + +; Imported symbols xref __CS0_LBR_INIT_PARAM xref __CS0_UBR_INIT_PARAM xref __CS0_CTL_INIT_PARAM diff --git a/nuttx/arch/z80/src/ez80/switch.h b/nuttx/arch/z80/src/ez80/switch.h index 8aec784f2..ef78d8420 100644 --- a/nuttx/arch/z80/src/ez80/switch.h +++ b/nuttx/arch/z80/src/ez80/switch.h @@ -52,46 +52,6 @@ * Definitions ************************************************************************************/ -/* EZ80_IRQSTATE_* definitions ******************************************************** - * These are used in the state field of 'struct z8_irqstate_s' structure to define - * the current state of the interrupt handling. These definition support "lazy" - * interrupt context saving. See comments below associated with s'truct z8_irqstate_s'. - */ - -#define EZ80_IRQSTATE_NONE 0 /* Not handling an interrupt */ -#define EZ80_IRQSTATE_ENTRY 1 /* In interrupt, context has not been saved */ -#define EZ80_IRQSTATE_SAVED 2 /* In interrupt, context has been saved */ - -/* The information saved on interrupt entry can be retained in a array of two - * uint16 values. These are - * - * value[0] = RP (MS byte) and Flags (LS) byte - * value[1] = PC - * - * The pointer to the save structure is a stack pointer at the time that up_doirq() - * was called: - * - * PC[7:0] - * PC[15:8] - * Flags Register - * SP -> RP - * - * The stack pointer on return from interrupt can be obtained by adding 4 to the - * pointer to the save structure. - */ - -#define EZ80_IRQSAVE_RPFLAGS (0) /* Index 10: RP (MS) and FLAGS (LS) */ -#define EZ80_IRQSAVE_PC (1) /* Index 2: PC[8:15] */ -#define EZ80_IRQSAVE_REGS (2) /* Number 16-bit values saved */ - -/* Byte offsets */ - -#define EZ80_IRQSAVE_RP_OFFS (2*EZ80_IRQSAVE_RPFLAGS) /* Offset 0: RP */ -#define EZ80_IRQSAVE_FLAGS_OFFS (2*EZ80_IRQSAVE_RPFLAGS+1) /* Offset 1: FLAGS */ -#define EZ80_IRQSAVE_PCH_OFFS (2*EZ80_IRQSAVE_PC) /* Offset 2: PC[8:15] */ -#define EZ80_IRQSAVE_PCL_OFFS (2*EZ80_IRQSAVE_PC+1) /* Offset 3: PC[0:7] */ -#define EZ80_IRQSAVE_SIZE (2*EZ80_IRQSAVE_REGS) /* Number 8-bit values saved */ - /* Macros for portability *********************************************************** * * Common logic in arch/z80/src/common is customized for the z8 context switching @@ -100,108 +60,64 @@ /* Initialize the IRQ state */ -#define INIT_IRQCONTEXT() \ - do { \ - g_z8irqstate.state = EZ80_IRQSTATE_NONE; \ - } while (0) +#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() \ - (g_z8irqstate.state != EZ80_IRQSTATE_NONE) +#define IN_INTERRUPT() (current_regs != NULL) /* The following macro is used when the system enters interrupt handling logic */ -#define IRQ_ENTER(irq, regs) \ - do { \ - g_z8irqstate.state = EZ80_IRQSTATE_ENTRY; \ - g_z8irqstate.regs = (regs); \ - up_maskack_irq(irq); \ - } while (0) +#define IRQ_ENTER(irq, regs) current_regs = (regs) /* The following macro is used when the system exits interrupt handling logic */ -#define IRQ_LEAVE(irq) \ - do { \ - g_z8irqstate.state = EZ80_IRQSTATE_NONE; \ - up_enable_irq(irq); \ - } while (0) +#define IRQ_LEAVE(irq) current_regs = NULL /* The following macro is used to sample the interrupt state (as a opaque handle) */ -#define IRQ_STATE() \ - (g_z8irqstate.regs) +#define IRQ_STATE() (current_regs) /* Save the current IRQ context in the specified TCB */ -#define SAVE_IRQCONTEXT(tcb) \ - z8_saveirqcontext((tcb)->xcp.regs) +#define SAVE_IRQCONTEXT(tcb) ez80_copystate((tcb)->xcp.regs, current_regs) /* Set the current IRQ context to the state specified in the TCB */ -#define SET_IRQCONTEXT(tcb) \ - do { \ - g_z8irqstate.state = EZ80_IRQSTATE_SAVED; \ - g_z8irqstate.regs = (tcb)->xcp.regs; \ - } while (0) +#define SET_IRQCONTEXT(tcb) ez80_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) +#define SAVE_USERCONTEXT(tcb) ez80_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) +#define RESTORE_USERCONTEXT(tcb) ez80_restorecontext((tcb)->xcp.regs) /* Dump the current machine registers */ -#define _REGISTER_DUMP() \ - z8_registerdump() +#define _REGISTER_DUMP() ez80_registerdump() /************************************************************************************ * Public Types ************************************************************************************/ -/* In order to provide faster interrupt handling, the interrupt logic does "lazy" - * context saving as described below: - * - * (1) At the time of the interrupt, minimum information is saved and the register - * pointer is changed so that the interrupt logic does not alter the state of - * the interrupted task's registers. - * (2) If no context switch occurs during the interrupt processing, then the return - * from interrupt is also simple. - * (3) If a context switch occurs during interrupt processing, then - * (a) The full context of the interrupt task is saved, and - * (b) A full context switch is performed when the interrupt exits (see - * z8_vector.S). - * - * The following structure is used to manage this "lazy" context saving. - */ - -#ifndef __ASSEMBLY__ -struct z8_irqstate_s -{ - ubyte state; /* See EZ80_IRQSTATE_* definitions above */ - chipreg_t *regs; /* Saved register information */ -}; -#endif - /************************************************************************************ * Public Variables ************************************************************************************/ #ifndef __ASSEMBLY__ -/* This structure holds information about the current interrupt processing state */ +/* This holds a references to the current interrupt level register storage structure. + * If is non-NULL only during interrupt processing. + */ -extern struct z8_irqstate_s g_z8irqstate; +extern chipreg_t *current_regs; #endif /************************************************************************************ @@ -216,29 +132,25 @@ extern "C" { #define EXTERN extern #endif -/* Defined in z8_irq.c */ - -EXTERN void up_maskack_irq(int irq); - -/* Defined in z8_saveusercontext.asm */ +/* Defined in ez80_copystate.c */ -EXTERN int z8_saveusercontext(FAR chipreg_t *regs); +EXTERN void ez80_copystate(chipreg_t *dest, const chipreg_t *src); -/* Defined in z8_saveirqcontext.c */ +/* Defined in ez80_saveusercontext.asm */ -EXTERN void z8_saveirqcontext(FAR chipreg_t *regs); +EXTERN int ez80_saveusercontext(chipreg_t *regs); -/* Defined in z8_restorecontext.asm */ +/* Defined in ez80_restorecontext.asm */ -EXTERN void z8_restorecontext(FAR chipreg_t *regs); +EXTERN void ez80_restorecontext(chipreg_t *regs); -/* Defined in z8_sigsetup.c */ +/* Defined in ez80_sigsetup.c */ -EXTERN void z8_sigsetup(FAR _TCB *tcb, sig_deliver_t sigdeliver, FAR chipreg_t *regs); +EXTERN void ez80_sigsetup(_TCB *tcb, sig_deliver_t sigdeliver, chipreg_t *regs); -/* Defined in z8_registerdump.c */ +/* Defined in ez80_registerdump.c */ -EXTERN void z8_registerdump(void); +EXTERN void ez80_registerdump(void); #undef EXTERN #ifdef __cplusplus diff --git a/nuttx/arch/z80/src/z80/z80_irq.c b/nuttx/arch/z80/src/z80/z80_irq.c index 4873abbf7..5b4de5dc9 100644 --- a/nuttx/arch/z80/src/z80/z80_irq.c +++ b/nuttx/arch/z80/src/z80/z80_irq.c @@ -56,7 +56,7 @@ ****************************************************************************/ /* This holds a references to the current interrupt level register storage -* structure. If is non-NULL only during interrupt processing. + * structure. If is non-NULL only during interrupt processing. */ chipreg_t *current_regs; diff --git a/nuttx/arch/z80/src/z80/z80_registerdump.c b/nuttx/arch/z80/src/z80/z80_registerdump.c index 8646fcb84..e9c4e77db 100644 --- a/nuttx/arch/z80/src/z80/z80_registerdump.c +++ b/nuttx/arch/z80/src/z80/z80_registerdump.c @@ -85,7 +85,7 @@ static void z80_registerdump(void) 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" + lldbg("SP: %04x PC: %04x\n" current_regs[XCPT_SP], current_regs[XCPT_PC]); } } diff --git a/nuttx/configs/ez80f910200kitg/src/ez80_lowinit.c b/nuttx/configs/ez80f910200kitg/src/ez80_lowinit.c index 97dc6fc48..25cd78a3e 100644 --- a/nuttx/configs/ez80f910200kitg/src/ez80_lowinit.c +++ b/nuttx/configs/ez80f910200kitg/src/ez80_lowinit.c @@ -52,7 +52,7 @@ * Private Functions ***************************************************************************/ -static void z8_gpioinit(void) +static void ez80_gpioinit(void) { } @@ -60,8 +60,8 @@ static void z8_gpioinit(void) * Public Functions ***************************************************************************/ -void z8_lowinit(void) +void ez80_lowinit(void) { - z8_gpioinit(); + ez80_gpioinit(); } -- cgit v1.2.3