summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-03-23 21:22:19 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-03-23 21:22:19 +0000
commitab79926704fe3e83ac5904029ac67c0db89f3e87 (patch)
treecb3924574e08597d61a00d9f9d27caa3cf226193 /nuttx/arch
parent80962cfd5bd1ba72390abaa35f2aa91cab69fd67 (diff)
downloadpx4-nuttx-ab79926704fe3e83ac5904029ac67c0db89f3e87.tar.gz
px4-nuttx-ab79926704fe3e83ac5904029ac67c0db89f3e87.tar.bz2
px4-nuttx-ab79926704fe3e83ac5904029ac67c0db89f3e87.zip
Fix access to ez80 I/O address space
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@748 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/z80/include/ez80/io.h87
-rw-r--r--nuttx/arch/z80/src/ez80/Make.defs2
-rw-r--r--nuttx/arch/z80/src/ez80/chip.h13
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_io.asm154
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_irq.c29
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_irqsave.asm8
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_lowuart.c37
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_registerdump.c7
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_serial.c39
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_timerisr.c36
10 files changed, 315 insertions, 97 deletions
diff --git a/nuttx/arch/z80/include/ez80/io.h b/nuttx/arch/z80/include/ez80/io.h
new file mode 100644
index 000000000..84ba3f965
--- /dev/null
+++ b/nuttx/arch/z80/include/ez80/io.h
@@ -0,0 +1,87 @@
+/****************************************************************************
+ * arch/z80/include/ez80/io.h
+ * arch/chip/io.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 arch/io.h
+ */
+
+#ifndef __ARCH_EZ80_IO_H
+#define __ARCH_EZ80_IO_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <sys/types.h>
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Inline functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+EXTERN void outp(uint16 p, ubyte c);
+EXTERN ubyte inp(uint16 p);
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif /* __ARCH_EZ80_IO_H */
diff --git a/nuttx/arch/z80/src/ez80/Make.defs b/nuttx/arch/z80/src/ez80/Make.defs
index 40a7469cb..9273735e1 100644
--- a/nuttx/arch/z80/src/ez80/Make.defs
+++ b/nuttx/arch/z80/src/ez80/Make.defs
@@ -43,7 +43,7 @@ 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_irqsave.asm \
+CHIP_ASRCS = ez80_startup.asm ez80_io.asm ez80_irqsave.asm \
ez80_saveusercontext.asm ez80_restorecontext.asm
ifeq ($(CONFIG_ARCH_CHIP_EZ80F91),y)
CHIP_ASRCS += ez80f91_init.asm
diff --git a/nuttx/arch/z80/src/ez80/chip.h b/nuttx/arch/z80/src/ez80/chip.h
index 82aed0495..ef1f68759 100644
--- a/nuttx/arch/z80/src/ez80/chip.h
+++ b/nuttx/arch/z80/src/ez80/chip.h
@@ -251,19 +251,6 @@
#define EZ80_UARTMSR_DDSR 0x02 /* Bit 1: Delta on DSR input */
#define EZ80_UARTMSR_DCTS 0x01 /* Bit 0: Delta on CTS input */
-/* Register access macros ***********************************************************/
-
-#ifndef __ASSEMBLY__
-
-# define getreg8(a) (*(volatile ubyte *)(a))
-# define putreg8(v,a) (*(volatile ubyte *)(a) = (v))
-# define getreg16(a) (*(volatile uint16 *)(a))
-# define putreg16(v,a) (*(volatile uint16 *)(a) = (v))
-# define getreg32(a) (*(volatile uint32 *)(a))
-# define putreg32(v,a) (*(volatile uint32 *)(a) = (v))
-
-#endif
-
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
diff --git a/nuttx/arch/z80/src/ez80/ez80_io.asm b/nuttx/arch/z80/src/ez80/ez80_io.asm
new file mode 100644
index 000000000..86af3b3e8
--- /dev/null
+++ b/nuttx/arch/z80/src/ez80/ez80_io.asm
@@ -0,0 +1,154 @@
+;**************************************************************************
+; arch/z80/src/ze80/ez80_io.c
+;
+; 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 _outp
+ xdef _inp
+
+;**************************************************************************
+; Global Symbols Expported
+;**************************************************************************
+
+ CONFIG_EZ80_Z80MODE equ 0
+
+;**************************************************************************
+; Code
+;**************************************************************************
+
+ segment CODE
+ .assume ADL=1
+
+;**************************************************************************
+; Name: void outp(uint16 p, ubyte c)
+;
+; Description:
+; Output byte c on port p
+;
+;**************************************************************************
+
+_outp:
+ ; Create a stack frame
+
+ push ix
+ ld ix, #0
+ add ix, sp
+
+ ; Get the arguments from the stack
+
+ .if CONFIG_EZ80_Z80MODE
+ ; Stack looks like:
+ ;
+ ; 7-8 Unused
+ ; 6 Value
+ ; 4-5 Port
+ ; 2-3 Return address
+ ; SP: 0-1 Caller's fame pointer
+
+ ld bc, (ix + 4) ; Port
+ ld a, (ix + 6) ; Value
+
+ .else
+ ; Stack looks like:
+ ;
+ ; 10-11 Unused
+ ; 9 Value
+ ; 8 Unused
+ ; 6-7 Port
+ ; 3-5 Return address
+ ; SP: 0-2 Caller's frame pointer
+
+ ld bc, (ix + 6) ; Port (upper 8 bits not used)
+ ld a, (ix + 9) ; Value
+
+ .endif
+
+ ; Output the specified by to the specified 8-bit I/O address
+
+ out (bc), a
+ pop ix
+ ret
+
+;**************************************************************************
+; Name: ubyte inp(uint16 p)
+;
+; Description:
+; Input byte from port p
+;
+;**************************************************************************
+
+_inp:
+ ; Create a stack frame
+
+ push ix
+ ld ix, #0
+ add ix, sp
+
+ ; Get the arguments from the stack
+
+ .if CONFIG_EZ80_Z80MODE
+ ; Stack looks like:
+ ;
+ ; 4-5 Port
+ ; 2-3 Return address
+ ; SP: 0-1 Caller's fame pointer
+
+ ld bc, (ix + 4) ; Port
+
+ .else
+ ; Stack looks like:
+ ;
+ ; 8 Unused
+ ; 6-7 Port
+ ; 3-5 Return address
+ ; SP: 0-2 Caller's frame pointer
+
+ ld bc, (ix + 6) ; Port (upper 8 bits not used)
+
+ .endif
+
+ ; Return port value in A
+
+ in a, (bc)
+ pop ix
+ ret
+
+ end
diff --git a/nuttx/arch/z80/src/ez80/ez80_irq.c b/nuttx/arch/z80/src/ez80/ez80_irq.c
index d36441f5e..6e0fa71c6 100644
--- a/nuttx/arch/z80/src/ez80/ez80_irq.c
+++ b/nuttx/arch/z80/src/ez80/ez80_irq.c
@@ -91,34 +91,35 @@ void up_irqinitialize(void)
* Name: up_disable_irq
*
* Description:
- * Disable the IRQ specified by 'irq'
+ * On many architectures, there are three levels of interrupt enabling: (1)
+ * at the global level, (2) at the level of the interrupt controller,
+ * and (3) at the device level. In order to receive interrupts, they
+ * must be enabled at all three levels.
+ *
+ * This function implements disabling of the device specified by 'irq'
+ * at the interrupt controller level if supported by the architecture
+ * (irqsave() supports the global level, the device level is hardware
+ * specific).
*
****************************************************************************/
void up_disable_irq(int irq)
{
+ /* There are no ez80 interrupt controller settings to disable IRQs */
}
/****************************************************************************
* Name: up_enable_irq
*
* Description:
- * Enable the IRQ specified by 'irq'
+ * This function implements enabling of the device specified by 'irq'
+ * at the interrupt controller level if supported by the architecture
+ * (irqsave() supports the global level, the device level is hardware
+ * specific).
*
****************************************************************************/
void up_enable_irq(int irq)
{
-}
-
-/****************************************************************************
- * Name: up_maskack_irq
- *
- * Description:
- * Mask the IRQ and acknowledge it
- *
- ****************************************************************************/
-
-void up_maskack_irq(int irq)
-{
+ /* There are no ez80 interrupt controller settings to enable IRQs */
}
diff --git a/nuttx/arch/z80/src/ez80/ez80_irqsave.asm b/nuttx/arch/z80/src/ez80/ez80_irqsave.asm
index be1381e6b..c19ef0bdd 100644
--- a/nuttx/arch/z80/src/ez80/ez80_irqsave.asm
+++ b/nuttx/arch/z80/src/ez80/ez80_irqsave.asm
@@ -51,13 +51,13 @@
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
@@ -66,13 +66,13 @@ _irqsave:
pop hl ;
ret ; And return
-;****************************************************************************
+;**************************************************************************
;* Name: void irqrestore(irqstate_t flags)
;*
;* Description:
;* Restore previous interrupt state
;*
-;****************************************************************************
+;**************************************************************************
_irqrestore:
di ; Assume disabled
diff --git a/nuttx/arch/z80/src/ez80/ez80_lowuart.c b/nuttx/arch/z80/src/ez80/ez80_lowuart.c
index 4700bef19..bddf693a1 100644
--- a/nuttx/arch/z80/src/ez80/ez80_lowuart.c
+++ b/nuttx/arch/z80/src/ez80/ez80_lowuart.c
@@ -42,6 +42,7 @@
#include <sys/types.h>
#include <string.h>
+#include <arch/io.h>
#include <nuttx/arch.h>
#include <nuttx/sched.h>
@@ -59,9 +60,9 @@
extern unsigned long SYS_CLK_FREQ;
#define _DEFCLK ((unsigned long)&SYS_CLK_FREQ)
-#ifdef CONFIG_UART1_SERIAL_CONSOLE
-# define ez80_getreg(offs) getreg8((EZ80_UART1_BASE+(offs)))
-# define ez80_putreg(val,offs) putreg8((val), (EZ80_UART1_BASE+(offs)))
+#ifdef CONFIG_UART0_SERIAL_CONSOLE
+# define ez80_inp(offs) inp((EZ80_UART0_BASE+(offs)))
+# define ez80_outp(offs,val) outp((EZ80_UART0_BASE+(offs)), (val))
# define CONFIG_UART_BAUD CONFIG_UART0_BAUD
# if CONFIG_UART0_BITS == 7
# define CONFIG_UART_BITS EZ80_UARTCHAR_7BITS
@@ -81,8 +82,8 @@ extern unsigned long SYS_CLK_FREQ;
# define CONFIG_UART_PARITY 0
# endif
#else
-# define ez80_getreg(offs) getreg8((EZ80_UART0_BASE+(offs)))
-# define ez80_putreg(val,offs) putreg8((val), (EZ80_UART0_BASE+(offs)))
+# define ez80_inp(offs) inp((EZ80_UART1_BASE+(offs)))
+# define ez80_outp(offs.val) outp((EZ80_UART1_BASE+(offs)), (val))
# define CONFIG_UART_BAUD CONFIG_UART1_BAUD
# if CONFIG_UART1_BITS == 7
# define CONFIG_UART_BITS EZ80_UARTCHAR_7BITS
@@ -131,15 +132,15 @@ static void ez80_setbaud(void)
/* Set the DLAB bit to enable access to the BRG registers */
- lctl = ez80_getreg(EZ80_UART_LCTL);
+ lctl = ez80_inp(EZ80_UART_LCTL);
lctl |= EZ80_UARTLCTL_DLAB;
- ez80_putreg(lctl, EZ80_UART_LCTL);
+ ez80_outp(EZ80_UART_LCTL, lctl);
- ez80_putreg((ubyte)(brg_divisor & 0xff), EZ80_UART_BRGL);
- ez80_putreg((ubyte)(brg_divisor >> 8), EZ80_UART_BRGH);
+ ez80_outp(EZ80_UART_BRGL, (ubyte)(brg_divisor & 0xff));
+ ez80_outp(EZ80_UART_BRGH, (ubyte)(brg_divisor >> 8));
lctl &= ~EZ80_UARTLCTL_DLAB;
- ez80_putreg(lctl, EZ80_UART_LCTL);
+ ez80_outp(EZ80_UART_LCTL, lctl);
}
#endif /* CONFIG_SUPPRESS_UART_CONFIG */
@@ -158,33 +159,33 @@ void up_lowuartinit(void)
/* Disable interrupts from the UART */
- reg = ez80_getreg(EZ80_UART_IER);
+ reg = ez80_inp(EZ80_UART_IER);
reg &= ~EZ80_UARTEIR_INTMASK;
- ez80_putreg(reg, EZ80_UART_IER);
+ ez80_outp(EZ80_UART_IER, reg);
/* Set the baud rate */
ez80_setbaud();
- ez80_putreg(0, EZ80_UART_MCTL);
+ ez80_outp(EZ80_UART_MCTL, 0);
/* Set the character properties */
- reg = ez80_getreg(EZ80_UART_LCTL);
+ reg = ez80_inp(EZ80_UART_LCTL);
reg &= ~EZ80_UARTLCTL_MASK;
reg |= (CONFIG_UART_BITS | CONFIG_UART_2STOP | CONFIG_UART_PARITY);
- ez80_putreg(reg, EZ80_UART_LCTL);
+ ez80_outp(EZ80_UART_LCTL, reg);
/* Enable and flush the receive FIFO */
reg = EZ80_UARTFCTL_FIFOEN;
- ez80_putreg(reg, EZ80_UART_FCTL);
+ ez80_outp(EZ80_UART_FCTL, reg);
reg |= (EZ80_UARTFCTL_CLRTxF|EZ80_UARTFCTL_CLRRxF);
- ez80_putreg(reg, EZ80_UART_FCTL);
+ ez80_outp(EZ80_UART_FCTL, reg);
/* Set the receive trigger level to 1 */
reg |= EZ80_UARTTRIG_1;
- ez80_putreg(reg, EZ80_UART_FCTL);
+ ez80_outp(EZ80_UART_FCTL, reg);
#endif /* CONFIG_SUPPRESS_UART_CONFIG */
}
#endif /* CONFIG_USE_LOWUARTINIT */
diff --git a/nuttx/arch/z80/src/ez80/ez80_registerdump.c b/nuttx/arch/z80/src/ez80/ez80_registerdump.c
index dace6ad65..31a69679c 100644
--- a/nuttx/arch/z80/src/ez80/ez80_registerdump.c
+++ b/nuttx/arch/z80/src/ez80/ez80_registerdump.c
@@ -79,10 +79,9 @@ static void ez80_registerdump(void)
{
if (current_regs)
{
- lldbg("AF: %02x|%02x I: %02x|%02x\n",
- (ubyte*)current_regs)[XCPT_A_OFFSET], (ubyte*)current_regs)[XCPT_F_OFFSET],
- (ubyte*)current_regs)[XCPT_IA_OFFSET], (ubyte*)current_regs)[XCPT_IF_OFFSET]);
#ifdef CONFIG_EZ80_Z80MODE
+ lldbg("AF: %04x I: %04x\n",
+ current_regs[XCPT_AF], current_regs[XCPT_I]);
lldbg("BC: %04x DE: %04x HL: %04x\n",
current_regs[XCPT_BC], current_regs[XCPT_DE], current_regs[XCPT_HL]);
lldbg("IX: %04x IY: %04x\n",
@@ -90,6 +89,8 @@ static void ez80_registerdump(void)
lldbg("SP: %04x PC: %04x\n"
current_regs[XCPT_SP], current_regs[XCPT_PC]);
#else
+ lldbg("AF: %06x I: %06x\n",
+ current_regs[XCPT_AF], current_regs[XCPT_I]);
lldbg("BC: %06x DE: %06x HL: %06x\n",
current_regs[XCPT_BC], current_regs[XCPT_DE], current_regs[XCPT_HL]);
lldbg("IX: %06x IY: %06x\n",
diff --git a/nuttx/arch/z80/src/ez80/ez80_serial.c b/nuttx/arch/z80/src/ez80/ez80_serial.c
index 30070f6a8..75a780153 100644
--- a/nuttx/arch/z80/src/ez80/ez80_serial.c
+++ b/nuttx/arch/z80/src/ez80/ez80_serial.c
@@ -50,6 +50,7 @@
#include <nuttx/arch.h>
#include <nuttx/serial.h>
#include <arch/serial.h>
+#include <arch/io.h>
#include "chip/chip.h"
#include "os_internal.h"
@@ -72,7 +73,7 @@ extern unsigned long SYS_CLK_FREQ;
struct ez80_dev_s
{
- unsigned int uartbase; /* Base address of UART registers */
+ uint16 uartbase; /* Base address of UART registers */
unsigned int baud; /* Configured baud */
ubyte irq; /* IRQ associated with this UART */
ubyte parity; /* 0=none, 1=odd, 2=even */
@@ -231,9 +232,9 @@ static uart_dev_t g_uart1port =
* Name: ez80_serialin
****************************************************************************/
-static inline ubyte ez80_serialin(struct ez80_dev_s *priv, uint32 offset)
+static inline ubyte ez80_serialin(struct ez80_dev_s *priv, ubyte offset)
{
- return getreg8(priv->uartbase + offset);
+ return inp(priv->uartbase + offset);
}
/****************************************************************************
@@ -242,7 +243,7 @@ static inline ubyte ez80_serialin(struct ez80_dev_s *priv, uint32 offset)
static inline void ez80_serialout(struct ez80_dev_s *priv, ubyte offset, ubyte value)
{
- putreg8(value, priv->uartbase + offset);
+ outp(priv->uartbase + offset, value);
}
/****************************************************************************
@@ -359,7 +360,7 @@ static int ez80_setup(struct uart_dev_s *dev)
/* Set the baud rate */
- ez80_disableuartint(priv, NULL);
+ ez80_disableuartint(priv);
ez80_setbaud(priv, priv->baud);
ez80_serialout(priv, EZ80_UART_MCTL, 0);
@@ -415,20 +416,10 @@ static void ez80_shutdown(struct uart_dev_s *dev)
static int ez80_attach(struct uart_dev_s *dev)
{
struct ez80_dev_s *priv = (struct ez80_dev_s*)dev->priv;
- int ret;
-
- /* Attach and enable the IRQ */
- ret = irq_attach(priv->irq, ez80_interrrupt);
- if (ret == OK)
- {
- /* Enable the interrupt (RX and TX interrupts are still disabled
- * in the UART
- */
+ /* Attach the IRQ */
- up_enable_irq(priv->irq);
- }
- return ret;
+ return irq_attach(priv->irq, ez80_interrrupt);
}
/****************************************************************************
@@ -444,7 +435,7 @@ static int ez80_attach(struct uart_dev_s *dev)
static void ez80_detach(struct uart_dev_s *dev)
{
struct ez80_dev_s *priv = (struct ez80_dev_s*)dev->priv;
- up_disable_irq(priv->irq);
+ ez80_disableuartint(priv);
irq_detach(priv->irq);
}
@@ -726,15 +717,15 @@ int up_putc(int ch)
****************************************************************************/
#ifdef CONFIG_UART1_SERIAL_CONSOLE
-# define ez80_getreg(offs) getreg8((EZ80_UART1_BASE+(offs)))
-# define ez80_putreg(val,offs) putreg8((val), (EZ80_UART1_BASE+(offs)))
+# define ez80_inp(offs) inp((EZ80_UART1_BASE+(offs)))
+# define ez80_outp(offs,val) outp((EZ80_UART1_BASE+(offs)), (val))
#else
-# define ez80_getreg(offs) getreg8((EZ80_UART0_BASE+(offs)))
-# define ez80_putreg(val,offs) putreg8((val), (EZ80_UART0_BASE+(offs)))
+# define ez80_inp(offs) inp((EZ80_UART0_BASE+(offs)))
+# define ez80_outp(offs,val) outp((EZ80_UART0_BASE+(offs)), (val))
#endif
-#define ez80_txready() ((ez80_getreg(EZ80_UART_LSR) & EZ80_UARTLSR_THRE) != 0)
-#define ez80_send(ch) ez80_putreg(ch, EZ80_UART_THR)
+#define ez80_txready() ((ez80_inp(EZ80_UART_LSR) & EZ80_UARTLSR_THRE) != 0)
+#define ez80_send(ch) ez80_outp(EZ80_UART_THR, ch)
/****************************************************************************
* Private Function Prototypes
diff --git a/nuttx/arch/z80/src/ez80/ez80_timerisr.c b/nuttx/arch/z80/src/ez80/ez80_timerisr.c
index 7f371ad57..57a42cf01 100644
--- a/nuttx/arch/z80/src/ez80/ez80_timerisr.c
+++ b/nuttx/arch/z80/src/ez80/ez80_timerisr.c
@@ -42,6 +42,7 @@
#include <sys/types.h>
#include <debug.h>
+#include <arch/io.h>
#include <nuttx/arch.h>
#include "chip/chip.h"
@@ -85,11 +86,11 @@ int up_timerisr(int irq, chipreg_t *regs)
/* Read the appropropriate timer0 registr to clear the interrupt */
#ifdef _EZ80F91
- reg = getreg8(EZ80_TMR0_IIR);
+ reg = inp(EZ80_TMR0_IIR);
#else
/* _EZ80190, _EZ80L92, _EZ80F92, _EZ80F93 */
- reg = getreg8(EZ80_TMR0_CTL);
+ reg = inp(EZ80_TMR0_CTL);
#endif
/* Process timer interrupt */
@@ -112,13 +113,13 @@ void up_timerinit(void)
uint16 reload;
ubyte reg;
- /* Disable timer0 interrupts */
-
- up_disable_irq(EZ80_IRQ_SYSTIMER);
-
/* Disable the timer */
- putreg8(0x00, EZ80_TMR0_CTL);
+ outp(EZ80_TMR0_CTL, 0x00);
+
+ /* Attach system timer interrupts */
+
+ irq_attach(EZ80_IRQ_SYSTIMER, (xcpt_t)up_timerisr);
/* Set up the timer reload value */
/* Write to the timer reload register to set the reload value.
@@ -138,35 +139,30 @@ void up_timerinit(void)
*/
reload = (uint16)(_DEFCLK / 1600);
- putreg8((ubyte)(reload >> 8), EZ80_TMR0_RRH);
- putreg8((ubyte)(reload), EZ80_TMR0_RRL);
+ outp(EZ80_TMR0_RRH, (ubyte)(reload >> 8));
+ outp(EZ80_TMR0_RRL, (ubyte)(reload));
/* Clear any pending timer interrupts */
#if defined(_EZ80F91)
- reg = getreg8(EZ80_TMR0_IIR);
+ reg = inp(EZ80_TMR0_IIR);
#elif defined(_EZ80L92) || defined(_EZ80F92) ||defined(_EZ80F93)
- reg = getreg8(EZ80_TMR0_CTL);
+ reg = inp(EZ80_TMR0_CTL);
#endif
/* Configure and enable the timer */
#if defined(_EZ80190)
- putreg8(0x5f, EZ80_TMR0_CTL);
+ outp(EZ80_TMR0_CTL, 0x5f);
#elif defined(_EZ80F91)
- putreg8((EZ80_TMRCLKDIV_16|EZ80_TMRCTL_TIMCONT|EZ80_TMRCTL_RLD|EZ80_TMRCTL_TIMEN), EZ80_TMR0_CTL);
+ outp(EZ80_TMR0_CTL, (EZ80_TMRCLKDIV_16|EZ80_TMRCTL_TIMCONT|EZ80_TMRCTL_RLD|EZ80_TMRCTL_TIMEN));
#elif defined(_EZ80L92) || defined(_EZ80F92) ||defined(_EZ80F93)
- putreg8(0x57, EZ80_TMR0_CTL);
+ outp(EZ80_TMR0_CTL, 0x57);
#endif
/* Enable timer end-of-count interrupts */
#if defined(_EZ80F91)
- putreg8(EZ80_TMRIER_EOCEN, EZ80_TMR0_IER);
+ outp(EZ80_TMR0_IER, EZ80_TMRIER_EOCEN);
#endif
-
- /* Attach and enable the timer */
-
- irq_attach(EZ80_IRQ_SYSTIMER, (xcpt_t)up_timerisr);
- up_enable_irq(EZ80_IRQ_SYSTIMER);
}