summaryrefslogtreecommitdiff
path: root/nuttx/arch/z80/include/ez80
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-03-09 19:56:37 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-03-09 19:56:37 +0000
commit961958ec0596a99fae3e89c33ef5244e9ffa3075 (patch)
tree1579b1a7a20708dc1ec24da460694d8dfb8631d7 /nuttx/arch/z80/include/ez80
parentde0affae842e70756489424f18ce5ab1d53786d9 (diff)
downloadpx4-nuttx-961958ec0596a99fae3e89c33ef5244e9ffa3075.tar.gz
px4-nuttx-961958ec0596a99fae3e89c33ef5244e9ffa3075.tar.bz2
px4-nuttx-961958ec0596a99fae3e89c33ef5244e9ffa3075.zip
EZ80 support
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@729 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/z80/include/ez80')
-rw-r--r--nuttx/arch/z80/include/ez80/arch.h77
-rw-r--r--nuttx/arch/z80/include/ez80/irq.h256
-rw-r--r--nuttx/arch/z80/include/ez80/types.h95
3 files changed, 428 insertions, 0 deletions
diff --git a/nuttx/arch/z80/include/ez80/arch.h b/nuttx/arch/z80/include/ez80/arch.h
new file mode 100644
index 000000000..2440c12e4
--- /dev/null
+++ b/nuttx/arch/z80/include/ez80/arch.h
@@ -0,0 +1,77 @@
+/****************************************************************************
+ * arch/ez80/arch.h
+ * arch/chip/arch.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather,
+ * only indirectly through nuttx/arch.h (via arch/arch.h)
+ */
+
+#ifndef __ARCH_EZ80_ARCH_H
+#define __ARCH_EZ80_ARCH_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __ARCH_EZ80_ARCH_H */
+
diff --git a/nuttx/arch/z80/include/ez80/irq.h b/nuttx/arch/z80/include/ez80/irq.h
new file mode 100644
index 000000000..96cb54f08
--- /dev/null
+++ b/nuttx/arch/z80/include/ez80/irq.h
@@ -0,0 +1,256 @@
+/****************************************************************************
+ * arch/ez80/include/ez80/irq.h
+ * arch/chip/irq.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather,
+ * only indirectly through nuttx/irq.h (via arch/irq.h)
+ */
+
+#ifndef __ARCH_EZ80_IRQ_H
+#define __ARCH_EZ80_IRQ_H
+
+#ifndef _EZ80F91
+# error "Only the EZ80F91 is currently supported"
+#endif
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* ez80 Interrupt Numbers ***************************************************/
+
+#define EZ80_EMACRX_IRQ (0) /* Vector 0x40 */
+#define EZ80_EMACTX_IRQ (1) /* Vector 0x44 */
+#define EZ80_EMACSYS_IRQ (2) /* Vector 0x48 */
+#define EZ80_PLL_IRQ (3) /* Vector 0x4c */
+#define EZ80_FLASH_IRQ (4) /* Vector 0x50 */
+
+#define EZ80_TIMER0_IRQ (5) /* Vector Ox54 */
+#define EZ80_TIMER1_IRQ (6) /* Vector Ox58 */
+#define EZ80_TIMER2_IRQ (7) /* Vector Ox5c */
+#define EZ80_TIMER3_IRQ (8) /* Vector Ox60 */
+
+#define EZ80_RTC_IRQ (9) /* Vector Ox6C */
+#define EZ80_UART0_IRQ (10) /* Vector Ox70 */
+#define EZ80_UART1_IRQ (11) /* Vector Ox74 */
+
+#define EZ80_I2C_IRQ (12) /* Vector Ox78 */
+#define EZ80_SPI_IRQ (13) /* Vector Ox7c */
+
+#define EZ80_PORTA0_IRQ (14) /* Vector Ox80 */
+#define EZ80_PORTA1_IRQ (15) /* Vector Ox84 */
+#define EZ80_PORTA2_IRQ (16) /* Vector Ox88 */
+#define EZ80_PORTA3_IRQ (17) /* Vector Ox8c */
+#define EZ80_PORTA4_IRQ (18) /* Vector Ox90 */
+#define EZ80_PORTA5_IRQ (19) /* Vector Ox94 */
+#define EZ80_PORTA6_IRQ (20) /* Vector Ox98 */
+#define EZ80_PORTA7_IRQ (21) /* Vector Ox9c */
+
+#define EZ80_PORTB0_IRQ (22) /* Vector Oxa0 */
+#define EZ80_PORTB1_IRQ (23) /* Vector Oxa4 */
+#define EZ80_PORTB2_IRQ (24) /* Vector Oxa8 */
+#define EZ80_PORTB3_IRQ (25) /* Vector Oxac */
+#define EZ80_PORTB4_IRQ (26) /* Vector Oxb0 */
+#define EZ80_PORTB5_IRQ (27) /* Vector Oxb4 */
+#define EZ80_PORTB6_IRQ (28) /* Vector Oxb8 */
+#define EZ80_PORTB7_IRQ (29) /* Vector Oxbc */
+
+#define EZ80_PORTC0_IRQ (30) /* Vector Oxc0 */
+#define EZ80_PORTC1_IRQ (31) /* Vector Oxc4 */
+#define EZ80_PORTC2_IRQ (32) /* Vector Oxc8 */
+#define EZ80_PORTC3_IRQ (33) /* Vector Oxcc */
+#define EZ80_PORTC4_IRQ (34) /* Vector Oxd0 */
+#define EZ80_PORTC5_IRQ (35) /* Vector Oxd4 */
+#define EZ80_PORTC6_IRQ (36) /* Vector Oxd8 */
+#define EZ80_PORTC7_IRQ (37) /* Vector Oxdc */
+
+#define EZ80_PORTD0_IRQ (38) /* Vector Oxe0 */
+#define EZ80_PORTD1_IRQ (39) /* Vector Oxe4 */
+#define EZ80_PORTD2_IRQ (40) /* Vector Oxe8 */
+#define EZ80_PORTD3_IRQ (41) /* Vector Oxec */
+#define EZ80_PORTD4_IRQ (42) /* Vector Oxf0 */
+#define EZ80_PORTD5_IRQ (43) /* Vector Oxf4 */
+#define EZ80_PORTD6_IRQ (44) /* Vector Oxf8 */
+#define EZ80_PORTD7_IRQ (45) /* Vector Oxfc */
+
+#define NR_IRQS (46)
+#define EZ80_IRQ_SYSTIMER EZ80_TIMER0_IRQ
+
+/* IRQ Management Macros ****************************************************/
+
+/* IRQ State Save Format ****************************************************
+ *
+ * These indices describe how the ez8 context is save in the state save array
+ *
+ * Byte offsets:
+ */
+
+/* IRQ Stack Frame Format
+ *
+ * This stack frame is created on each interrupt. These registers are stored
+ * in the TCB to many context switches.
+ */
+
+/* chipreg_t indices */
+
+#define XCPT_I (0) /* Index 0: 16-bit interrupt vector register */
+#define XCPT_BC (1) /* Index 1: Saved 16-bit BC register */
+#define XCPT_DE (2) /* Index 2: Saved 16-bit DE register */
+#define XCPT_IX (3) /* Index 3: Saved 16-bit IX register */
+#define XCPT_IY (4) /* Index 4: Saved 16-bit IY register */
+#define XCPT_SP (5) /* Index 5: Saved 16-bit SP at time of interrupt */
+#define XCPT_HL (6) /* Index 6: Saved 16-bit HL register */
+#define XCPT_AF (7) /* Index 7: Saved 16-bit AF register */
+#define XCPT_PC (8) /* Index 8: Offset to 16-bit PC at time of interrupt */
+#define XCPTCONTEXT_REGS (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_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 */
+# define XCPT_DE_OFFSET (2*XCPT_DE) /* Offset 4: Saved 16-bit DE register */
+# define XCPT_E_OFFSET (2*XCPT_DE+0) /* Offset 4: Saved 8-bit E register */
+# define XCPT_D_OFFSET (2*XCPT_DE+1) /* Offset 5: Saved 8-bit D register */
+# define XCPT_IX_OFFSET (2*XCPT_IX) /* Offset 6: Saved 16-bit IX register */
+# define XCPT_IY_OFFSET (2*XCPT_IY) /* Offset 8: Saved 16-bit IY register */
+# define XCPT_SP_OFFSET (2*XCPT_SP) /* Offset 10: Saved 16-bit SP at time of interrupt */
+# define XCPT_HL_OFFSET (2*XCPT_HL) /* Offset 12: Saved 16-bit HL register */
+# define XCPT_L_OFFSET (2*XCPT_HL+0) /* Offset 12: Saved 8-bit L register */
+# define XCPT_H_OFFSET (2*XCPT_HL+1) /* Offset 13: Saved 8-bit H register */
+# define XCPT_AF_OFFSET (2*XCPT_AF) /* Offset 14: Saved 16-bit AF register */
+# define XCPT_F_OFFSET (2*XCPT_AF+0) /* Offset 14: Saved flags */
+# define XCPT_A_OFFSET (2*XCPT_AF+1) /* Offset 15: Saved 8-bit A register */
+# define XCPT_PC_OFFSET (2*XCPT_PC) /* Offset 16: Offset to 16-bit PC at time of interrupt */
+# define XCPTCONTEXT_SIZE (2*XCPTCONTEXT_REGS)
+#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_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 */
+# define XCPT_DE_OFFSET (3*XCPT_DE) /* Offset 6: Saved 24-bit DE register */
+# define XCPT_E_OFFSET (3*XCPT_DE+1) /* Offset 7: Saved 8-bit E register */
+# define XCPT_D_OFFSET (3*XCPT_DE+2) /* Offset 8: Saved 8-bit D register */
+# define XCPT_IX_OFFSET (3*XCPT_IX) /* Offset 9: Saved 24-bit IX register */
+# define XCPT_IY_OFFSET (3*XCPT_IY) /* Offset 12: Saved 24-bit IY register */
+# define XCPT_SP_OFFSET (3*XCPT_SP) /* Offset 15: Saved 24-bit SP at time of interrupt */
+# define XCPT_HL_OFFSET (3*XCPT_HL) /* Offset 18: Saved 24-bit HL register */
+# define XCPT_L_OFFSET (3*XCPT_HL+1) /* Offset 19: Saved 8-bit L register */
+# define XCPT_H_OFFSET (3*XCPT_HL+2) /* Offset 20: Saved 8-bit H register */
+# define XCPT_AF_OFFSET (3*XCPT_AF) /* Offset 21: Saved AF register */
+# define XCPT_F_OFFSET (3*XCPT_AF+1) /* Offset 22: Saved AF register */
+# define XCPT_A_OFFSET (3*XCPT_AF+2) /* Offset 23: Saved 8-bit A register */
+# define XCPT_PC_OFFSET (3*XCPT_PC) /* Offset 24: Offset to 24-bit PC at time of interrupt */
+# define XCPTCONTEXT_SIZE (3*XCPTCONTEXT_REGS)
+#endif
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/* This is the type of the register save array */
+
+#ifdef CONFIG_EZ80_Z80MODE
+typedef uint16 chipreg_t;
+#else
+typedef uint24 chipreg_t;
+#endif
+
+/* This struct defines the way the registers are stored. */
+
+struct xcptcontext
+{
+ /* Register save area */
+
+ chipreg_t regs[XCPTCONTEXT_REGS];
+
+ /* The following function pointer is non-zero if there
+ * are pending signals to be processed.
+ */
+
+#ifndef CONFIG_DISABLE_SIGNALS
+ CODE void *sigdeliver; /* Actual type is sig_deliver_t */
+
+ /* The following retains that state during signal execution */
+
+ chipreg_t saved_pc; /* Saved return address */
+ chipreg_t saved_irqctl; /* Saved interrupt state */
+#endif
+};
+#endif
+
+/****************************************************************************
+ * Inline functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+EXTERN irqstate_t irqsave(void);
+EXTERN void irqrestore(irqstate_t flags);
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif /* __ARCH_EZ80_IRQ_H */
+
diff --git a/nuttx/arch/z80/include/ez80/types.h b/nuttx/arch/z80/include/ez80/types.h
new file mode 100644
index 000000000..a84e9eb57
--- /dev/null
+++ b/nuttx/arch/z80/include/ez80/types.h
@@ -0,0 +1,95 @@
+/****************************************************************************
+ * arch/z80/include/ez80/types.h
+ * include/arch/chip/types.h
+ *
+ * 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 Gregory Nutt 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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather, only indirectly
+ * through sys/types.h
+ */
+
+#ifndef __ARCH_CHIP_TYPES_H
+#define __ARCH_CHIP_TYPES_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Type Declarations
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/* These are the sizes of the types supported by the ZiLOG Z8Encore! compiler:
+ *
+ * int - 24-bits
+ * short - 16-bits
+ * long - 32-bits
+ * char - 8-bits
+ * float - 32-bits
+ *
+ * Pointers:
+ *
+ * Z80 mode - 16 bits
+ * ADL mode - 24 bits
+ */
+
+typedef char sbyte;
+typedef unsigned char ubyte;
+typedef unsigned char uint8;
+typedef unsigned char boolean;
+typedef short sint16;
+typedef unsigned short uint16;
+typedef int sint24;
+typedef unsigned int uint24;
+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
+ */
+
+typedef ubyte irqstate_t;
+
+#endif /* __ASSEMBLY__ */
+
+/****************************************************************************
+ * Global Function Prototypes
+ ****************************************************************************/
+
+#endif /* __ARCH_CHIP_TYPES_H */