summaryrefslogtreecommitdiff
path: root/nuttx/arch/z80
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-12-12 17:06:47 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-12-12 17:06:47 +0000
commit1d7cb63254ce5ed4142cb5192c6358ac1521f2c8 (patch)
treec8fb78daf768769eb74bab2fcb25c47450a5dfc0 /nuttx/arch/z80
parent0cfc4cf403f5aa72624359c7db7f3a6c88346ad3 (diff)
downloadpx4-nuttx-1d7cb63254ce5ed4142cb5192c6358ac1521f2c8.tar.gz
px4-nuttx-1d7cb63254ce5ed4142cb5192c6358ac1521f2c8.tar.bz2
px4-nuttx-1d7cb63254ce5ed4142cb5192c6358ac1521f2c8.zip
Add z180 interrupt initialization logic
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5433 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/z80')
-rw-r--r--nuttx/arch/z80/include/z180/irq.h6
-rw-r--r--nuttx/arch/z80/src/z180/z180_irq.c64
-rw-r--r--nuttx/arch/z80/src/z180/z180_romvectors.asm38
-rw-r--r--nuttx/arch/z80/src/z180/z180_vectcommon.asm21
-rw-r--r--nuttx/arch/z80/src/z180/z180_vectors.asm38
5 files changed, 106 insertions, 61 deletions
diff --git a/nuttx/arch/z80/include/z180/irq.h b/nuttx/arch/z80/include/z180/irq.h
index 6fbeaf5b5..1d0c27cb4 100644
--- a/nuttx/arch/z80/include/z180/irq.h
+++ b/nuttx/arch/z80/include/z180/irq.h
@@ -111,14 +111,10 @@
*
* 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_INT1 (9) /* Vector offset 0: External /INT1 */
#define Z180_INT2 (10) /* Vector offset 2: External /INT2 */
diff --git a/nuttx/arch/z80/src/z180/z180_irq.c b/nuttx/arch/z80/src/z180/z180_irq.c
index d5d625b33..96a691c4c 100644
--- a/nuttx/arch/z80/src/z180/z180_irq.c
+++ b/nuttx/arch/z80/src/z180/z180_irq.c
@@ -38,10 +38,16 @@
****************************************************************************/
#include <nuttx/config.h>
+
+#include <stdint.h>
+
#include <nuttx/arch.h>
#include <nuttx/irq.h>
-#include "chip/switch.h"
+#include <arch/io.h>
+
+#include "switch.h"
+#include "z180_iomap.h"
#include "up_internal.h"
/****************************************************************************
@@ -66,6 +72,12 @@ volatile chipreg_t *current_regs;
uint8_t current_cbr;
+/* The interrupt vector table is exported by z180_vectors.asm or
+ * z180_romvectors.asm with the name up_vectors:
+ */
+
+extern uintptr_t up_vectors[16];
+
/****************************************************************************
* Private Data
****************************************************************************/
@@ -75,6 +87,22 @@ uint8_t current_cbr;
****************************************************************************/
/****************************************************************************
+ * Name: z180_seti
+ *
+ * Description:
+ * Input byte from port p
+ *
+ ****************************************************************************/
+
+static void z180_seti(uint8_t value) __naked
+{
+ __asm
+ ld a, 4(ix) ;value
+ ld l, a
+ __endasm;
+}
+
+/****************************************************************************
* Public Functions
****************************************************************************/
@@ -119,3 +147,37 @@ statedisable:
ret ; and return
__endasm;
}
+
+/****************************************************************************
+ * Name: up_irqinitialize
+ *
+ * Description:
+ * Initialize and enable interrupts
+ *
+ ****************************************************************************/
+
+void up_irqinitialize(void)
+{
+ uint16_t vectaddr = (uint16_t)up_vectors;
+ uint8_t regval;
+
+ /* Initialize the I and IL registers so that the interrupt vector table
+ * is used.
+ */
+
+ regval = (uint8_t)(vectaddr >> 8);
+ z180_seti(regval);
+
+ regval = (uint8_t)(vectaddr & IL_MASK);
+ outp(Z180_INT_IL, regval);
+
+ /* Disable external interrupts */
+
+ outp(Z180_INT_ITC, 0);
+
+ /* And finally, enable interrupts (including the timer) */
+
+#ifndef CONFIG_SUPPRESS_INTERRUPTS
+ irqrestore(Z180_C_FLAG);
+#endif
+}
diff --git a/nuttx/arch/z80/src/z180/z180_romvectors.asm b/nuttx/arch/z80/src/z180/z180_romvectors.asm
index 2871be2bb..b4ca907cb 100644
--- a/nuttx/arch/z80/src/z180/z180_romvectors.asm
+++ b/nuttx/arch/z80/src/z180/z180_romvectors.asm
@@ -54,12 +54,6 @@
.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
@@ -71,19 +65,19 @@
.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
+ .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
diff --git a/nuttx/arch/z80/src/z180/z180_vectcommon.asm b/nuttx/arch/z80/src/z180/z180_vectcommon.asm
index 300ad2f31..c7d9a608a 100644
--- a/nuttx/arch/z80/src/z180/z180_vectcommon.asm
+++ b/nuttx/arch/z80/src/z180/z180_vectcommon.asm
@@ -58,14 +58,13 @@
.globl _up_doirq ; Interrupt decoding logic
-
;**************************************************************************
; Vector Handlers
;**************************************************************************
.area _CODE
-up_int1:: ; Vector offset 0: External /INT1
+_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
@@ -73,7 +72,7 @@ up_int1:: ; Vector offset 0: External /INT1
ld a, #9 ; 9 = Z180_INT1
jr _up_vectcommon ; Remaining RST handling is common
-up_int2:: ; Vector offset 2: External /INT2
+_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
@@ -81,7 +80,7 @@ up_int2:: ; Vector offset 2: External /INT2
ld a, #10 ; 10 = Z180_INT2
jr _up_vectcommon ; Remaining RST handling is common
-up_prt0:: ; Vector offset 4: PRT channel 0
+_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
@@ -89,7 +88,7 @@ up_prt0:: ; Vector offset 4: PRT channel 0
ld a, #11 ; 11 = Z180_PRT0
jr _up_vectcommon ; Remaining RST handling is common
-up_prt1:: ; Vector offset 6: PRT channel 1
+_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
@@ -97,7 +96,7 @@ up_prt1:: ; Vector offset 6: PRT channel 1
ld a, #12 ; 12 = Z180_PRT1
jr _up_vectcommon ; Remaining RST handling is common
-up_dma0:: ; Vector offset 8: DMA channel 0
+_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
@@ -105,7 +104,7 @@ up_dma0:: ; Vector offset 8: DMA channel 0
ld a, #13 ; 13 = Z180_DMA0
jr _up_vectcommon ; Remaining RST handling is common
-up_dma1:: ; Vector offset 8: DMA channel 1
+_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
@@ -113,7 +112,7 @@ up_dma1:: ; Vector offset 8: DMA channel 1
ld a, #14 ; 14 = Z180_DMA1
jr _up_vectcommon ; Remaining RST handling is common
-up_csio:: ; Vector offset 12: Clocked serial I/O
+_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
@@ -121,7 +120,7 @@ up_csio:: ; Vector offset 12: Clocked serial I/O
ld a, #15 ; 15 = Z180_CSIO
jr _up_vectcommon ; Remaining RST handling is common
-up_asci0:: ; Vector offset 14: Async channel 0
+_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
@@ -129,7 +128,7 @@ up_asci0:: ; Vector offset 14: Async channel 0
ld a, #16 ; 16 = Z180_ASCI0
jr _up_vectcommon ; Remaining RST handling is common
-up_asci1:: ; Vector offset 16: Async channel 1
+_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
@@ -137,7 +136,7 @@ up_asci1:: ; Vector offset 16: Async channel 1
ld a, #17 ; 17 = Z180_ASCI1
jr _up_vectcommon ; Remaining RST handling is common
-up_unused:: ; Vector offset 18: Unused
+_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
diff --git a/nuttx/arch/z80/src/z180/z180_vectors.asm b/nuttx/arch/z80/src/z180/z180_vectors.asm
index cd544b926..3bda5c470 100644
--- a/nuttx/arch/z80/src/z180/z180_vectors.asm
+++ b/nuttx/arch/z80/src/z180/z180_vectors.asm
@@ -54,12 +54,6 @@
.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
@@ -72,19 +66,19 @@
.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
+ .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