From 9c5663a9a6caf432fa32043f6b347110691433ad Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 29 Dec 2007 16:31:25 +0000 Subject: First successful z80 compile & link git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@457 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/configs/z80sim/src/Makefile | 6 +- nuttx/configs/z80sim/src/z80_decodeirq.c | 56 ++++++---------- nuttx/configs/z80sim/src/z80_irq.c | 12 ++-- nuttx/configs/z80sim/src/z80_lowputc.c | 101 ++++++++++++++++++++++++++++ nuttx/configs/z80sim/src/z80_serial.c | 5 +- nuttx/configs/z80sim/src/z80_timerisr.c | 112 ++++++++----------------------- 6 files changed, 158 insertions(+), 134 deletions(-) create mode 100644 nuttx/configs/z80sim/src/z80_lowputc.c (limited to 'nuttx/configs/z80sim/src') diff --git a/nuttx/configs/z80sim/src/Makefile b/nuttx/configs/z80sim/src/Makefile index 24226f2f9..d1f495608 100644 --- a/nuttx/configs/z80sim/src/Makefile +++ b/nuttx/configs/z80sim/src/Makefile @@ -36,11 +36,11 @@ -include $(TOPDIR)/Make.defs MKDEP = $(TOPDIR)/tools/mkdeps.sh -CFLAGS += -I$(TOPDIR)/sched +CFLAGS += -I$(TOPDIR)/sched -I$(TOPDIR)/arch/z80/src/common -I$(TOPDIR)/arch/z80/src/z80 -ASRCS = z80_lowputc$(ASMEXT) +ASRCS = AOBJS = $(ASRCS:$(ASMEXT)=$(OBJEXT)) -CSRCS = z80_decodeirq.c z80_irq.c z80_serial.c z80_timerisr.c +CSRCS = z80_decodeirq.c z80_irq.c z80_serial.c z80_timerisr.c z80_lowputc.c COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) diff --git a/nuttx/configs/z80sim/src/z80_decodeirq.c b/nuttx/configs/z80sim/src/z80_decodeirq.c index d4faf0f89..c1acfffb9 100644 --- a/nuttx/configs/z80sim/src/z80_decodeirq.c +++ b/nuttx/configs/z80sim/src/z80_decodeirq.c @@ -1,5 +1,5 @@ /******************************************************************************** - * z80/z80_decodeirq.c + * board/z80_decodeirq.c * * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -38,12 +38,13 @@ ********************************************************************************/ #include + #include #include #include #include #include -#include "up_arch.h" + #include "os_internal.h" #include "up_internal.h" @@ -64,56 +65,37 @@ ********************************************************************************/ /******************************************************************************** - * Public Funtions + * Public Functions ********************************************************************************/ -void up_decodeirq(uint16* regs) +FAR chipreg_t *up_decodeirq(FAR chipreg_t *regs) { #ifdef CONFIG_SUPPRESS_INTERRUPTS + lib_lowprintf("Unexpected IRQ\n"); current_regs = regs; PANIC(OSERR_ERREXCEPTION); -#else - /* Decode the interrupt. First, fetch the interrupt id register. */ - - uint16 irqentry = getreg16(DM320_INTC_IRQENTRY0); - - /* The irqentry value is an offset into a table. Zero means no interrupt. */ + return NULL; /* Won't get here */ - if (irqentry != 0) - { - /* If non-zero, then we can map the table offset into an IRQ number */ - - int irq = (irqentry >> 2) - 1; - - /* Verify that the resulting IRQ number is valie */ - - if ((unsigned)irq < NR_IRQS) - { - /* Mask and acknowledge the interrupt */ - - up_maskack_irq(irq); +#else - /* Current regs non-zero indicates that we are processing an interrupt; - * current_regs is also used to manage interrupt level context switches. - */ + /* Current regs non-zero indicates that we are processing an interrupt; + * current_regs is also used to manage interrupt level context switches. + */ - current_regs = regs; + current_regs = regs; - /* Deliver the IRQ */ + /* Deliver the IRQ -- the simulation supports only timer interrupts */ - irq_dispatch(irq, regs); + irq_dispatch(Z80_IRQ_SYSTIMER, regs); - /* Indicate that we are no long in an interrupt handler */ + /* If a context switch occurred, current_regs will hold the new context */ - current_regs = NULL; + regs = current_regs; - /* Unmask the last interrupt (global interrupts are still - * disabled. - */ + /* Indicate that we are no long in an interrupt handler */ - up_enable_irq(irq); - } - } + current_regs = NULL; + return regs; #endif } diff --git a/nuttx/configs/z80sim/src/z80_irq.c b/nuttx/configs/z80sim/src/z80_irq.c index 3c3443663..b6e81b32e 100644 --- a/nuttx/configs/z80sim/src/z80_irq.c +++ b/nuttx/configs/z80sim/src/z80_irq.c @@ -1,7 +1,7 @@ /**************************************************************************** - * z80/z80_irq.c + * board/z80_irq.c * - * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -14,7 +14,7 @@ * 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 + * 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. * @@ -38,8 +38,10 @@ ****************************************************************************/ #include + #include #include + #include "up_arch.h" #include "os_internal.h" #include "up_internal.h" @@ -52,8 +54,6 @@ * Public Data ****************************************************************************/ -uint32 *current_regs; - /**************************************************************************** * Private Data ****************************************************************************/ @@ -63,7 +63,7 @@ uint32 *current_regs; ****************************************************************************/ /**************************************************************************** - * Public Funtions + * Public Functions ****************************************************************************/ /**************************************************************************** diff --git a/nuttx/configs/z80sim/src/z80_lowputc.c b/nuttx/configs/z80sim/src/z80_lowputc.c new file mode 100644 index 000000000..1c8abb2a4 --- /dev/null +++ b/nuttx/configs/z80sim/src/z80_lowputc.c @@ -0,0 +1,101 @@ +/******************************************************************************** + * board/z80_lowputc.c + * + * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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. + * + ********************************************************************************/ + +/******************************************************************************** + * Included Files + ********************************************************************************/ + +#include +#include +#include +#include +#include +#include +#include "up_arch.h" +#include "os_internal.h" +#include "up_internal.h" + +/******************************************************************************** + * Definitions + ********************************************************************************/ + +/******************************************************************************** + * Public Data + ********************************************************************************/ + +/******************************************************************************** + * Private Data + ********************************************************************************/ + +/******************************************************************************** + * Private Functions + ********************************************************************************/ + +/******************************************************************************** + * Public Functions + ********************************************************************************/ + +/******************************************************************************** + * Name: up_lowputc + * + * Data sent to port 0xbe are echoed on stdout by the simulation + * + ********************************************************************************/ + +void up_lowputc(char ch) __naked +{ + _asm + ld a, #2(sp) + out #0xbe, a + ret + _endasm; +} + +/******************************************************************************** + * Name: up_lowgetc + * + * Data from stdin can be received on port 0xbe in the simulation + * + ********************************************************************************/ + +char up_lowgetc(void) __naked +{ + _asm + in #0xbe, a + ld l, a + ld h, #0 + ret + _endasm; +} diff --git a/nuttx/configs/z80sim/src/z80_serial.c b/nuttx/configs/z80sim/src/z80_serial.c index 73bba4932..dbca1b78e 100644 --- a/nuttx/configs/z80sim/src/z80_serial.c +++ b/nuttx/configs/z80sim/src/z80_serial.c @@ -1,5 +1,5 @@ /**************************************************************************** - * z80/z80_serial.c + * board/z80_serial.c * * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -41,7 +41,6 @@ #include #include -#include #include #include #include @@ -282,7 +281,7 @@ static boolean up_txfifoempty(struct uart_dev_s *dev) } /**************************************************************************** - * Public Funtions + * Public Functions ****************************************************************************/ /**************************************************************************** diff --git a/nuttx/configs/z80sim/src/z80_timerisr.c b/nuttx/configs/z80sim/src/z80_timerisr.c index 603a66c91..e56678d13 100644 --- a/nuttx/configs/z80sim/src/z80_timerisr.c +++ b/nuttx/configs/z80sim/src/z80_timerisr.c @@ -1,7 +1,7 @@ -/************************************************************ - * dm320/dm320_timerisr.c +/**************************************************************************** + * board/z80_timerisr.c * - * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -14,7 +14,7 @@ * 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 + * 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. * @@ -31,89 +31,48 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * - ************************************************************/ + ****************************************************************************/ -/************************************************************ +/**************************************************************************** * Included Files - ************************************************************/ + ****************************************************************************/ #include + #include #include + #include + #include "clock_internal.h" #include "up_internal.h" -#include "up_arch.h" -/************************************************************ +/**************************************************************************** * Definitions - ************************************************************/ + ****************************************************************************/ -/* DM320 Timers - * - * Each of the general-purpose timers can run in one of two modes: one- - * shot mode and free-run mode. In one-shot mode, an interrupt only - * occurs once and then the timer must be explicitly reset to begin the - * timing operation again. In free-run mode, when the timer generates an - * interrupt, the timer counter is automatically reloaded to start the count - * operation again. Use the bit field MODE in TMMDx to configure the - * timer for one-shot more or free-run mode. The bit field MODE in TMMDx - * also allows you to stop the timer. - * - * Either the ARM clock divided by 2 (CLK_ARM/2) or an external clock - * connected to the M27XI pin can be selected as the clock source of the - * timer. - * - * The actual clock frequency used in the timer count operation is the input - * clock divided by: 1 plus the value set in the bit field PRSCL of the - * register TMPRSCLx (10 bits). The timer expires when it reaches the - * value set in the bit field DIV of the register TMDIVx (16 bits) plus 1. - * PRSCL+1 is the source clock frequency divide factor and DIV+1 is the - * timer count value. The frequency of a timer interrupt is given by the - * following equation: - * - * Interrupt Frequency = (Source Clock Frequency) / (PRSCL+1) / (DIV+1) - */ - -/* System Timer - * - * Timer0 is dedicated as the system timer. The rate of system timer - * interrupts is assumed to to 10MS per tick / 100Hz. The following - * register settings are used for timer 0 - * - * System clock formula: - * Interrupt Frequency = (Source Clock Frequency) / (PRSCL+1) / (DIV+1) - * Source Clock Frequency = 27MHz (PLL clock) - * DIV = 26,999 (Yields 1Khz timer clock) - * PRSCL = 9 (Produces 100Hz interrupts) - */ - -#define DM320_TMR0_MODE DM320_TMR_MODE_FREERUN /* Free running */ -#define DM320_TMR0_DIV 26999 /* (see above) */ -#define DM320_TMR0_PRSCL 9 /* (see above) */ - -/************************************************************ +/**************************************************************************** * Private Types - ************************************************************/ + ****************************************************************************/ -/************************************************************ +/**************************************************************************** * Private Function Prototypes - ************************************************************/ + ****************************************************************************/ -/************************************************************ +/**************************************************************************** * Global Functions - ************************************************************/ + ****************************************************************************/ -/************************************************************ +/**************************************************************************** * Function: up_timerisr * * Description: - * The timer ISR will perform a variety of services for - * various portions of the systems. + * The timer ISR will perform a variety of services for various portions of + * the system. * - ************************************************************/ + ****************************************************************************/ -int up_timerisr(int irq, uint32 *regs) +int up_timerisr(int irq, FAR chipreg_t *regs) { /* Process timer interrupt */ @@ -121,33 +80,16 @@ int up_timerisr(int irq, uint32 *regs) return 0; } -/************************************************************ +/**************************************************************************** * Function: up_timerinit * * Description: - * This function is called during start-up to initialize - * the timer interrupt. + * This function is called during start-up to initialize the timer + * interrupt. * - ************************************************************/ + ****************************************************************************/ void up_timerinit(void) { - up_disable_irq(DM320_IRQ_SYSTIMER); - - /* Start timer0 running so that an interrupt is generated at - * the rate MSEC_PER_TICK. - */ - - putreg16(DM320_TMR0_PRSCL, DM320_TIMER0_TMPRSCL); /* Timer 0 Prescalar */ - putreg16(DM320_TMR0_DIV, DM320_TIMER0_TMDIV); /* Timer 0 Divisor (count) */ - - /* Start the timer */ - - putreg16(DM320_TMR0_MODE, DM320_TIMER0_TMMD); /* Timer 0 Mode */ - - /* Attach and enable the timer interrupt */ - - irq_attach(DM320_IRQ_SYSTIMER, (xcpt_t)up_timerisr); - up_enable_irq(DM320_IRQ_SYSTIMER); } -- cgit v1.2.3