From 4915733091314a804c5d8884f04905a3dcc80c2d Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 1 Nov 2008 16:12:09 +0000 Subject: Added ST71x system timer logic git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1115 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/include/str71x/irq.h | 4 +- nuttx/arch/arm/src/str71x/str71x_head.S | 41 +---- nuttx/arch/arm/src/str71x/str71x_timer.h | 1 + nuttx/arch/arm/src/str71x/str71x_timerisr.c | 217 ++++++++++++++++++++++++++ nuttx/configs/olimex-strp711/ostest/defconfig | 2 +- nuttx/configs/olimex-strp711/src/up_buttons.c | 6 +- nuttx/configs/olimex-strp711/src/up_leds.c | 8 +- 7 files changed, 235 insertions(+), 44 deletions(-) create mode 100644 nuttx/arch/arm/src/str71x/str71x_timerisr.c diff --git a/nuttx/arch/arm/include/str71x/irq.h b/nuttx/arch/arm/include/str71x/irq.h index f598b7f95..d68b3779f 100644 --- a/nuttx/arch/arm/include/str71x/irq.h +++ b/nuttx/arch/arm/include/str71x/irq.h @@ -81,7 +81,7 @@ #define STR71X_IRQ_T0OC1 (30) #define STR71X_IRQ_T0OC2 (31) -#define LPC214X_IRQ_SYSTIMER STR71X_IRQ_T0TIMI +#define STR71X_IRQ_SYSTIMER STR71X_IRQ_T0TIMI #define NR_IRQS 32 /* FIQ channels */ @@ -118,5 +118,5 @@ EXTERN int up_irqpriority(int irq, ubyte priority); /* Set interrupt priority (0 #endif #endif -#endif /* __ARCH_LPC214X_IRQ_H */ +#endif /* __ARCH_ARM_INCLUDE_STR71X_IRQ_H */ diff --git a/nuttx/arch/arm/src/str71x/str71x_head.S b/nuttx/arch/arm/src/str71x/str71x_head.S index bbb3df34a..9965f8c69 100644 --- a/nuttx/arch/arm/src/str71x/str71x_head.S +++ b/nuttx/arch/arm/src/str71x/str71x_head.S @@ -49,38 +49,11 @@ *****************************************************************************/ /* This file holds the NuttX start logic that runs when the STR711 - * is reset. This logic must be located at address 0x0000:0000 in - * flash but may be linked to run at different locations based on - * the selected mode: - * - * default: Executes from 0x0000:0000. In non-default modes, the - * MEMAP register is set override the settings of the CPU configuration - * pins. - * - * CONFIG_EXTMEM_MODE: Code executes from external memory starting at - * address 0x6000:0000. - * - * CONFIG_RAM_MODE: Code executes from on-chip RAM at address - * 0x2000:0000. - * - * Starupt Code must be linked to run at the correct address - * corresponding to the selected mode. + * is reset. This logic must be located at address 0x4000:0000 in + * flash. It will also be mapped to address zero when the STR711 is + * reset. */ -#if defined(CONFIG_EXTMEM_MODE) -# if CONFIG_CODE_BASE != STR71X_EXTMEM_BASE -# error "CONFIG_CODE_BASE must be 0x60000000 in EXTMEM mode" -# endif -#elif defined(CONFIG_RAM_MODE) -# if CONFIG_CODE_BASE != STR71X_ONCHIP_RAM_BASE -# error "CONFIG_CODE_BASE must be 0x20000000 in EXTMEM mode" -# endif -#else -# if CONFIG_CODE_BASE != STR71X_FLASH_BASE -# error "CONFIG_CODE_BASE must be 0x00000000 in default mode" -# endif -#endif - /***************************************************************************** * External references *****************************************************************************/ @@ -331,7 +304,7 @@ /* Zero IVR 31:16 */ - str \value, [\eicbase, STR71X_EIC_IVR_OFFSET] + str \value, [\eicbase, #STR71X_EIC_IVR_OFFSET] /* Set up the loop to initialize each SIR register. Start * with IRQ number 0 and SIR0 @@ -435,9 +408,9 @@ eicloop: * * Description: * Interrrupt vector table. This must be located at the beginning - * of the memory space (at CONFIG_CODE_BASE). The first entry in - * the vector table is the reset vector and this is the code that - * will execute whn the processor is reset. + * of the memory space (at the beginning FLASH which will be mapped to + * address 0x00000000). The first entry in the vector table is the reset + * vector and this is the code that will execute whn the processor is reset. * *****************************************************************************/ diff --git a/nuttx/arch/arm/src/str71x/str71x_timer.h b/nuttx/arch/arm/src/str71x/str71x_timer.h index 860316004..331c538de 100644 --- a/nuttx/arch/arm/src/str71x/str71x_timer.h +++ b/nuttx/arch/arm/src/str71x/str71x_timer.h @@ -125,6 +125,7 @@ #define STR71X_TIMERCR1_PWMI (0x4000) /* Bit 14: Pulse width modulation input */ #define STR71X_TIMERCR1_EN (0x8000) /* Bit 15: Timer count enable */ +#define STR71X_TIMERCR2_DIVMASK (0x00ff) /* Bits 0-7: Timer prescaler value */ #define STR71X_TIMERCR2_OCBIE (0x0800) /* Bit 11: Output capture B enable */ #define STR71X_TIMERCR2_ICBIE (0x1000) /* Bit 12: Input capture B enable */ #define STR71X_TIMERCR2_TOIE (0x2000) /* Bit 13: Timer overflow enable */ diff --git a/nuttx/arch/arm/src/str71x/str71x_timerisr.c b/nuttx/arch/arm/src/str71x/str71x_timerisr.c new file mode 100644 index 000000000..1e6f6215a --- /dev/null +++ b/nuttx/arch/arm/src/str71x/str71x_timerisr.c @@ -0,0 +1,217 @@ +/**************************************************************************** + * arch/arm/src/str71x/str71x_timerisr.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 "clock_internal.h" +#include "up_internal.h" +#include "up_arch.h" + +#include "chip.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* Calculate the value of PCLK2 from settings in board.h. + * + * Example: + * STR71X_RCCU_MAIN_OSC = 4MHz + * CLK2 = 4MHz (not divided by 2) + * PLL1OUT = 16 * CLK2 / 2 = 32MHz + * CLK3 = 32MHz + * RCLK = 32MHz + * PCLK2 = 32MHz / 1 = 32MHz + */ + +#ifdef STR71X_PLL1IN_DIV2 /* Input may be divided by 2 */ +# define CLK2 (STR71X_RCCU_MAIN_OSC/2) /* CLK2 is input to PLL1 */ +#else +# define CLK2 STR71X_RCCU_MAIN_OSC /* CLK2 is input to PLL1 */ +#endif + /* PLL1OUT derives from CLK2 */ +#define PLL1OUT (STR71X_PLL1OUT_MUL * CLK2 / STR71X_PLL1OUT_DIV) +#define CLK3 PLL1OUT /* CLK3 hard coded to be PLL1OUT */ +#define RCLK CLK3 /* RCLK hard coded to be CLK3 */ +#define PCLK2 (RCLK / STR71X_APB2_DIV) /* PCLK2 derives from RCLK */ + +/* The desired timer interrupt frequency is provided by the definition + * CLK_TCK (see include/time.h). CLK_TCK defines the desired number of + * system clock ticks per second. That value is a user configurable setting + * that defaults to 100 (100 ticks per second = 10 MS interval). + * + * The best accuracy would be obtained by using the largest value in the + * the output compare register (OCAR), i.e., 0xffff = 65,535: + */ + +#define MAX_OCAR 65535 + + /* In this case, the desired, maximum clocking would be MAX_TIM0CLK. For + * example if CLK_TCK is the default of 100Hz, then the ideal clocking for + * timer0 would be 6,553,500 */ + +#define MAX_TIM0CLK (MAX_OCAR * CLK_TCK) + + /* The best divider then would be the one that reduces PCLK2 to MAX_TIM0CLK. + * Note that the following calculation forces an integer divisor to the next + * integer above the optimal. So, for example, if MAX_TIM0CLK is 6,553,500 + * and PCLK2 is 32MHz, then ideal PCLK2_DIVIDER would be 4.88 but 5 is used + * instead. The value 5 would give an actual TIM0CLK of 6,400,000, less + * than the maximum. + */ + +#if PCLK2 > MAX_TIM0CLK +# define PCLK2_DIVIDER (((PCLK2) + (MAX_TIM0CLK+1)) / MAX_TIM0CLK) +#else +# define PCLK2_DIVIDER (1) +#endif + +#if PCLK2_DIVIDER > 255 +# error "PCLK2 is too fast for any divisor" +#endif + + /* Then we can get the actual OCAR value from the selected divider value. + * For example, if PCLK2 is 32MHz and PCLK2_DIVIDER is 5, then the actual + * TIM0CLK would 6,4000,000 and the final OCAR_VALUE would be 64,000. + */ + +#define ACTUAL_TIM0CLK (PCLK2 / PCLK2_DIVIDER) +#define OCAR_VALUE (ACTUAL_TIM0CLK / CLK_TCK) + +#if OCAR_VALUE > 65535 +# error "PCLK2 is too fast for the configured CLK_TCK" +#endif + +/**************************************************************************** + * 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, uint32 *regs) +{ + /* 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) +{ + uint16 cr1; + uint16 cr2; + + /* Make sure that timer0 is disabled */ + + putreg16(0x0000, STR71X_TIMER0_CR1); + putreg16(0x0000, STR71X_TIMER0_CR2); + putreg16(0x0000, STR71X_TIMER0_SR); + + /* Start The TIM0 Counter */ + + cr1 = STR71X_TIMERCR1_EN; + putreg16(cr1, STR71X_TIMER0_CR1); + + /* Configure TIM0 so that it is clocked by the internal APB2 frequency (PCLK2) + * divided by the above prescaler value (1) -- versus an external Clock. + * -- Nothing to do because STR71X_TIMERCR1_ECKEN is already cleared. + * + * + * Select a divisor to reduce the frequency of clocking. This must be + * done so that the entire timer interval can fit in the 16-bit OCAR register. + * (see the discussion above). + */ + + cr2 = PCLK2_DIVIDER; + putreg16(cr2, STR71X_TIMER0_CR2); + + /* Setup output compare A for desired interrupt frequency. Note that + * the OCAE and OCBE bits are cleared and the pins are available for other + * functions. + */ + + putreg16(OCAR_VALUE, STR71X_TIMER0_OCAR); + putreg16(0, STR71X_TIMER0_CNTR); + + /* Enable TIM0 Output Compare A interrupt */ + + cr2 |= STR71X_TIMERCR2_OCAIE; + putreg16(cr2, STR71X_TIMER0_CR2); + + /* Set the IRQ interrupt priority */ + + up_irqpriority(STR71X_IRQ_SYSTIMER, 1); + + /* Attach the timer interrupt vector */ + + (void)irq_attach(STR71X_IRQ_SYSTIMER, (xcpt_t)up_timerisr); + + /* And enable the timer interrupt */ + + up_enable_irq(STR71X_IRQ_SYSTIMER); +} diff --git a/nuttx/configs/olimex-strp711/ostest/defconfig b/nuttx/configs/olimex-strp711/ostest/defconfig index e310f54fe..1ff1ad1c0 100644 --- a/nuttx/configs/olimex-strp711/ostest/defconfig +++ b/nuttx/configs/olimex-strp711/ostest/defconfig @@ -108,7 +108,7 @@ CONFIG_STR71X_BSPI1=n CONFIG_STR71X_HDLC=n CONFIG_STR71X_XTI=n CONFIG_STR71X_GPIO0=y -CONFIG_STR71X_GPIO1=n +CONFIG_STR71X_GPIO1=y CONFIG_STR71X_GPIO2=n CONFIG_STR71X_ADC12=n CONFIG_STR71X_CKOUT=n diff --git a/nuttx/configs/olimex-strp711/src/up_buttons.c b/nuttx/configs/olimex-strp711/src/up_buttons.c index 2ee386daa..108a5831c 100644 --- a/nuttx/configs/olimex-strp711/src/up_buttons.c +++ b/nuttx/configs/olimex-strp711/src/up_buttons.c @@ -82,15 +82,15 @@ void up_buttoninit(void) /* Configure the GPIO pins as inputs */ reg16 = getreg16(STR71X_GPIO1_PC0); - reg16 |= STR71X_BOTHBUTTONS_GPIO1 + reg16 |= STR71X_BOTHBUTTONS_GPIO1; putreg16(reg16, STR71X_GPIO1_PC0); reg16 = getreg16(STR71X_GPIO1_PC1); - reg16 &= ~STR71X_BOTHBUTTONS_GPIO1 + reg16 &= ~STR71X_BOTHBUTTONS_GPIO1; putreg16(reg16, STR71X_GPIO1_PC1); reg16 = getreg16(STR71X_GPIO1_PC2); - reg16 &= ~STR71X_BOTHBUTTONS_GPIO1 + reg16 &= ~STR71X_BOTHBUTTONS_GPIO1; putreg16(reg16, STR71X_GPIO1_PC2); } diff --git a/nuttx/configs/olimex-strp711/src/up_leds.c b/nuttx/configs/olimex-strp711/src/up_leds.c index 873994c68..a5719d5f9 100644 --- a/nuttx/configs/olimex-strp711/src/up_leds.c +++ b/nuttx/configs/olimex-strp711/src/up_leds.c @@ -106,21 +106,21 @@ void up_ledinit(void) /* Set normal function output */ reg16 = getreg16(STR71X_GPIO1_PC0); - reg16 |= STR71X_LEDGPIO1_BITS + reg16 |= STR71X_LEDGPIO1_BITS; putreg16(reg16, STR71X_GPIO1_PC0); reg16 = getreg16(STR71X_GPIO1_PC1); - reg16 &= ~STR71X_LEDGPIO1_BITS + reg16 &= ~STR71X_LEDGPIO1_BITS; putreg16(reg16, STR71X_GPIO1_PC1); reg16 = getreg16(STR71X_GPIO1_PC2); - reg16 |= STR71X_LEDGPIO1_BITS + reg16 |= STR71X_LEDGPIO1_BITS; putreg16(reg16, STR71X_GPIO1_PC2); /* Clear the LEDs (1 clears; 0 sets) */ reg16 = getreg16(STR71X_GPIO1_PD); - reg16 |= STR71X_LEDGPIO1_BITS + reg16 |= STR71X_LEDGPIO1_BITS; putreg16(reg16, STR71X_GPIO1_PD); } -- cgit v1.2.3