From 37e7ef6f42e3d8b27a78a6e96c8b147a8578a0c0 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 15 Dec 2012 15:03:35 +0000 Subject: Add z180 system timer git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5438 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/z80/src/z180/Kconfig | 5 +- nuttx/arch/z80/src/z180/Make.defs | 1 + nuttx/arch/z80/src/z180/z180_config.h | 88 ++++++++++++++++-- nuttx/arch/z80/src/z180/z180_iomap.h | 38 ++++---- nuttx/arch/z80/src/z180/z180_lowscc.c | 39 +------- nuttx/arch/z80/src/z180/z180_lowuart.c | 35 +------ nuttx/arch/z80/src/z180/z180_serial.h | 10 +- nuttx/arch/z80/src/z180/z180_timerisr.c | 157 ++++++++++++++++++++++++++++++++ 8 files changed, 277 insertions(+), 96 deletions(-) create mode 100644 nuttx/arch/z80/src/z180/z180_timerisr.c (limited to 'nuttx/arch/z80/src/z180') diff --git a/nuttx/arch/z80/src/z180/Kconfig b/nuttx/arch/z80/src/z180/Kconfig index 34297f7a7..160c66b50 100644 --- a/nuttx/arch/z80/src/z180/Kconfig +++ b/nuttx/arch/z80/src/z180/Kconfig @@ -175,11 +175,12 @@ config Z180_ESCCB ---help--- Select to enable a serial port on ESCC Channel B -config Z180_TMR1 +config Z180_PRT1 bool "Timer 1" default n ---help--- - Select to enable a Timer 1 (Timer 0 is used by NuttX as the system timer) + Select to enable a Programmable Reload Timer 1 (PRT1, PRT0 is used + by NuttX as the system timer) # config Z180_DMA0 # bool "DMA0" diff --git a/nuttx/arch/z80/src/z180/Make.defs b/nuttx/arch/z80/src/z180/Make.defs index 7b495e693..24d2cb64a 100644 --- a/nuttx/arch/z80/src/z180/Make.defs +++ b/nuttx/arch/z80/src/z180/Make.defs @@ -60,3 +60,4 @@ endif CHIP_CSRCS = z180_copystate.c z180_initialstate.c z180_io.c z180_irq.c CHIP_CSRCS += z180_lowscc.c z180_lowserial.c z180_modifiyreg8.c z180_mmu.c CHIP_CSRCS += z180_registerdump.c z180_schedulesigaction.c z180_sigdeliver.c +CHIP_CSRCS += z180_timerisr.c diff --git a/nuttx/arch/z80/src/z180/z180_config.h b/nuttx/arch/z80/src/z180/z180_config.h index 65815c21b..556973a75 100644 --- a/nuttx/arch/z80/src/z180/z180_config.h +++ b/nuttx/arch/z80/src/z180/z180_config.h @@ -44,6 +44,8 @@ #include +#include "up_internal.h" + /************************************************************************************ * Pre-processor Definitions ************************************************************************************/ @@ -103,7 +105,7 @@ # undef CONFIG_Z180_ESCCA_SERIAL_CONSOLE #endif -#ifndef CONFIG_Z180_ESCCA +#ifndef CONFIG_Z180_ESCCB # undef CONFIG_Z180_ESCCB_SERIAL_CONSOLE #endif @@ -114,34 +116,106 @@ #undef HAVE_SERIAL_CONSOLE #if defined(CONFIG_Z180_UART0_SERIAL_CONSOLE) +# define HAVE_UART_CONSOLE 1 +# define HAVE_SERIAL_CONSOLE 1 + + /* Disable other console selections */ + # undef CONFIG_Z180_UART1_SERIAL_CONSOLE # undef CONFIG_Z180_SCC_SERIAL_CONSOLE # undef CONFIG_Z180_ESCCA_SERIAL_CONSOLE # undef CONFIG_Z180_ESCCB_SERIAL_CONSOLE + + /* If we are not using the serial driver, then the serial console is all + * that we will support. + */ + +# ifndef USE_SERIALDRIVER +# undef CONFIG_Z180_UART1 +# undef CONFIG_Z180_SCC +# undef CONFIG_Z180_ESCCA +# undef CONFIG_Z180_ESCCB +# endif + +#elif defined(CONFIG_Z180_UART1_SERIAL_CONSOLE) # define HAVE_UART_CONSOLE 1 # define HAVE_SERIAL_CONSOLE 1 -#elif defined(CONFIG_Z180_UART1_SERIAL_CONSOLE) + /* Disable other console selections */ + # undef CONFIG_Z180_SCC_SERIAL_CONSOLE # undef CONFIG_Z180_ESCCA_SERIAL_CONSOLE # undef CONFIG_Z180_ESCCB_SERIAL_CONSOLE -# define HAVE_UART_CONSOLE 1 + + /* If we are not using the serial driver, then the serial console is all + * that we will support. + */ + +# ifndef USE_SERIALDRIVER +# undef CONFIG_Z180_UART0 +# undef CONFIG_Z180_SCC +# undef CONFIG_Z180_ESCCA +# undef CONFIG_Z180_ESCCB +# endif + +#elif defined(CONFIG_Z180_SCC_SERIAL_CONSOLE) +# define HAVE_SCC_CONSOLE 1 # define HAVE_SERIAL_CONSOLE 1 -#elif defined(CONFIG_Z180_ESCC_SERIAL_CONSOLE) + /* Disable other console selections */ + # undef CONFIG_Z180_ESCCA_SERIAL_CONSOLE # undef CONFIG_Z180_ESCCB_SERIAL_CONSOLE -# define HAVE_SCC_CONSOLE 1 -# define HAVE_SERIAL_CONSOLE 1 + + /* If we are not using the serial driver, then the serial console is all + * that we will support. + */ + +# ifndef USE_SERIALDRIVER +# undef CONFIG_Z180_UART0 +# undef CONFIG_Z180_UART1 +# undef CONFIG_Z180_ESCCA +# undef CONFIG_Z180_ESCCB +# endif #elif defined(CONFIG_Z180_ESCCA_SERIAL_CONSOLE) -# undef CONFIG_Z180_ESCCB_SERIAL_CONSOLE # define HAVE_SCC_CONSOLE 1 # define HAVE_SERIAL_CONSOLE 1 + /* Disable other console selections */ + +# undef CONFIG_Z180_ESCCB_SERIAL_CONSOLE + + /* If we are not using the serial driver, then the serial console is all + * that we will support. + */ + +# ifndef USE_SERIALDRIVER +# undef CONFIG_Z180_UART0 +# undef CONFIG_Z180_UART1 +# undef CONFIG_Z180_SCC +# undef CONFIG_Z180_ESCCB +# endif + + /* If we are not using the serial driver, then the serial console is all + * that we will support. + */ + #elif defined(CONFIG_Z180_ESCCB_SERIAL_CONSOLE) # define HAVE_SCC_CONSOLE 1 # define HAVE_SERIAL_CONSOLE 1 + + /* If we are not using the serial driver, then the serial console is all + * that we will support. + */ + +# ifndef USE_SERIALDRIVER +# undef CONFIG_Z180_UART0 +# undef CONFIG_Z180_UART1 +# undef CONFIG_Z180_SCC +# undef CONFIG_Z180_ESCCA +# endif + #endif /************************************************************************************ diff --git a/nuttx/arch/z80/src/z180/z180_iomap.h b/nuttx/arch/z80/src/z180/z180_iomap.h index 8717ae814..f2e9d5915 100644 --- a/nuttx/arch/z80/src/z180/z180_iomap.h +++ b/nuttx/arch/z80/src/z180/z180_iomap.h @@ -89,18 +89,18 @@ #define Z180_CSIO_CNTR (SFR_OFFSET+0x0a) /* CSI/O Control Register */ #define Z180_CSIO_TRD (SFR_OFFSET+0x0b) /* Transmit/Receive Data Register */ -/* Timer Registers */ +/* Programmable Reload Timer (PTR) Registers */ -#define Z180_TMR0_DRL (SFR_OFFSET+0x0c) /* Timer Data Register Ch 0 L */ -#define Z180_TMR0_DRH (SFR_OFFSET+0x0d) /* Data Register Ch 0 H */ -#define Z180_TMR0_RLDRL (SFR_OFFSET+0x0e) /* Reload Register Ch 0 L */ -#define Z180_TMR0_RLDRH (SFR_OFFSET+0x0f) /* Reload Register Ch 0 H */ -#define Z180_TMR_TCR (SFR_OFFSET+0x10) /* Timer Control Register */ +#define Z180_PRT0_DRL (SFR_OFFSET+0x0c) /* Timer Data Register Ch 0 L */ +#define Z180_PRT0_DRH (SFR_OFFSET+0x0d) /* Data Register Ch 0 H */ +#define Z180_PRT0_RLDRL (SFR_OFFSET+0x0e) /* Reload Register Ch 0 L */ +#define Z180_PRT0_RLDRH (SFR_OFFSET+0x0f) /* Reload Register Ch 0 H */ +#define Z180_PRT_TCR (SFR_OFFSET+0x10) /* Timer Control Register */ -#define Z180_TMR1_DRL (SFR_OFFSET+0x14) /* Data Register Ch 1 L */ -#define Z180_TMR1_DRH (SFR_OFFSET+0x15) /* Data Register Ch 1 H */ -#define Z180_TMR1_RLDRL (SFR_OFFSET+0x16) /* Reload Register Ch 1 L */ -#define Z180_TMR1_RLDRH (SFR_OFFSET+0x17) /* Reload Register Ch 1 H */ +#define Z180_PRT1_DRL (SFR_OFFSET+0x14) /* Data Register Ch 1 L */ +#define Z180_PRT1_DRH (SFR_OFFSET+0x15) /* Data Register Ch 1 H */ +#define Z180_PRT1_RLDRL (SFR_OFFSET+0x16) /* Reload Register Ch 1 L */ +#define Z180_PRT1_RLDRH (SFR_OFFSET+0x17) /* Reload Register Ch 1 H */ #define Z180_FRC (SFR_OFFSET+0x18) /* Free Running Counter */ @@ -398,16 +398,16 @@ /* Timer Reload Register Channel 0L (RLDR0L: 0x0e) -- 8-bit data */ /* Timer Reload Register Channel 0H (RLDR0H: 0x0f) -- 8-bit data */ -/* Timer Control Register (TCR: 0x10) */ +/* Programmable Reload Timer (PTR) Control Register (TCR: 0x10) */ -#define TMR_TCR_TIF1 (0x80) /* Bit 7: Timer 1 Interrupt Flag */ -#define TMR_TCR_TIF0 (0x40) /* Bit 6: Timer 0 Interrupt Flag */ -#define TMR_TCR_TIE1 (0x20) /* Bit 5: Timer 1 Interrupt Enable */ -#define TMR_TCR_TIE0 (0x10) /* Bit 4: Timer 0 Interrupt Enable */ -#define TMR_TCR_TOC1 (0x08) /* Bit 3: Timer 1 Output Control */ -#define TMR_TCR_TOC0 (0x04) /* Bit 2: Timer 0 Output Control */ -#define TMR_TCR_TDE1 (0x02) /* Bit 1: Timer 1 Down Count Enable */ -#define TMR_TCR_TDE0 (0x01) /* Bit 0: Timer 0 Down Count Enable */ +#define PRT_TCR_TIF1 (0x80) /* Bit 7: Timer 1 Interrupt Flag */ +#define PRT_TCR_TIF0 (0x40) /* Bit 6: Timer 0 Interrupt Flag */ +#define PRT_TCR_TIE1 (0x20) /* Bit 5: Timer 1 Interrupt Enable */ +#define PRT_TCR_TIE0 (0x10) /* Bit 4: Timer 0 Interrupt Enable */ +#define PRT_TCR_TOC1 (0x08) /* Bit 3: Timer 1 Output Control */ +#define PRT_TCR_TOC0 (0x04) /* Bit 2: Timer 0 Output Control */ +#define PRT_TCR_TDE1 (0x02) /* Bit 1: Timer 1 Down Count Enable */ +#define PRT_TCR_TDE0 (0x01) /* Bit 0: Timer 0 Down Count Enable */ /* Timer Data Register 1L (TMDR1L: 0x14) -- 8-bit data */ /* Timer Data Register 1H (TMDR1H: 0x15) -- 8-bit data */ diff --git a/nuttx/arch/z80/src/z180/z180_lowscc.c b/nuttx/arch/z80/src/z180/z180_lowscc.c index e5d5171c1..f729355c6 100644 --- a/nuttx/arch/z80/src/z180/z180_lowscc.c +++ b/nuttx/arch/z80/src/z180/z180_lowscc.c @@ -90,20 +90,6 @@ * Private Functions ****************************************************************************/ -/**************************************************************************** - * Name: z180_scc_setbaud - * - * Description: - * - ****************************************************************************/ - -#if defined(HAVE_SCC_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG) -static void z180_scc_setbaud(void) -{ -#warning "Missing logic" -} -#endif /* HAVE_SCC_CONSOLE && !CONFIG_SUPPRESS_UART_CONFIG */ - /**************************************************************************** * Public Functions ****************************************************************************/ @@ -112,34 +98,19 @@ static void z180_scc_setbaud(void) * Name: z180_scc_lowinit * * Description: - * Called early in the boot sequence to initialize the [E]SCC channel(s) + * Called early in the boot sequence to initialize the [E]SCC console + * channel (only). * ****************************************************************************/ +#ifdef USE_LOWSERIALINIT void z180_scc_lowinit(void) { -#warning "Missing logic" - - /* Configure for usage of {E]SCC channels (whether or not we have a console) */ - -#ifdef CONFIG_Z180_SCC -#warning "Missing logic" -#endif - -#ifdef CONFIG_Z180_ESCCA -#warning "Missing logic" -#endif - -#ifdef CONFIG_Z180_ESCCB +#ifdef HAVE_SCC_CONSOLE #warning "Missing logic" #endif - - /* Configure the console for immediate usage */ - -#if defined(HAVE_SCC_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG) -#warning "Missing logic" -#endif /* HAVE_SCC_CONSOLE && !CONFIG_SUPPRESS_UART_CONFIG */ } +#endif /**************************************************************************** * Name: z180_putc diff --git a/nuttx/arch/z80/src/z180/z180_lowuart.c b/nuttx/arch/z80/src/z180/z180_lowuart.c index 493a793cd..308e01980 100644 --- a/nuttx/arch/z80/src/z180/z180_lowuart.c +++ b/nuttx/arch/z80/src/z180/z180_lowuart.c @@ -83,20 +83,6 @@ * Private Functions ****************************************************************************/ -/**************************************************************************** - * Name: z180_uart_setbaud - * - * Description: - * - ****************************************************************************/ - -#if defined(HAVE_UART_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG) -static void z180_uart_setbaud(void) -{ -#warning "Missing logic" -} -#endif /* HAVE_UART_CONSOLE && !CONFIG_SUPPRESS_UART_CONFIG */ - /**************************************************************************** * Public Functions ****************************************************************************/ @@ -105,30 +91,19 @@ static void z180_uart_setbaud(void) * Name: z180_uart_lowinit * * Description: - * Called early in the boot sequence to initialize the [E]SCC channel(s) + * Called early in the boot sequence to initialize the uart console + * channel (only). * ****************************************************************************/ +#ifdef USE_LOWSERIALINIT void z180_uart_lowinit(void) { -#warning "Missing logic" - - /* Configure for usage of {E]SCC channels (whether or not we have a console) */ - -#ifdef CONFIG_Z180_UART0 -#warning "Missing logic" -#endif - -#ifdef CONFIG_Z180_UART1 +#ifdef HAVE_UART_CONSOLE #warning "Missing logic" #endif - - /* Configure the console for immediate usage */ - -#if defined(HAVE_UART_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG) -#warning "Missing logic" -#endif /* HAVE_UART0_CONSOLE && !CONFIG_SUPPRESS_UART_CONFIG */ } +#endif /**************************************************************************** * Name: z180_putc diff --git a/nuttx/arch/z80/src/z180/z180_serial.h b/nuttx/arch/z80/src/z180/z180_serial.h index 31248eb51..0b0e12d79 100644 --- a/nuttx/arch/z80/src/z180/z180_serial.h +++ b/nuttx/arch/z80/src/z180/z180_serial.h @@ -57,11 +57,12 @@ * Name: z180_uart_lowinit * * Description: - * Called early in the boot sequence to initialize the UART(s) + * Called early in the boot sequence to initialize the uart console + * channel (only). * ****************************************************************************/ -#ifdef HAVE_UART +#if defined(HAVE_UART) && defined(USE_LOWSERIALINIT) void z180_uart_lowinit(void); #else # define z180_uart_lowinit() @@ -71,11 +72,12 @@ void z180_uart_lowinit(void); * Name: z180_scc_lowinit * * Description: - * Called early in the boot sequence to initialize the [E]SCC channel(s) + * Called early in the boot sequence to initialize the [E]SCC console + * channel (only). * ****************************************************************************/ -#ifdef HAVE_SCC +#if defined(HAVE_SCC) && defined(USE_LOWSERIALINIT) void z180_scc_lowinit(void); #else # define z180_scc_lowinit() diff --git a/nuttx/arch/z80/src/z180/z180_timerisr.c b/nuttx/arch/z80/src/z180/z180_timerisr.c new file mode 100644 index 000000000..ceb7efb5f --- /dev/null +++ b/nuttx/arch/z80/src/z180/z180_timerisr.c @@ -0,0 +1,157 @@ +/**************************************************************************** + * arch/z80/src/z180/z180_timerisr.c + * + * Copyright (C) 2012 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 "clock_internal.h" +#include "up_internal.h" + +#include "chip.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* "The Z180 contains a two channel 16-bit Programmable Reload Timer. Each + * PRT channel contains a 16-bit down counter and a 16-bit reload register." + * Channel 0 is dedicated as the system timer. + */ + +/* "The PRT input clock for both channels is equal to the system clock + * divided by 20." + */ + +#define Z180_PRT_CLOCK (Z180_SYSCLOCK / 20) + +/* The data Register "(TMDR) is decremented once every twenty clocks. When + * TMDR counts down to 0, it is automatically reloaded with the value + * contained in the Reload Register (RLDR)." + */ + +#define A180_PRT0_RELOAD (Z180_PRT_CLOCK / CLK_TCK) + +/**************************************************************************** + * 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. + * + ****************************************************************************/ + +int up_timerisr(int irq, chipreg_t *regs) +{ + volatile uint8_t regval; + + /* "When TMDR0 decrements to 0, TIF0 is set to 1. This generates an interrupt + * request if enabled by TIE0 = 1. TIF0 is reset to 0 when TCR is read and + * the higher or lower byte of TMDR0 is read." + */ + + regval = inp(Z180_PRT_TCR); + regval = inp(Z180_PRT0_DRL); + regval = inp(Z180_PRT0_DRH); + + /* Process timer interrupt */ + + sched_process_timer(); + return 0; +} + +/**************************************************************************** + * Function: up_timerinit + * + * Description: + * This function is called during start-up to initialize the timer + * interrupt. + * + ****************************************************************************/ + +void up_timerinit(void) +{ + uint8_t regval; + + /* Configure PRT0 to interrupt at the requested rate */ + /* First stop PRT0 and disable interrupts */ + + regval = inp(Z180_PRT_TCR); + regval &= (PRT_TCR_TIF0|PRT_TCR_TIE0|PRT_TCR_TDE0); + outp(Z180_PRT_TCR, regval); + + /* Set the timer reload value so that the timer will interrupt at the + * desired frequency. "For writing, the TMDR down counting must be + * inhibited using the TDE (Timer Down Count Enable) bits in the TCR + * (Timer Control Register). Then, any or both higher and lower bytes of + * TMDR can be freely written (and read) in any order." + */ + + outp(Z180_PRT0_RLDRL, (A180_PRT0_RELOAD & 0xff)); + outp(Z180_PRT0_RLDRH, (A180_PRT0_RELOAD >> 8)); + + /* Enable down-counting */ + + regval |= PRT_TCR_TDE0; + outp(Z180_PRT_TCR, regval); + + /* Attach the timer interrupt vector */ + + (void)irq_attach(Z180_PRT0, (xcpt_t)up_timerisr); + + /* And enable the timer interrupt */ + + regval |= PRT_TCR_TIE0; + outp(Z180_PRT_TCR, regval); +} -- cgit v1.2.3