summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-03-16 00:06:05 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-03-16 00:06:05 +0000
commit586a725f04ff196e58e5eea642ffe1efad1c03da (patch)
tree9570d747aa8d750fc261abfb3e9e67155d38fcdc /nuttx/arch
parent66078ce7c851b1718be106e3c780db8d597689cf (diff)
downloadpx4-nuttx-586a725f04ff196e58e5eea642ffe1efad1c03da.tar.gz
px4-nuttx-586a725f04ff196e58e5eea642ffe1efad1c03da.tar.bz2
px4-nuttx-586a725f04ff196e58e5eea642ffe1efad1c03da.zip
First cut at ez80 boot logic
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@736 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/z80/include/ez80/irq.h10
-rw-r--r--nuttx/arch/z80/src/ez80/Make.defs10
-rw-r--r--nuttx/arch/z80/src/ez80/chip.h15
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_initialstate.c93
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_startup.asm155
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_vectors.asm314
-rw-r--r--nuttx/arch/z80/src/ez80/ez80f91_init.asm253
7 files changed, 836 insertions, 14 deletions
diff --git a/nuttx/arch/z80/include/ez80/irq.h b/nuttx/arch/z80/include/ez80/irq.h
index 96cb54f08..b63ac7aef 100644
--- a/nuttx/arch/z80/include/ez80/irq.h
+++ b/nuttx/arch/z80/include/ez80/irq.h
@@ -143,8 +143,9 @@
#ifdef CONFIG_EZ80_Z80MODE
/* Byte offsets */
-# define XCPT_I16_OFFSET (2*XCPT_I) /* Offset 0: 16-bit interrupt vector register */
-# define XCPT_I_OFFSET (2*XCPT_I+1) /* Offset 1: 8-bit interrupt vector register */
+# define XCPT_I_OFFSET (2*XCPT_I) /* Offset 0: 16-bit interrupt vector register */
+# define XCPT_IF_OFFSET (2*XCPT_I+0) /* Offset 1: Saved flags. P set if interrupts enabled */
+# define XCPT_IA_OFFSET (2*XCPT_I+1) /* Offset 2: Saved lower 8-bits of interrupt vector register */
# define XCPT_BC_OFFSET (2*XCPT_BC) /* Offset 2: Saved 16-bit BC register */
# define XCPT_C_OFFSET (2*XCPT_BC+0) /* Offset 2: Saved 8-bit C register */
# define XCPT_B_OFFSET (2*XCPT_BC+1) /* Offset 3: Saved 8-bit D register */
@@ -165,8 +166,9 @@
#else
/* Byte offsets */
-# define XCPT_I24_OFFSET (3*XCPT_I) /* Offset 0: Saved 24-bit interrupt vector register */
-# define XCPT_I_OFFSET (3*XCPT_I+2) /* Offset 2: Saved 8-bit interrupt vector register */
+# define XCPT_I_OFFSET (3*XCPT_I) /* Offset 0: Saved 24-bit interrupt vector register */
+# define XCPT_IF_OFFSET (2*XCPT_I+1) /* Offset 1: Saved flags. P set if interrupts enabled */
+# define XCPT_IA_OFFSET (2*XCPT_I+2) /* Offset 2: Saved lower 8-bits of interrupt vector register */
# define XCPT_BC_OFFSET (3*XCPT_BC) /* Offset 3: Saved 24-bit BC register */
# define XCPT_C_OFFSET (3*XCPT_BC+1) /* Offset 4: Saved 8-bit C register */
# define XCPT_B_OFFSET (3*XCPT_BC+2) /* Offset 5: Saved 8-bit D register */
diff --git a/nuttx/arch/z80/src/ez80/Make.defs b/nuttx/arch/z80/src/ez80/Make.defs
index 4c64bd84c..fc9e9e844 100644
--- a/nuttx/arch/z80/src/ez80/Make.defs
+++ b/nuttx/arch/z80/src/ez80/Make.defs
@@ -33,7 +33,8 @@
#
############################################################################
-HEAD_SSRC = ez80_head.S
+HEAD_ASRC = ez80_vectors.asm
+HEAD_SSRC =
CMN_SSRCS =
CMN_CSRCS = up_initialize.c up_allocateheap.c up_createstack.c \
@@ -42,8 +43,11 @@ CMN_CSRCS = up_initialize.c up_allocateheap.c up_createstack.c \
up_reprioritizertr.c up_idle.c up_assert.c up_doirq.c \
up_mdelay.c up_udelay.c up_usestack.c
-CHIP_SSRCS = ez80_vector.S ez80_saveusercontext.S ez80_restorecontext.S
+CHIP_ASRCS = ez80_startup.asm ez80_saveusercontext.asm ez80_restorecontext.asm
+ifeq ($(_EZ80F91),y)
+CHIP_ASRCS += ez80f91_init.asm
+endif
+CHIP_SSRCS =
CHIP_CSRCS = ez80_initialstate.c ez80_irq.c ez80_saveirqcontext.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/chip.h b/nuttx/arch/z80/src/ez80/chip.h
index 18a2c62cd..6e21295a8 100644
--- a/nuttx/arch/z80/src/ez80/chip.h
+++ b/nuttx/arch/z80/src/ez80/chip.h
@@ -45,13 +45,14 @@
* Definitions
************************************************************************************/
-/* Hexadecimal Representation *******************************************************/
-
-#ifdef __ASSEMBLY__
-# define _HX(h) %##h
-#else
-# define _HX(h) 0x##h
-#endif
+/* Bits in the Z80 FLAGS register ***************************************************/
+
+#define EZ80_C_FLAG 0x01 /* Bit 0: Carry flag */
+#define EZ80_N_FLAG 0x02 /* Bit 1: Add/Subtract flag */
+#define EZ80_PV_FLAG 0x04 /* Bit 2: Parity/Overflow flag */
+#define EZ80_H_FLAG 0x10 /* Bit 4: Half carry flag */
+#define EZ80_Z_FLAG 0x40 /* Bit 5: Zero flag */
+#define EZ80_S_FLAG 0x80 /* Bit 7: Sign flag */
/* Memory Map */
/* Special Function Registers *******************************************************
diff --git a/nuttx/arch/z80/src/ez80/ez80_initialstate.c b/nuttx/arch/z80/src/ez80/ez80_initialstate.c
new file mode 100644
index 000000000..997616bdf
--- /dev/null
+++ b/nuttx/arch/z80/src/ez80/ez80_initialstate.c
@@ -0,0 +1,93 @@
+/****************************************************************************
+ * arch/z80/src/ez80/ez80_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;
+ chireg_t *regs = xcp->regs;
+
+ /* Initialize the initial exception register context structure */
+
+ memset(xcp, 0, sizeof(struct xcptcontext));
+#ifndef CONFIG_SUPPRESS_INTERRUPTS
+ ((ubyte*)regs)[XCPT_IF_OFFSET] = EZ80_PV_FLAG; /* Parity/Overflow flag will enable interrupts */
+#endif
+ regs[XCPT_SP] = (chipreg_t)tcb->adj_stack_ptr;
+ regs[XCPT_PC] = (chipreg_t)tcb->start;
+}
diff --git a/nuttx/arch/z80/src/ez80/ez80_startup.asm b/nuttx/arch/z80/src/ez80/ez80_startup.asm
new file mode 100644
index 000000000..8ec95b0c2
--- /dev/null
+++ b/nuttx/arch/z80/src/ez80/ez80_startup.asm
@@ -0,0 +1,155 @@
+;**************************************************************************
+; arch/z80/src/ez80/ez80_startup.asm
+;
+; 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
+;**************************************************************************
+
+;**************************************************************************
+; Constants
+;**************************************************************************
+
+;**************************************************************************
+; Global symbols used
+;**************************************************************************
+
+ xref __stack
+ xref _ez80_init
+ xref _ez80_initvectors
+ xref _ez80_initsysclk
+ xref _up_lowinit
+ xref __low_bss ; Low address of bss segment
+ xref __len_bss ; Length of bss segment
+
+ xref __low_data ; Address of initialized data section
+ xref __low_romdata ; Addr of initialized data section in ROM
+ xref __len_data ; Length of initialized data section
+
+ xref __copy_code_to_ram
+ xref __len_code
+ xref __low_code
+ xref __low_romcode
+ xref __open_periphdevice
+ xref __close_periphdevice
+ xref _os_start
+ xdef _ez80_startup
+ xdef _ez80_halt
+
+;**************************************************************************
+; System reset start logic
+;**************************************************************************
+
+_ez80_startup:
+ ; Set up the stack pointer at the location determined the lincmd
+ ; file
+
+ ld sp, __stack
+
+ ; Peform chip-specific initialization
+
+ call _ez80_init
+
+ ; initialize the interrupt vector table
+
+ call _ez80_initvectors
+
+ ; Initialize the system clock
+
+ call _ez80_initsysclk
+
+ ; Perform C initializations
+ ; Clear the uninitialized data section
+
+ ld bc, __len_bss ; Check for non-zero length
+ ld a, __len_bss >> 16
+ or a, c
+ or a, b
+ jr z, _ez80_bssdone ; BSS is zero-length ...
+ xor a, a
+ ld (__low_bss), a
+ sbc hl, hl ; hl = 0
+ dec bc ; 1st byte's taken care of
+ sbc hl, bc
+ jr z, _ez80_bssdone ; Just 1 byte ...
+ ld hl, __low_bss ; reset hl
+ ld de, __low_bss + 1 ; [de] = bss + 1
+ ldir
+_ez80_bssdone:
+
+ ; Copy the initialized data section
+ ld bc, __len_data ; [bc] = data length
+ ld a, __len_data >> 16 ; Check for non-zero length
+ or a, c
+ or a, b
+ jr z, _ez80_datadone ; __len_data is zero-length ...
+ ld hl, __low_romdata ; [hl] = data_copy
+ ld de, __low_data ; [de] = data
+ ldir ; Copy the data section
+_ez80_datadone:
+
+ ; Copy CODE (which may be in FLASH) to RAM if the
+ ; copy_code_to_ram symbol is set in the link control file
+ ld a, __copy_code_to_ram
+ or a, a
+ jr z, _ez80_codedone
+ ld bc, __len_code ; [bc] = code length
+ ld a, __len_code >> 16 ; Check for non-zero length
+ or a, c
+ or a, b
+ jr z, _ez80_codedone ; __len_code is zero-length
+ ld hl, __low_romcode ; [hl] = code_copy
+ ld de, __low_code ; [de] = code
+ ldir ; Copy the code section
+_ez80_codedone:
+
+ ; Initialize the peripheral devices
+
+ call __open_periphdevice
+
+ ; Perform board-specific intialization
+
+ call _up_lowinit
+
+ ; Then start NuttX
+
+ call _os_start ; jump to the OS entry point
+
+ ; NuttX will never return, but just in case...
+
+ call __close_periphdevice
+_ez80_halt::
+ halt ; We should never get here
+ jp _ez80_halt
+
diff --git a/nuttx/arch/z80/src/ez80/ez80_vectors.asm b/nuttx/arch/z80/src/ez80/ez80_vectors.asm
new file mode 100644
index 000000000..b6140abb1
--- /dev/null
+++ b/nuttx/arch/z80/src/ez80/ez80_vectors.asm
@@ -0,0 +1,314 @@
+;**************************************************************************
+; arch/z80/src/ez80/ez80_vectors.asm
+;
+; 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.
+;
+;**************************************************************************
+
+;**************************************************************************
+; Constants
+;**************************************************************************
+
+NVECTORS EQU 64 ; max possible interrupt vectors
+
+;**************************************************************************
+; Global symbols used
+;**************************************************************************
+
+ xref _ez80_startup
+ xdef _ez80_reset
+ xdef _ez80_initvectors
+ xdef _ez80_handlers
+ xdef _ez80_rstcommon
+ xdef _ez80_initvectors
+ xdef _ez80_vectable
+
+;**************************************************************************
+; Macros
+;**************************************************************************
+
+; Define one reset handler
+; 1. Disable interrupts
+; 2. Dlear mixed memory mode (MADL) flag
+; 3. jump to initialization procedure with jp.lil to set ADL
+rstvector: macro
+ di
+ rsmix
+ jp.lil _ez80_startup
+ endmac rstvector
+
+; Define one interrupt handler
+irqhandler: macro vectno
+ ; Save AF on the stack, set the interrupt number and jump to the
+ ; common reset handling logic.
+ ; Offset 8: Return PC is already on the stack
+ push af ; Offset 7: AF (retaining flags)
+ ld a, #vectno ; A = vector number
+ jr _ez80_rstcommon ; Remaining RST handling is common
+ endmac irqhandler
+
+; Save Interrupt State
+irqsave: macro
+ ld a, i ; sets parity bit to value of IEF2
+ push af
+ di ; disable interrupts while loading table
+ endmac irqsave
+
+; Restore Interrupt State
+irqrestore: macro
+ pop af
+ jp po, $+5 ; parity bit is IEF2
+ ei
+ endmac irqrestore
+
+;**************************************************************************
+; Reset entry points
+;**************************************************************************
+
+ define .RESET, space = ROM
+ segment .RESET
+
+_ez80_reset:
+_rst0:
+ rstvector
+_rst8:
+ rstvector
+_rst10:
+ rstvector
+_rst18:
+ rstvector
+_rst20:
+ rstvector
+_rst28:
+ rstvector
+_rst30:
+ rstvector
+_rst38:
+ rstvector
+ ds %26
+_nmi:
+ retn
+
+;**************************************************************************
+; Startup logic
+;**************************************************************************
+
+ define .STARTUP, space = ROM
+ segment .STARTUP
+ .assume ADL=1
+
+;**************************************************************************
+; Interrupt Vector Handling
+;**************************************************************************
+
+_ez80_handlers:
+ irqhandler 0
+ handlersize equ . - _ez80handlers
+ irqhandler 1
+ irqhandler 2
+ irqhandler 3
+ irqhandler 4
+ irqhandler 5
+ irqhandler 6
+ irqhandler 7
+ irqhandler 8
+ irqhandler 9
+ irqhandler 10
+ irqhandler 11
+ irqhandler 12
+ irqhandler 13
+ irqhandler 14
+ irqhandler 15
+ irqhandler 16
+ irqhandler 17
+ irqhandler 18
+ irqhandler 19
+ irqhandler 20
+ irqhandler 21
+ irqhandler 22
+ irqhandler 23
+ irqhandler 24
+ irqhandler 25
+ irqhandler 26
+ irqhandler 27
+ irqhandler 28
+ irqhandler 29
+ irqhandler 30
+ irqhandler 31
+ irqhandler 32
+ irqhandler 33
+ irqhandler 34
+ irqhandler 35
+ irqhandler 36
+ irqhandler 37
+ irqhandler 38
+ irqhandler 39
+ irqhandler 40
+ irqhandler 41
+ irqhandler 42
+ irqhandler 43
+ irqhandler 44
+ irqhandler 45
+ irqhandler 46
+ irqhandler 47
+ irqhandler 48
+ irqhandler 49
+ irqhandler 50
+ irqhandler 51
+ irqhandler 52
+ irqhandler 53
+ irqhandler 54
+ irqhandler 55
+ irqhandler 56
+ irqhandler 57
+ irqhandler 58
+ irqhandler 59
+ irqhandler 60
+ irqhandler 61
+ irqhandler 62
+ irqhandler 63
+
+;**************************************************************************
+; Common Interrupt handler
+;**************************************************************************
+
+_ez80_rstcommon::
+ ; Create a register frame. SP points to top of frame + 4, pushes
+ ; decrement the stack pointer. Already have
+ ;
+ ; Offset 8: Return PC is already on the stack
+ ; Offset 7: AF (retaining flags)
+ ;
+ ; IRQ number is in A
+
+ 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 b, a ; Save the reset number in B
+ 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 #2 is the beginning of the reg structure
+ add hl, sp ;
+ push hl ; Place argument #2 at the top of stack
+ push bc ; Argument #1 is the Reset number
+ inc sp ; (make byte sized)
+ call _up_doirq ; Decode the IRQ
+
+ ; On return, HL points to the beginning of the reg structure to restore
+ ; Note that (1) the arguments pushed on the stack are not popped, and (2) the
+ ; original stack pointer is lost. In the normal case (no context switch),
+ ; HL will contain the value of the SP before the arguments wer pushed.
+
+ ld sp, hl ; Use the new stack pointer
+
+ ; 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
+ ex af, af' ; Restore original AF
+ 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
+ ld hl, #-2 ; Offset of SP to account for ret addr on stack
+ pop de ; Offset 5: HL' = Stack pointer after return
+ add hl, de ; HL = Stack pointer value before return
+ exx ; Restore original BC/DE/HL
+ pop hl ; Offset 6: HL
+ pop af ; Offset 7: AF
+
+ ; Restore the stack pointer
+
+ exx ; Use alternate BC/DE/HL
+ ld sp, hl ; Set SP = saved stack pointer value before return
+ exx ; Restore original BC/DE/HL
+
+ ; 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
+
+;**************************************************************************
+; Vector Setup Logic
+;**************************************************************************
+
+_ez80_initvectors:
+ ; Initialize the vector table
+
+ ld hl, _vector_table
+ ld b, NVECTORS
+ ld iy, _ez80_handlers
+ ld a, 0
+$1:
+ ld (iy), hl ; Store IRQ handler
+ ld (iy+3), a ; Pad to 4 bytes
+ add hl, handlersize ; Point to next handler
+ add iy, 4 ; Point to next entry in vector table
+ djnz $2 ; Loop until all vectors have been written
+
+ ; Select interrupt mode 2
+
+ im 2 ; Interrupt mode 2
+
+ ; Write the address of the vector table into the interrupt vector base
+
+ ld hl, _ez80_vectable >> 8
+ ld i, hl
+ ret
+
+;**************************************************************************
+; Vector Table
+;**************************************************************************
+; This segment must be aligned on a 512 byte boundary anywhere in RAM
+; Each entry will be a 3-byte address in a 4-byte space
+
+ define .IVECTS, space = RAM, align = 200h
+ segment .IVECTS
+
+_ez80_vectable:
+ ds NVECTORS * 4
diff --git a/nuttx/arch/z80/src/ez80/ez80f91_init.asm b/nuttx/arch/z80/src/ez80/ez80f91_init.asm
new file mode 100644
index 000000000..fa208882f
--- /dev/null
+++ b/nuttx/arch/z80/src/ez80/ez80f91_init.asm
@@ -0,0 +1,253 @@
+;**************************************************************************
+; arch/z80/src/ez80/ez80f91_init.asm
+;
+; 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 "ez80f91.inc"
+
+;**************************************************************************
+; Constants
+;**************************************************************************
+
+;PLL_DIV_L EQU %5C
+;PLL_DIV_H EQU %5D
+;PLL_CTL0 EQU %5E
+;PLL_CTL1 EQU %5F
+
+OSC EQU 0
+PLL EQU 1
+RTC EQU 2
+
+CLK_MUX_OSC EQU %00
+CLK_MUX_PLL EQU %01
+CLK_MUX_RTC EQU %02
+
+CHRP_CTL_0 EQU %00
+CHRP_CTL_1 EQU %40
+CHRP_CTL_2 EQU %80
+CHRP_CTL_3 EQU %C0
+
+LDS_CTL_0 EQU %00
+LDS_CTL_1 EQU %04
+LDS_CTL_2 EQU %08
+LDS_CTL_3 EQU %0C
+
+LCK_STATUS EQU %20
+INT_LOCK EQU %10
+INT_UNLOCK EQU %08
+INT_LOCK_EN EQU %04
+INT_UNLOCK_EN EQU %02
+PLL_ENABLE EQU %01
+
+;**************************************************************************
+; Global symbols used
+;**************************************************************************
+
+ xdef _ez80_init
+ xref __CS0_LBR_INIT_PARAM
+ xref __CS0_UBR_INIT_PARAM
+ xref __CS0_CTL_INIT_PARAM
+ xref __CS1_LBR_INIT_PARAM
+ xref __CS1_UBR_INIT_PARAM
+ xref __CS1_CTL_INIT_PARAM
+ xref __CS2_LBR_INIT_PARAM
+ xref __CS2_UBR_INIT_PARAM
+ xref __CS2_CTL_INIT_PARAM
+ xref __CS3_LBR_INIT_PARAM
+ xref __CS3_UBR_INIT_PARAM
+ xref __CS3_CTL_INIT_PARAM
+ xref __CS0_BMC_INIT_PARAM
+ xref __CS1_BMC_INIT_PARAM
+ xref __CS2_BMC_INIT_PARAM
+ xref __CS3_BMC_INIT_PARAM
+ xref __FLASH_CTL_INIT_PARAM
+ xref __FLASH_ADDR_U_INIT_PARAM
+ xref __RAM_CTL_INIT_PARAM
+ xref __RAM_ADDR_U_INIT_PARAM
+ xref _SYS_CLK_SRC
+ xref _SYS_CLK_FREQ
+ xref _OSC_FREQ
+ xref _OSC_FREQ_MULT
+ xref __PLL_CTL0_INIT_PARAM
+
+;**************************************************************************
+; Chip-specific initialization logic
+;**************************************************************************
+; Minimum default initialization for eZ80F91
+
+ define .STARTUP, space = ROM
+ segment .STARTUP
+ .assume ADL = 1
+
+_ez80_init:
+ ; Disable internal peripheral interrupt sources
+
+ ld a, %ff
+ out0 (PA_DDR), a ; GPIO
+ out0 (PB_DDR), a
+ out0 (PC_DDR), a
+ out0 (PD_DDR), a
+ ld a, %00
+ out0 (PA_ALT1), a
+ out0 (PB_ALT1), a
+ out0 (PC_ALT1), a
+ out0 (PD_ALT1), a
+ out0 (PA_ALT2), a
+ out0 (PB_ALT2), a
+ out0 (PC_ALT2), a
+ out0 (PD_ALT2), a
+ out0 (PLL_CTL1), a ; PLL
+ out0 (TMR0_IER), a ; timers
+ out0 (TMR1_IER), a
+ out0 (TMR2_IER), a
+ out0 (TMR3_IER), a
+ out0 (UART0_IER), a ; UARTs
+ out0 (UART1_IER), a
+ out0 (I2C_CTL), a ; I2C
+ out0 (EMAC_IEN), a ; EMAC
+ out0 (FLASH_IRQ), a ; Flash
+ ld a, %04
+ out0 (SPI_CTL), a ; SPI
+ in0 a, (RTC_CTRL) ; RTC,
+ and a, %be
+ out0 (RTC_CTRL), a
+
+ ; Configure external memory/io
+
+ ld a, __CS0_LBR_INIT_PARAM
+ out0 (CS0_LBR), a
+ ld a, __CS0_UBR_INIT_PARAM
+ out0 (CS0_UBR), a
+ ld a, __CS0_BMC_INIT_PARAM
+ out0 (CS0_BMC), a
+ ld a, __CS0_CTL_INIT_PARAM
+ out0 (CS0_CTL), a
+
+ ld a, __CS1_LBR_INIT_PARAM
+ out0 (CS1_LBR), a
+ ld a, __CS1_UBR_INIT_PARAM
+ out0 (CS1_UBR), a
+ ld a, __CS1_BMC_INIT_PARAM
+ out0 (CS1_BMC), a
+ ld a, __CS1_CTL_INIT_PARAM
+ out0 (CS1_CTL), a
+
+ ld a, __CS2_LBR_INIT_PARAM
+ out0 (CS2_LBR), a
+ ld a, __CS2_UBR_INIT_PARAM
+ out0 (CS2_UBR), a
+ ld a, __CS2_BMC_INIT_PARAM
+ out0 (CS2_BMC), a
+ ld a, __CS2_CTL_INIT_PARAM
+ out0 (CS2_CTL), a
+
+ ld a, __CS3_LBR_INIT_PARAM
+ out0 (CS3_LBR), a
+ ld a, __CS3_UBR_INIT_PARAM
+ out0 (CS3_UBR), a
+ ld a, __CS3_BMC_INIT_PARAM
+ out0 (CS3_BMC), a
+ ld a, __CS3_CTL_INIT_PARAM
+ out0 (CS3_CTL), a
+
+ ; Enable internal memory
+
+ ld a, __FLASH_ADDR_U_INIT_PARAM
+ out0 (FLASH_ADDR_U), a
+ ld a, __FLASH_CTL_INIT_PARAM
+ out0 (FLASH_CTRL), a
+
+ ld a, __RAM_ADDR_U_INIT_PARAM
+ out0 (RAM_ADDR_U), a
+ ld a, __RAM_CTL_INIT_PARAM
+ out0 (RAM_CTL), a
+ ret
+
+;*****************************************************************************
+; eZ80F91 System Clock Initialization
+;*****************************************************************************
+
+_ez80_initsysclk:
+ ; check if the PLL should be used
+ ld a, (_ez80_sysclksrc)
+ cp a, PLL
+ jr nz, _ez80_initsysclkdone
+
+ ; Load PLL divider
+
+ ld a, (_ez80_oscfreqmult) ;CR 6202
+ out0 (PLL_DIV_L), a
+ ld a, (_ez80_oscfreqmult+1)
+ out0 (PLL_DIV_H), a
+
+ ; Set charge pump and lock criteria
+
+ ld a, __PLL_CTL0_INIT_PARAM
+ and a, %CC ; mask off reserved and clock source bits
+ out0 (PLL_CTL0), a
+
+ ; Enable PLL
+
+ in0 a, (PLL_CTL1)
+ set 0, a
+ out0 (PLL_CTL1), a
+
+ ; Wait for PLL to lock
+_ez80_initsysclkwait:
+ in0 a, (PLL_CTL1)
+ and a, LCK_STATUS
+ cp a, LCK_STATUS
+ jr nz, _ez80_initsysclkwait
+
+ ; Select PLL as system clock source
+
+ ld a, __PLL_CTL0_INIT_PARAM
+ set 0, a
+ out0 (PLL_CTL0), a
+
+_ez80_initsysclkdone:
+ ret
+
+;_ez80_oscfreq:
+; dl _OSC_FREQ
+_ez80_oscfreqmult:
+ dw _OSC_FREQ_MULT
+;_ez80_sysclkfreq:
+; dl _SYS_CLK_FREQ
+_ez80_sysclksrc:
+ db _SYS_CLK_SRC
+ end \ No newline at end of file