From 0cfc4cf403f5aa72624359c7db7f3a6c88346ad3 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 12 Dec 2012 16:38:50 +0000 Subject: Add z180 interrupt vectors git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5432 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/z80/include/z180/irq.h | 100 ++++++++++--- nuttx/arch/z80/src/z180/Make.defs | 8 + nuttx/arch/z80/src/z180/z180_head.asm | 130 ++-------------- nuttx/arch/z80/src/z180/z180_rom.asm | 133 +++-------------- nuttx/arch/z80/src/z180/z180_romvectors.asm | 89 +++++++++++ nuttx/arch/z80/src/z180/z180_vectcommon.asm | 223 ++++++++++++++++++++++++++++ nuttx/arch/z80/src/z180/z180_vectors.asm | 90 +++++++++++ 7 files changed, 520 insertions(+), 253 deletions(-) create mode 100644 nuttx/arch/z80/src/z180/z180_romvectors.asm create mode 100644 nuttx/arch/z80/src/z180/z180_vectcommon.asm create mode 100644 nuttx/arch/z80/src/z180/z180_vectors.asm (limited to 'nuttx') diff --git a/nuttx/arch/z80/include/z180/irq.h b/nuttx/arch/z80/include/z180/irq.h index a72cf4708..6fbeaf5b5 100644 --- a/nuttx/arch/z80/include/z180/irq.h +++ b/nuttx/arch/z80/include/z180/irq.h @@ -54,18 +54,85 @@ ****************************************************************************/ /* Z180 Interrupts */ +/* Resets */ + /* RST 0 is the power-up interrupt vector */ +#define Z180_RST1 (0) /* RST 1 */ +#define Z180_RST2 (1) /* RST 2 */ +#define Z180_RST3 (2) /* RST 3 */ +#define Z180_RST4 (3) /* RST 4 */ +#define Z180_RST5 (4) /* RST 5 */ +#define Z180_RST6 (5) /* RST 6 */ +#define Z180_RST7 (6) /* RST 7 */ + +/* TRAP Interrupt + * + * The Z8X180 generates a non-maskable TRAP interrupt when an undefined Op + * Code fetch occurs. When a TRAP interrupt occurs the Z8X180 operates as + * follows: + * + * 1. The TRAP bit in the Interrupt TRAP/Control (ITC) register is set to 1. + * 2. The current PC (Program Counter) is saved on the stack. + * 3. The Z8X180 vectors to logical address 0 (which may or may not be the + * same as reset which vectors to physical address 0x00000). + * + * The state of the UFO (Undefined Fetch Object) bit in ITC allows TRAP + * manipulation software to correctly adjust the stacked PC, depending on + * whether the second or third byte of the Op Code generated the TRAP. If + * UFO is 0, the starting address of the invalid instruction is equal to + * the stacked PC-1. If UFO is 1, the starting address of the invalid + * instruction is equal to the stacked PC-2. + */ + +#define Z180_TRAP (7) + +/* INT0 + * + * INT0 (only) has 3 different software programmable interrupt response + * modes—Mode 0, Mode 1 and Mode 2. + * + * - INT0 Mode 0. During the interrupt acknowledge cycle, an instruction + * is fetched from the data bus (DO–D7) at the rising edge of T3. + * + * - INT0 Mode 1. The PC is stacked and instruction execution restarts at + * logical address 0x0038. + * + * - INT0 Mode 2. The restart address is obtained by reading the contents + * of a table residing in memory. The vector table consists of up to + * 128 two-byte restart addresses stored in low byte, high byte order. + * + * This is similar to normal vector mode interrupts (like INT1 and 2): + * The 256-bit table address comes from I, however the lower-order 8 + * bits of the vector is fetched from the data bus. + */ + +#define Z180_INT0 (8) + +/* Vector Interrupts + * + * Normal vector interrupts use a vector table with 16 entries (2 bytes + * per entry). Each entry holds the address of the interrupt handler. + * + * The vector table address is determined by 11-bits from the I and IL + * registers. The vector table must be aligned on 32-byte address + * boundaries. + * - Traps vector to logic address 0x0000 which may or may not be the same + * as the RST 0. + * - INT0 +/* Interrupt vectors (offsets) for Z180 internal interrupts */ -#define Z180_RST0 (0) -#define Z180_RST1 (1) -#define Z180_RST2 (2) -#define Z180_RST3 (3) -#define Z180_RST4 (4) -#define Z180_RST5 (5) -#define Z180_RST6 (6) -#define Z180_RST7 (7) +#define Z180_INT1 (9) /* Vector offset 0: External /INT1 */ +#define Z180_INT2 (10) /* Vector offset 2: External /INT2 */ +#define Z180_PRT0 (11) /* Vector offset 4: PRT channel 0 */ +#define Z180_PRT1 (12) /* Vector offset 6: PRT channel 1 */ +#define Z180_DMA0 (13) /* Vector offset 8: DMA channel 0 */ +#define Z180_DMA1 (14) /* Vector offset 10: DMA Channel 1 */ +#define Z180_CSIO (15) /* Vector offset 12: Clocked serial I/O */ +#define Z180_ASCI0 (16) /* Vector offset 14: Async channel 0 */ +#define Z180_ASCI1 (18) /* Vector offset 16: Async channel 1 */ +#define Z180_UNUSED (19) /* Vector offset 18-20: unused */ #define Z180_IRQ_SYSTIMER Z180_RST7 -#define NR_IRQS (8) +#define NR_IRQS (20) /* IRQ Stack Frame Format * @@ -86,21 +153,6 @@ #define XCPTCONTEXT_REGS (9) #define XCPTCONTEXT_SIZE (2 * XCPTCONTEXT_REGS) -/* Interrupt vectors (offsets) for Z180 internal interrupts */ - -#define Z180_INT1_VECTOR 0x00 /* External /INT1 */ -#define Z180_INT2_VECTOR 0x02 /* External /INT2 */ -#define Z180_PRT0_VECTOR 0x04 /* PRT channel 0 */ -#define Z180_PRT1_VECTOR 0x06 /* PRT channel 1 */ -#define Z180_DMA0_VECTOR 0x08 /* DMA channel 0 */ -#define Z180_DMA1_VECTOR 0x0a /* DMA Channel 1 */ -#define Z180_CSIO_VECTOR 0x0c /* Clocked serial I/O */ -#define Z180_ASCI0_VECTOR 0x0e /* Async channel 0 */ -#define Z180_ASCI1_VECTOR 0x10 /* Async channel 1 */ -#define Z180_INCAP_VECTOR 0x12 /* Input capture */ -#define Z180_OUTCMP_VECTOR 0x14 /* Output compare */ -#define Z180_TIMOV_VECTOR 0x16 /* Timer overflow */ - /**************************************************************************** * Public Types ****************************************************************************/ diff --git a/nuttx/arch/z80/src/z180/Make.defs b/nuttx/arch/z80/src/z180/Make.defs index 069f36204..f196c45d7 100644 --- a/nuttx/arch/z80/src/z180/Make.defs +++ b/nuttx/arch/z80/src/z180/Make.defs @@ -49,6 +49,14 @@ CMN_CSRCS += up_releasestack.c up_reprioritizertr.c up_unblocktask.c CMN_CSRCS += up_udelay.c up_usestack.c CHIP_ASRCS = z180_restoreusercontext.asm z180_saveusercontext.asm +CHIP_ASRCS += z180_vectcommon.asm + +ifeq ($(CONFIG_LINKER_ROM_AT_0000),y) +CHIP_ASRCS += z180_romvectors.asm +else +CHIP_ASRCS += z180_vectors.asm +endif + CHIP_CSRCS = z180_copystate.c z180_initialstate.c z180_io.c z180_irq.c CHIP_CSRCS += z180_mmu.c z180_registerdump.c z180_schedulesigaction.c CHIP_CSRCS += z180_sigdeliver.c diff --git a/nuttx/arch/z80/src/z180/z180_head.asm b/nuttx/arch/z80/src/z180/z180_head.asm index cb370ffda..2ecbefe24 100644 --- a/nuttx/arch/z80/src/z180/z180_head.asm +++ b/nuttx/arch/z80/src/z180/z180_head.asm @@ -40,18 +40,6 @@ ; Constants ;************************************************************************** - ; Register save area layout - - XCPT_I == 0 ; Offset 0: Saved I w/interrupt state in carry - XCPT_BC == 2 ; Offset 1: Saved BC register - XCPT_DE == 4 ; Offset 2: Saved DE register - XCPT_IX == 6 ; Offset 3: Saved IX register - XCPT_IY == 8 ; Offset 4: Saved IY register - XCPT_SP == 10 ; Offset 5: Offset to SP at time of interrupt - XCPT_HL == 12 ; Offset 6: Saved HL register - XCPT_AF == 14 ; Offset 7: Saved AF register - XCPT_PC == 16 ; Offset 8: Offset to PC at time of interrupt - ; Default stack base (needs to be fixed) .include "asm_mem.h" @@ -61,8 +49,9 @@ ;************************************************************************** .globl _os_start ; OS entry point - .globl _up_doirq ; Interrupt decoding logic + .globl _up_vectcommon ; Common interrupt handling logic .globl _z180_mmu_lowinit ; MMU initialization logic + .globl s__HEAP ; Start of the heap ;************************************************************************** ; Reset entry point @@ -77,16 +66,6 @@ ;************************************************************************** ; Other reset handlers -; -; 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 0x0008 ; RST 1 @@ -95,8 +74,8 @@ ; common reset handling logic. ; Offset 8: Return PC is already on the stack push af ; Offset 7: AF (retaining flags) - ld a, #1 ; 1 = Z180_RST1 - jr _up_rstcommon ; Remaining RST handling is common + ld a, #0 ; 0 = Z180_RST1 + jp _up_vectcommon ; Remaining RST handling is common .org 0x0010 ; RST 2 @@ -104,8 +83,8 @@ ; common reset handling logic. ; Offset 8: Return PC is already on the stack push af ; Offset 7: AF (retaining flags) - ld a, #2 ; 2 = Z180_RST2 - jr _up_rstcommon ; Remaining RST handling is common + ld a, #1 ; 1 = Z180_RST2 + jp _up_vectcommon ; Remaining RST handling is common .org 0x0018 ; RST 3 @@ -113,8 +92,8 @@ ; common reset handling logic. ; Offset 8: Return PC is already on the stack push af ; Offset 7: AF (retaining flags) - ld a, #3 ; 1 = Z180_RST3 - jr _up_rstcommon ; Remaining RST handling is common + ld a, #2 ; 2 = Z180_RST3 + jp _up_vectcommon ; Remaining RST handling is common .org 0x0020 ; RST 4 @@ -122,8 +101,8 @@ ; common reset handling logic. ; Offset 8: Return PC is already on the stack push af ; Offset 7: AF (retaining flags) - ld a, #4 ; 1 = Z180_RST4 - jr _up_rstcommon ; Remaining RST handling is common + ld a, #3 ; 3 = Z180_RST4 + jp _up_vectcommon ; Remaining RST handling is common .org 0x0028 ; RST 5 @@ -131,8 +110,8 @@ ; common reset handling logic. ; Offset 8: Return PC is already on the stack push af ; Offset 7: AF (retaining flags) - ld a, #5 ; 1 = Z180_RST5 - jr _up_rstcommon ; Remaining RST handling is common + ld a, #4 ; 4 = Z180_RST5 + jp _up_vectcommon ; Remaining RST handling is common .org 0x0030 ; RST 6 @@ -140,8 +119,8 @@ ; common reset handling logic. ; Offset 8: Return PC is already on the stack push af ; Offset 7: AF (retaining flags) - ld a, #6 ; 1 = Z180_RST6 - jr _up_rstcommon ; Remaining RST handling is common + ld a, #5 ; 5 = Z180_RST6 + jp _up_vectcommon ; Remaining RST handling is common .org 0x0038 ; Int mode 1 / RST 7 @@ -149,8 +128,8 @@ ; common reset handling logic. ; Offset 8: Return PC is already on the stack push af ; Offset 7: AF (retaining flags) - ld a, #7 ; 7 = Z180_RST7 - jr _up_rstcommon ; Remaining RST handling is common + ld a, #6 ; 6 = Z180_RST7 + jp _up_vectcommon ; Remaining RST handling is common ;************************************************************************** ; NMI interrupt handler @@ -188,83 +167,6 @@ _up_halt:: halt ; We should never get here jp _up_halt -;************************************************************************** -; Common Interrupt handler -;************************************************************************** - -_up_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 ; Parity bit holds interrupt state - push af ; Offset 0: I with interrupt state in parity - di - - ; Call the interrupt decode logic. SP points to the beginning 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 were 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 - jp po, nointenable ; Odd parity, IFF2=0, means disabled - ex af, af' ; Restore AF (before enabling interrupts) - ei ; yes - reti -nointenable:: - ex af, af' ; Restore AF - reti - ;************************************************************************** ; Ordering of segments for the linker (SDCC only) ;************************************************************************** diff --git a/nuttx/arch/z80/src/z180/z180_rom.asm b/nuttx/arch/z80/src/z180/z180_rom.asm index c27574f4e..8a7a62a54 100644 --- a/nuttx/arch/z80/src/z180/z180_rom.asm +++ b/nuttx/arch/z80/src/z180/z180_rom.asm @@ -40,18 +40,6 @@ ; Constants ;************************************************************************** - ; Register save area layout - - XCPT_I == 0 ; Offset 0: Saved I w/interrupt state in carry - XCPT_BC == 2 ; Offset 1: Saved BC register - XCPT_DE == 4 ; Offset 2: Saved DE register - XCPT_IX == 6 ; Offset 3: Saved IX register - XCPT_IY == 8 ; Offset 4: Saved IY register - XCPT_SP == 10 ; Offset 5: Offset to SP at time of interrupt - XCPT_HL == 12 ; Offset 6: Saved HL register - XCPT_AF == 14 ; Offset 7: Saved AF register - XCPT_PC == 16 ; Offset 8: Offset to PC at time of interrupt - ; Default stack base (needs to be fixed) .include "asm_mem.h" @@ -60,8 +48,10 @@ ; Global symbols used ;************************************************************************** - .globl _os_start ; OS entry point - .globl _up_doirq ; Interrupt decoding logic + .globl _os_start ; OS entry point + .globl _up_vectcommon ; Common interrupt handling logic + .globl _z180_mmu_lowinit ; MMU initialization logic + .globl s__HEAP ; Start of the heap ;************************************************************************** ; System start logic @@ -107,16 +97,6 @@ _up_rstvectors: ;************************************************************************** ; Other reset handlers -; -; 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. -; ;************************************************************************** _up_rst1: ; RST 1 @@ -124,133 +104,56 @@ _up_rst1: ; RST 1 ; common reset handling logic. ; Offset 8: Return PC is already on the stack push af ; Offset 7: AF (retaining flags) - ld a, #1 ; 1 = Z180_RST1 - jr _up_rstcommon ; Remaining RST handling is common + ld a, #0 ; 0 = Z180_RST1 + jp _up_vectcommon ; Remaining RST handling is common _up_rst2: ; RST 2 ; 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, #2 ; 2 = Z180_RST2 - jr _up_rstcommon ; Remaining RST handling is common + ld a, #1 ; 1 = Z180_RST2 + jp _up_vectcommon ; Remaining RST handling is common _up_rst3: ; RST 3 ; 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, #3 ; 1 = Z180_RST3 - jr _up_rstcommon ; Remaining RST handling is common + ld a, #2 ; 2 = Z180_RST3 + jp _up_vectcommon ; Remaining RST handling is common _up_rst4: ; RST 4 ; 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, #4 ; 1 = Z180_RST4 - jr _up_rstcommon ; Remaining RST handling is common + ld a, #3 ; 3 = Z180_RST4 + jp _up_vectcommon ; Remaining RST handling is common _up_rst5: ; RST 5 ; 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, #5 ; 1 = Z180_RST5 - jr _up_rstcommon ; Remaining RST handling is common + ld a, #4 ; 4 = Z180_RST5 + jp _up_vectcommon ; Remaining RST handling is common _up_rst6: ; RST 6 ; 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, #6 ; 1 = Z180_RST6 - jr _up_rstcommon ; Remaining RST handling is common + ld a, #5 ; 5 = Z180_RST6 + jp _up_vectcommon ; Remaining RST handling is common _up_rst7: ; RST 7 ; 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, #7 ; 7 = Z180_RST7 - jr _up_rstcommon ; Remaining RST handling is common - -;************************************************************************** -; Common Interrupt handler -;************************************************************************** - -_up_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 ; Parity bit holds interrupt state - push af ; Offset 0: I with interrupt state in parity - di - - ; Call the interrupt decode logic. SP points to the beginning 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 were 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 - jp po, nointenable ; Odd parity, IFF2=0, means disabled - ex af, af' ; Restore AF (before enabling interrupts) - ei ; yes - reti -nointenable:: - ex af, af' ; Restore AF - reti + ld a, #6 ; 6 = Z180_RST7 + jp _up_vectcommon ; Remaining RST handling is common ;************************************************************************** ; Ordering of segments for the linker (SDCC only) diff --git a/nuttx/arch/z80/src/z180/z180_romvectors.asm b/nuttx/arch/z80/src/z180/z180_romvectors.asm new file mode 100644 index 000000000..2871be2bb --- /dev/null +++ b/nuttx/arch/z80/src/z180/z180_romvectors.asm @@ -0,0 +1,89 @@ +;************************************************************************** +; arch/z80/src/z180/z180_romvectors.asm +; +; Copyright (C) 2012 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. +; +;************************************************************************** + + .title NuttX for the Z180 + .module z180_romvectors + +;************************************************************************** +; Constants +;************************************************************************** + +;************************************************************************** +; Global symbols used +;************************************************************************** + + .globl _up_int1 ; Vector offset 0: External /INT1 + .globl _up_int2 ; Vector offset 2: External /INT2 + .globl _up_prt0 ; Vector offset 4: PRT channel 0 + .globl _up_prt1 ; Vector offset 6: PRT channel 1 + .globl _up_dma0 ; Vector offset 8: DMA channel 0 + .globl _up_dma1 ; Vector offset 8: DMA channel 1 + .globl _up_csio ; Vector offset 12: Clocked serial I/O + .globl _up_asci0 ; Vector offset 14: Async channel 0 + .globl _up_asci1 ; Vector offset 16: Async channel 1 + .globl _up_unused ; Vector offset 18: Unused + .globl _up_unused ; Vector offset 20: Unused + .globl _up_unused ; Vector offset 22: Unused + .globl _up_unused ; Vector offset 24: Unused + .globl _up_unused ; Vector offset 26: Unused + .globl _up_unused ; Vector offset 28: Unused + .globl _up_unused ; Vector offset 30: Unused + +;************************************************************************** +; Interrupt Vector Table +;************************************************************************** + +; The start of the _VECTORS area must be set by the linker to lie at some +; 32-byte-aligned address + + .area _VECTORS + +_up_vectors:: + .dw up_int1 ; Vector offset 0: External /INT1 + .dw up_int2 ; Vector offset 2: External /INT2 + .dw up_prt0 ; Vector offset 4: PRT channel 0 + .dw up_prt1 ; Vector offset 6: PRT channel 1 + .dw up_dma0 ; Vector offset 8: DMA channel 0 + .dw up_dma1 ; Vector offset 8: DMA channel 1 + .dw up_csio ; Vector offset 12: Clocked serial I/O + .dw up_asci0 ; Vector offset 14: Async channel 0 + .dw up_asci1 ; Vector offset 16: Async channel 1 + .dw up_unused ; Vector offset 18: Unused + .dw up_unused ; Vector offset 20: Unused + .dw up_unused ; Vector offset 22: Unused + .dw up_unused ; Vector offset 24: Unused + .dw up_unused ; Vector offset 26: Unused + .dw up_unused ; Vector offset 28: Unused + .dw up_unused ; Vector offset 30: Unused \ No newline at end of file diff --git a/nuttx/arch/z80/src/z180/z180_vectcommon.asm b/nuttx/arch/z80/src/z180/z180_vectcommon.asm new file mode 100644 index 000000000..300ad2f31 --- /dev/null +++ b/nuttx/arch/z80/src/z180/z180_vectcommon.asm @@ -0,0 +1,223 @@ +;************************************************************************** +; arch/z80/src/z180/z180_vectcommon.asm +; +; Copyright (C) 2012 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. +; +;************************************************************************** + + .title NuttX for the Z180 + .module z180_vectcommon + +;************************************************************************** +; Constants +;************************************************************************** + + ; Register save area layout + + XCPT_I == 0 ; Offset 0: Saved I w/interrupt state in carry + XCPT_BC == 2 ; Offset 1: Saved BC register + XCPT_DE == 4 ; Offset 2: Saved DE register + XCPT_IX == 6 ; Offset 3: Saved IX register + XCPT_IY == 8 ; Offset 4: Saved IY register + XCPT_SP == 10 ; Offset 5: Offset to SP at time of interrupt + XCPT_HL == 12 ; Offset 6: Saved HL register + XCPT_AF == 14 ; Offset 7: Saved AF register + XCPT_PC == 16 ; Offset 8: Offset to PC at time of interrupt + +;************************************************************************** +; Global symbols used +;************************************************************************** + + .globl _up_doirq ; Interrupt decoding logic + + +;************************************************************************** +; Vector Handlers +;************************************************************************** + + .area _CODE + +up_int1:: ; Vector offset 0: External /INT1 + ; 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, #9 ; 9 = Z180_INT1 + jr _up_vectcommon ; Remaining RST handling is common + +up_int2:: ; Vector offset 2: External /INT2 + ; 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, #10 ; 10 = Z180_INT2 + jr _up_vectcommon ; Remaining RST handling is common + +up_prt0:: ; Vector offset 4: PRT channel 0 + ; 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, #11 ; 11 = Z180_PRT0 + jr _up_vectcommon ; Remaining RST handling is common + +up_prt1:: ; Vector offset 6: PRT channel 1 + ; 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, #12 ; 12 = Z180_PRT1 + jr _up_vectcommon ; Remaining RST handling is common + +up_dma0:: ; Vector offset 8: DMA channel 0 + ; 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, #13 ; 13 = Z180_DMA0 + jr _up_vectcommon ; Remaining RST handling is common + +up_dma1:: ; Vector offset 8: DMA channel 1 + ; 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, #14 ; 14 = Z180_DMA1 + jr _up_vectcommon ; Remaining RST handling is common + +up_csio:: ; Vector offset 12: Clocked serial I/O + ; 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, #15 ; 15 = Z180_CSIO + jr _up_vectcommon ; Remaining RST handling is common + +up_asci0:: ; Vector offset 14: Async channel 0 + ; 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, #16 ; 16 = Z180_ASCI0 + jr _up_vectcommon ; Remaining RST handling is common + +up_asci1:: ; Vector offset 16: Async channel 1 + ; 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, #17 ; 17 = Z180_ASCI1 + jr _up_vectcommon ; Remaining RST handling is common + +up_unused:: ; Vector offset 18: Unused + ; 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, #18 ; 18 = Z180_UNUSED + jr _up_vectcommon ; Remaining RST handling is common + +;************************************************************************** +; Common Interrupt handler +;************************************************************************** + +_up_vectcommon:: + ; 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 ; Parity bit holds interrupt state + push af ; Offset 0: I with interrupt state in parity + di + + ; Call the interrupt decode logic. SP points to the beginning 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 were 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 + jp po, nointenable ; Odd parity, IFF2=0, means disabled + ex af, af' ; Restore AF (before enabling interrupts) + ei ; yes + reti +nointenable:: + ex af, af' ; Restore AF + reti diff --git a/nuttx/arch/z80/src/z180/z180_vectors.asm b/nuttx/arch/z80/src/z180/z180_vectors.asm new file mode 100644 index 000000000..cd544b926 --- /dev/null +++ b/nuttx/arch/z80/src/z180/z180_vectors.asm @@ -0,0 +1,90 @@ +;************************************************************************** +; arch/z80/src/z180/z180_vectors.asm +; +; Copyright (C) 2012 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. +; +;************************************************************************** + + .title NuttX for the Z180 + .module z180_vectors + +;************************************************************************** +; Constants +;************************************************************************** + +;************************************************************************** +; Global symbols used +;************************************************************************** + + .globl _up_int1 ; Vector offset 0: External /INT1 + .globl _up_int2 ; Vector offset 2: External /INT2 + .globl _up_prt0 ; Vector offset 4: PRT channel 0 + .globl _up_prt1 ; Vector offset 6: PRT channel 1 + .globl _up_dma0 ; Vector offset 8: DMA channel 0 + .globl _up_dma1 ; Vector offset 8: DMA channel 1 + .globl _up_csio ; Vector offset 12: Clocked serial I/O + .globl _up_asci0 ; Vector offset 14: Async channel 0 + .globl _up_asci1 ; Vector offset 16: Async channel 1 + .globl _up_unused ; Vector offset 18: Unused + .globl _up_unused ; Vector offset 20: Unused + .globl _up_unused ; Vector offset 22: Unused + .globl _up_unused ; Vector offset 24: Unused + .globl _up_unused ; Vector offset 26: Unused + .globl _up_unused ; Vector offset 28: Unused + .globl _up_unused ; Vector offset 30: Unused + +;************************************************************************** +; Interrupt Vector Table +;************************************************************************** + +; The Vector Table is located at address 0x0040, between the RST vectors +; and the NMI vector + + .area _VECTORS (ABS) + .org 0x0040 + +_up_vectors:: + .dw up_int1 ; Vector offset 0: External /INT1 + .dw up_int2 ; Vector offset 2: External /INT2 + .dw up_prt0 ; Vector offset 4: PRT channel 0 + .dw up_prt1 ; Vector offset 6: PRT channel 1 + .dw up_dma0 ; Vector offset 8: DMA channel 0 + .dw up_dma1 ; Vector offset 8: DMA channel 1 + .dw up_csio ; Vector offset 12: Clocked serial I/O + .dw up_asci0 ; Vector offset 14: Async channel 0 + .dw up_asci1 ; Vector offset 16: Async channel 1 + .dw up_unused ; Vector offset 18: Unused + .dw up_unused ; Vector offset 20: Unused + .dw up_unused ; Vector offset 22: Unused + .dw up_unused ; Vector offset 24: Unused + .dw up_unused ; Vector offset 26: Unused + .dw up_unused ; Vector offset 28: Unused + .dw up_unused ; Vector offset 30: Unused \ No newline at end of file -- cgit v1.2.3