summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-03-23 17:58:08 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-03-23 17:58:08 +0000
commit80962cfd5bd1ba72390abaa35f2aa91cab69fd67 (patch)
tree2c69ec9524423f404b8e0ef0e1b21b171e0caa93 /nuttx
parent739f1170b4d8b8f02e33c9f46ae933454ddf3078 (diff)
downloadpx4-nuttx-80962cfd5bd1ba72390abaa35f2aa91cab69fd67.tar.gz
px4-nuttx-80962cfd5bd1ba72390abaa35f2aa91cab69fd67.tar.bz2
px4-nuttx-80962cfd5bd1ba72390abaa35f2aa91cab69fd67.zip
Implement irqsave/restore
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@747 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/z80/include/ez80/types.h4
-rw-r--r--nuttx/arch/z80/src/ez80/Make.defs3
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_irq.c29
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_irqsave.asm88
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_vectors.asm14
5 files changed, 98 insertions, 40 deletions
diff --git a/nuttx/arch/z80/include/ez80/types.h b/nuttx/arch/z80/include/ez80/types.h
index a84e9eb57..f8de240c4 100644
--- a/nuttx/arch/z80/include/ez80/types.h
+++ b/nuttx/arch/z80/include/ez80/types.h
@@ -81,10 +81,10 @@ typedef long sint32;
typedef unsigned long uint32;
/* This is the size of the interrupt state save returned by irqsave().
- * It holds the contents of the interrupt vector address
+ * It holds the AF regiser pair + a zero pad byte
*/
-typedef ubyte irqstate_t;
+typedef uint24 irqstate_t;
#endif /* __ASSEMBLY__ */
diff --git a/nuttx/arch/z80/src/ez80/Make.defs b/nuttx/arch/z80/src/ez80/Make.defs
index 1d9eba434..40a7469cb 100644
--- a/nuttx/arch/z80/src/ez80/Make.defs
+++ b/nuttx/arch/z80/src/ez80/Make.defs
@@ -43,7 +43,8 @@ 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_ASRCS = ez80_startup.asm ez80_saveusercontext.asm ez80_restorecontext.asm
+CHIP_ASRCS = ez80_startup.asm ez80_irqsave.asm \
+ ez80_saveusercontext.asm ez80_restorecontext.asm
ifeq ($(CONFIG_ARCH_CHIP_EZ80F91),y)
CHIP_ASRCS += ez80f91_init.asm
endif
diff --git a/nuttx/arch/z80/src/ez80/ez80_irq.c b/nuttx/arch/z80/src/ez80/ez80_irq.c
index 7702be3a6..d36441f5e 100644
--- a/nuttx/arch/z80/src/ez80/ez80_irq.c
+++ b/nuttx/arch/z80/src/ez80/ez80_irq.c
@@ -78,30 +78,13 @@ chipreg_t *current_regs;
void up_irqinitialize(void)
{
-}
+ current_regs = NULL;
+
+ /* And finally, enable interrupts */
-/****************************************************************************
- * Name: irqsave
- *
- * Description:
- * Disable all interrupts; return previous interrupt state
- *
- ****************************************************************************/
-
-irqstate_t irqsave(void)
-{
-}
-
-/****************************************************************************
- * Name: irqrestore
- *
- * Description:
- * Restore previous interrupt state
- *
- ****************************************************************************/
-
-void irqrestore(irqstate_t flags)
-{
+#ifndef CONFIG_SUPPRESS_INTERRUPTS
+ asm("ei");
+#endif
}
/****************************************************************************
diff --git a/nuttx/arch/z80/src/ez80/ez80_irqsave.asm b/nuttx/arch/z80/src/ez80/ez80_irqsave.asm
new file mode 100644
index 000000000..be1381e6b
--- /dev/null
+++ b/nuttx/arch/z80/src/ez80/ez80_irqsave.asm
@@ -0,0 +1,88 @@
+;**************************************************************************
+; arch/z80/src/ez80/ez80_irqsave.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.
+;
+;**************************************************************************
+
+;**************************************************************************
+; Global Symbols Imported
+;**************************************************************************
+
+;**************************************************************************
+; Global Symbols Expported
+;**************************************************************************
+
+ xdef _irqsave
+ xdef _irqrestore
+
+;**************************************************************************
+; Code
+;**************************************************************************
+
+ segment CODE
+ .assume ADL=1
+
+;****************************************************************************
+;* Name: irqstate_t irqsave(void)
+;*
+;* Description:
+;* Disable all interrupts; return previous interrupt state
+;*
+;****************************************************************************
+
+_irqsave:
+ ld a, i ; AF = interrupt state
+ di ; Interrupts are disabled (does not affect F)
+ push af ; Transfer to HL via the stack
+ pop hl ;
+ ret ; And return
+
+;****************************************************************************
+;* Name: void irqrestore(irqstate_t flags)
+;*
+;* Description:
+;* Restore previous interrupt state
+;*
+;****************************************************************************
+
+_irqrestore:
+ di ; Assume disabled
+ pop hl ; HL = return address
+ pop af ; AF Parity bit holds interrupt state
+ jp po, _disabled ; Skip over re-enable if Parity odd
+ ei ; Re-enable interrupts
+_disabled:
+ push af ; Restore stack
+ push hl ;
+ ret ; and return
+
+ end
diff --git a/nuttx/arch/z80/src/ez80/ez80_vectors.asm b/nuttx/arch/z80/src/ez80/ez80_vectors.asm
index 6dc461dff..1b9d7ef45 100644
--- a/nuttx/arch/z80/src/ez80/ez80_vectors.asm
+++ b/nuttx/arch/z80/src/ez80/ez80_vectors.asm
@@ -81,20 +81,6 @@ irqhandler: macro vectno
jp _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
;**************************************************************************