From 94432d7c9193cb123c7121d07957681493852760 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 22 Mar 2009 19:52:48 +0000 Subject: Patch [2696648] Z80: interrupt flag stored in parity bit git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1640 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/z80/src/ez80/ez80_restorecontext.asm | 4 ++-- nuttx/arch/z80/src/ez80/ez80_saveusercontext.asm | 6 +++--- nuttx/arch/z80/src/ez80/ez80_vectors.asm | 6 +++--- nuttx/arch/z80/src/z80/switch.h | 6 +++--- nuttx/arch/z80/src/z80/z80_head.asm | 8 ++++---- nuttx/arch/z80/src/z80/z80_initialstate.c | 6 +++--- nuttx/arch/z80/src/z80/z80_irq.c | 8 ++++---- nuttx/arch/z80/src/z80/z80_restoreusercontext.asm | 6 +++--- nuttx/arch/z80/src/z80/z80_rom.asm | 16 ++++++++-------- nuttx/arch/z80/src/z80/z80_saveusercontext.asm | 6 +++--- nuttx/configs/xtrs/src/xtrs_head.asm | 12 ++++++------ 11 files changed, 42 insertions(+), 42 deletions(-) (limited to 'nuttx') diff --git a/nuttx/arch/z80/src/ez80/ez80_restorecontext.asm b/nuttx/arch/z80/src/ez80/ez80_restorecontext.asm index 1785ddb17..da1d050f0 100644 --- a/nuttx/arch/z80/src/ez80/ez80_restorecontext.asm +++ b/nuttx/arch/z80/src/ez80/ez80_restorecontext.asm @@ -1,7 +1,7 @@ ;************************************************************************** ; arch/z80/src/ez80/ez80_restorcontext.asm ; -; Copyright (C) 2008 Gregory Nutt. All rights reserved. +; Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. ; Author: Gregory Nutt ; ; Redistribution and use in source and binary forms, with or without @@ -76,7 +76,7 @@ _ez80_restorecontext: ; Restore registers. HL points to the beginning of the reg structure to restore ex af, af' ; Select alternate AF - pop af ; Offset 0: AF' = I with interrupt state in carry + pop af ; Offset 0: AF' = I with interrupt state in parity ex af, af' ; Restore original AF pop bc ; Offset 1: BC pop de ; Offset 2: DE diff --git a/nuttx/arch/z80/src/ez80/ez80_saveusercontext.asm b/nuttx/arch/z80/src/ez80/ez80_saveusercontext.asm index 4a034dc21..ecd7db114 100644 --- a/nuttx/arch/z80/src/ez80/ez80_saveusercontext.asm +++ b/nuttx/arch/z80/src/ez80/ez80_saveusercontext.asm @@ -1,7 +1,7 @@ ;************************************************************************* ; arch/z80/src/ez80/ez80_saveusercontext.asm ; -; Copyright (C) 2008 Gregory Nutt. All rights reserved. +; Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. ; Author: Gregory Nutt ; ; Redistribution and use in source and binary forms, with or without @@ -52,7 +52,7 @@ .if CONFIG_EZ80_Z80MODE ; Register save area layout - XCPT_I equ 2*0 ; Offset 0: Saved I w/interrupt state in carry + XCPT_I equ 2*0 ; Offset 0: Saved I w/interrupt state in parity XCPT_BC equ 2*1 ; Offset 1: Saved BC register XCPT_DE equ 2*2 ; Offset 2: Saved DE register XCPT_IX equ 2*3 ; Offset 3: Saved IX register @@ -73,7 +73,7 @@ .else ; Register save area layout - XCPT_I equ 3*0 ; Offset 0: Saved I w/interrupt state in carry + XCPT_I equ 3*0 ; Offset 0: Saved I w/interrupt state in parity XCPT_BC equ 3*1 ; Offset 1: Saved BC register XCPT_DE equ 3*2 ; Offset 2: Saved DE register XCPT_IX equ 3*3 ; Offset 3: Saved IX register diff --git a/nuttx/arch/z80/src/ez80/ez80_vectors.asm b/nuttx/arch/z80/src/ez80/ez80_vectors.asm index e6b7ea2fb..3e3d44ced 100644 --- a/nuttx/arch/z80/src/ez80/ez80_vectors.asm +++ b/nuttx/arch/z80/src/ez80/ez80_vectors.asm @@ -1,7 +1,7 @@ ;************************************************************************** ; arch/z80/src/ez80/ez80_vectors.asm ; -; Copyright (C) 2008 Gregory Nutt. All rights reserved. +; Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. ; Author: Gregory Nutt ; ; Redistribution and use in source and binary forms, with or without @@ -230,7 +230,7 @@ _ez80_rstcommon: ; this context is restored ld bc, #EZ80_PV_FLAG ; Parity bit. 1=parity odd, IEF2=1 - push bc ; Offset 0: I with interrupt state in carry + push bc ; Offset 0: I with interrupt state in parity di ; (not necessary) ; Call the interrupt decode logic. SP points to the beggining of the reg structure @@ -253,7 +253,7 @@ _ez80_rstcommon: ; Restore registers. HL points to the beginning of the reg structure to restore ex af, af' ; Select alternate AF - pop af ; Offset 0: AF' = I with interrupt state in carry + pop af ; Offset 0: AF' = I with interrupt state in parity ex af, af' ; Restore original AF pop bc ; Offset 1: BC pop de ; Offset 2: DE diff --git a/nuttx/arch/z80/src/z80/switch.h b/nuttx/arch/z80/src/z80/switch.h index 73a88d449..318a01a13 100644 --- a/nuttx/arch/z80/src/z80/switch.h +++ b/nuttx/arch/z80/src/z80/switch.h @@ -2,7 +2,7 @@ * arch/z80/src/z80/switch.h * arch/z80/src/chip/switch.h * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -52,7 +52,7 @@ /* Macros for portability *********************************************************** * - * Common logic in arch/z80/src/common is customized for the z8 context switching + * Common logic in arch/z80/src/common is customized for the z80 context switching * logic via the following macros. */ @@ -60,7 +60,7 @@ #define INIT_IRQCONTEXT() current_regs = NULL -/* IN_INTERRUPT returns TRUE if the system is current operating in the interrupt +/* IN_INTERRUPT returns TRUE if the system is currently operating in the interrupt * context. IN_INTERRUPT is the inline equivalent of up_interrupt_context(). */ diff --git a/nuttx/arch/z80/src/z80/z80_head.asm b/nuttx/arch/z80/src/z80/z80_head.asm index ce1a4c948..0eb166af6 100644 --- a/nuttx/arch/z80/src/z80/z80_head.asm +++ b/nuttx/arch/z80/src/z80/z80_head.asm @@ -1,7 +1,7 @@ ;************************************************************************** ; arch/z80/src/z80/z80_head.asm ; -; Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. +; Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. ; Author: Gregory Nutt ; ; Redistribution and use in source and binary forms, with or without @@ -205,8 +205,8 @@ _up_rstcommon:: 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 + 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 beggining of the reg structure @@ -251,7 +251,7 @@ _up_rstcommon:: ; Restore interrupt state ex af, af' ; Recover interrupt state - jr nc, nointenable ; No carry, IFF2=0, means disabled + jp po, nointenable ; Odd parity, IFF2=0, means disabled ex af, af' ; Restore AF (before enabling interrupts) ei ; yes reti diff --git a/nuttx/arch/z80/src/z80/z80_initialstate.c b/nuttx/arch/z80/src/z80/z80_initialstate.c index c63baa021..f9d3456b1 100644 --- a/nuttx/arch/z80/src/z80/z80_initialstate.c +++ b/nuttx/arch/z80/src/z80/z80_initialstate.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/z80/src/z80/z80_initialstate.c * - * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -71,7 +71,7 @@ * 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 + * This function must setup the initial architecture registers * and/or stack so that execution will begin at tcb->start * on the next context switch. * @@ -85,7 +85,7 @@ void up_initial_state(_TCB *tcb) memset(xcp, 0, sizeof(struct xcptcontext)); #ifndef CONFIG_SUPPRESS_INTERRUPTS - xcp->regs[XCPT_I] = Z80_C_FLAG; /* Carry flag will enable interrupts */ + xcp->regs[XCPT_I] = Z80_PV_FLAG; /* Parity flag will enable interrupts */ #endif 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/z80/z80_irq.c b/nuttx/arch/z80/src/z80/z80_irq.c index 5b4de5dc9..f3b37bcb4 100644 --- a/nuttx/arch/z80/src/z80/z80_irq.c +++ b/nuttx/arch/z80/src/z80/z80_irq.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/z80/src/z80/z80_irq.c * - * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -84,7 +84,7 @@ chipreg_t *current_regs; irqstate_t irqsave(void) __naked { _asm - ld a, i ; AF Carry bit holds interrupt state + ld a, i ; AF Parity bit holds interrupt state di ; Interrupts are disabled push af ; Return AF in HL pop hl ; @@ -105,8 +105,8 @@ void irqrestore(irqstate_t flags) __naked _asm di ; Assume disabled pop hl ; HL = return address - pop af ; AF Carry bit hold interrupt state - jr nc, statedisable + pop af ; AF Parity bit holds interrupt state + jp po, statedisable ei statedisable: push af ; Restore stack diff --git a/nuttx/arch/z80/src/z80/z80_restoreusercontext.asm b/nuttx/arch/z80/src/z80/z80_restoreusercontext.asm index 27dbdf433..79c3a6034 100644 --- a/nuttx/arch/z80/src/z80/z80_restoreusercontext.asm +++ b/nuttx/arch/z80/src/z80/z80_restoreusercontext.asm @@ -1,7 +1,7 @@ ;************************************************************************** ; arch/z80/src/z80/z80_restoreusercontext.asm ; -; Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. +; Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. ; Author: Gregory Nutt ; ; Redistribution and use in source and binary forms, with or without @@ -72,7 +72,7 @@ _z80_restoreusercontext: ; Restore registers. HL points to the beginning of the reg structure to restore ex af, af' ; Select alternate AF - pop af ; Offset 0: AF' = I with interrupt state in carry + pop af ; Offset 0: AF' = I with interrupt state in parity ex af, af' ; Restore original AF pop bc ; Offset 1: BC pop de ; Offset 2: DE @@ -95,7 +95,7 @@ _z80_restoreusercontext: ; Restore interrupt state ex af, af' ; Recover interrupt state - jr nc, noinrestore ; No carry, IFF2=0, means disabled + jp po, noinrestore ; Odd parity, IFF2=0, means disabled ex af, af' ; Restore AF (before enabling interrupts) ei ; yes.. Enable interrupts ret ; and return diff --git a/nuttx/arch/z80/src/z80/z80_rom.asm b/nuttx/arch/z80/src/z80/z80_rom.asm index 9b7a2a191..b2fd76bb3 100644 --- a/nuttx/arch/z80/src/z80/z80_rom.asm +++ b/nuttx/arch/z80/src/z80/z80_rom.asm @@ -1,7 +1,7 @@ ;************************************************************************** ; arch/z80/src/z80/z80_rom.asm ; -; Copyright (C) 2008 Gregory Nutt. All rights reserved. +; Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. ; Author: Gregory Nutt ; ; Redistribution and use in source and binary forms, with or without @@ -42,7 +42,7 @@ ; Register save area layout - XCPT_I == 0 ; Offset 0: Saved I w/interrupt state in carry + XCPT_I == 0 ; Offset 0: Saved I w/interrupt state in parity XCPT_BC == 2 ; Offset 1: Saved BC register XCPT_DE == 4 ; Offset 2: Saved DE register XCPT_IX == 6 ; Offset 3: Saved IX register @@ -198,11 +198,11 @@ _up_rstcommon: 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 + 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 beggining of the reg structure + ; 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 ; @@ -214,14 +214,14 @@ _up_rstcommon: ; 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. + ; 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 + pop af ; Offset 0: AF' = I with interrupt state in parity ex af, af' ; Restore original AF pop bc ; Offset 1: BC pop de ; Offset 2: DE @@ -244,7 +244,7 @@ _up_rstcommon: ; Restore interrupt state ex af, af' ; Recover interrupt state - jr nc, nointenable ; No carry, IFF2=0, means disabled + jp po, nointenable ; Odd parity, IFF2=0, means disabled ex af, af' ; Restore AF (before enabling interrupts) ei ; yes reti diff --git a/nuttx/arch/z80/src/z80/z80_saveusercontext.asm b/nuttx/arch/z80/src/z80/z80_saveusercontext.asm index 807b3fce1..e23039dfc 100644 --- a/nuttx/arch/z80/src/z80/z80_saveusercontext.asm +++ b/nuttx/arch/z80/src/z80/z80_saveusercontext.asm @@ -1,7 +1,7 @@ ;************************************************************************* ; arch/z80/src/z80/z80_saveusercontext.asm ; -; Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. +; Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. ; Author: Gregory Nutt ; ; Redistribution and use in source and binary forms, with or without @@ -39,7 +39,7 @@ ; Register save area layout - .globl XCPT_I ; Offset 0: Saved I w/interrupt state in carry + .globl XCPT_I ; Offset 0: Saved I w/interrupt state in parity .globl XCPT_BC ; Offset 1: Saved BC register .globl XCPT_DE ; Offset 2: Saved DE register .globl XCPT_IX ; Offset 3: Saved IX register @@ -85,7 +85,7 @@ _z80_saveusercontext: ld a, i ; Get interrupt state push af pop hl - ld XCPT_I(iy), l ; Offset 0: I w/interrupt state in carry + ld XCPT_I(iy), l ; Offset 0: I w/interrupt state in parity ld XCPT_I+1(iy), h ; Save BC at offset 1 diff --git a/nuttx/configs/xtrs/src/xtrs_head.asm b/nuttx/configs/xtrs/src/xtrs_head.asm index 9ead016fd..5fb33c3c8 100644 --- a/nuttx/configs/xtrs/src/xtrs_head.asm +++ b/nuttx/configs/xtrs/src/xtrs_head.asm @@ -1,7 +1,7 @@ ;************************************************************************** ; configs/xtrs/src/xtrs_head.asm ; -; Copyright (C) 2008 Gregory Nutt. All rights reserved. +; Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. ; Author: Gregory Nutt ; ; Redistribution and use in source and binary forms, with or without @@ -42,7 +42,7 @@ ; Register save area layout - XCPT_I == 0 ; Offset 0: Saved I w/interrupt state in carry + XCPT_I == 0 ; Offset 0: Saved I w/interrupt state in parity XCPT_BC == 2 ; Offset 1: Saved BC register XCPT_DE == 4 ; Offset 2: Saved DE register XCPT_IX == 6 ; Offset 3: Saved IX register @@ -198,8 +198,8 @@ _up_rstcommon: 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 + 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 beggining of the reg structure @@ -221,7 +221,7 @@ _up_rstcommon: ; Restore registers. HL points to the beginning of the reg structure to restore ex af, af' ; Select alternate AF - pop af ; Offset 0: AF' = I with interrupt state in carry + pop af ; Offset 0: AF' = I with interrupt state in parity ex af, af' ; Restore original AF pop bc ; Offset 1: BC pop de ; Offset 2: DE @@ -244,7 +244,7 @@ _up_rstcommon: ; Restore interrupt state ex af, af' ; Recover interrupt state - jr nc, nointenable ; No carry, IFF2=0, means disabled + jp po, nointenable ; Odd parity, IFF2=0, means disabled ex af, af' ; Restore AF (before enabling interrupts) ei ; yes reti -- cgit v1.2.3