From fa0e1e5d0b4bbbeb2af68e1517997dba6ef60ec9 Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 28 Sep 2009 19:14:37 +0000 Subject: Add RCC support git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2101 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/stm32/Make.defs | 5 +- nuttx/arch/arm/src/stm32/stm32_internal.h | 6 +- nuttx/arch/arm/src/stm32/stm32_rcc.c | 419 ++++++++++++++++++++++++++++ nuttx/arch/arm/src/stm32/stm32_rcc.h | 20 +- nuttx/arch/arm/src/stm32/stm32_timerisr.c | 8 +- nuttx/configs/stm3210e-eval/include/board.h | 40 ++- 6 files changed, 475 insertions(+), 23 deletions(-) create mode 100755 nuttx/arch/arm/src/stm32/stm32_rcc.c diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs index 1536d8619..391a93bc4 100755 --- a/nuttx/arch/arm/src/stm32/Make.defs +++ b/nuttx/arch/arm/src/stm32/Make.defs @@ -45,5 +45,6 @@ CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \ up_usestack.c up_doirq.c up_hardfault.c up_svcall.c CHIP_ASRCS = -CHIP_CSRCS = stm32_start.c stm32_irq.c stm32_timerisr.c stm32_lowputc.c stm32_serial.c -# stm32_gpio.c stm32_spi.c stm32_dumpgpio.c +CHIP_CSRCS = stm32_start.c stm32_rcc.c stm32_irq.c stm32_timerisr.c \ + stm32_lowputc.c stm32_serial.c + diff --git a/nuttx/arch/arm/src/stm32/stm32_internal.h b/nuttx/arch/arm/src/stm32/stm32_internal.h index 10e8da0d6..285e0ae20 100755 --- a/nuttx/arch/arm/src/stm32/stm32_internal.h +++ b/nuttx/arch/arm/src/stm32/stm32_internal.h @@ -146,13 +146,11 @@ EXTERN void up_lowsetup(void); * Name: stm32_clockconfig * * Description: - * Called to change to new clock based on desired rcc and rcc2 settings. - * This is use to set up the initial clocking but can be used later to - * support slow clocked, low power consumption modes. + * Called to change to new clock based on settings in board.h * ****************************************************************************/ -EXTERN void stm32_clockconfig(uint32 newrcc, uint32 newrcc2); +EXTERN void stm32_clockconfig(void); /**************************************************************************** * Name: up_clockconfig diff --git a/nuttx/arch/arm/src/stm32/stm32_rcc.c b/nuttx/arch/arm/src/stm32/stm32_rcc.c new file mode 100755 index 000000000..b9bb3c28b --- /dev/null +++ b/nuttx/arch/arm/src/stm32/stm32_rcc.c @@ -0,0 +1,419 @@ +/**************************************************************************** + * arch/arm/src/stm32/stm32_rcc.c + * + * Copyright (C) 2009 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 "up_internal.h" +#include "up_arch.h" + +#include "chip.h" +#include "stm32_rcc.h" +#include "stm32_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +#define HSERDY_TIMEOUT 256 + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* Put all RCC registers in reset state */ + +static inline void rcc_reset(void) +{ + uint32 regval; + + putreg32(0, STM32_RCC_APB2RSTR); /* Disable APB2 Peripheral Reset */ + putreg32(0, STM32_RCC_APB1RSTR); /* Disable APB1 Peripheral Reset */ + putreg32(RCC_AHBENR_FLITFEN|RCC_AHBENR_SRAMEN, STM32_RCC_AHBENR); /* FLITF and SRAM Clock ON */ + putreg32(0, STM32_RCC_APB2ENR); /* Disable APB2 Peripheral Clock */ + putreg32(0, STM32_RCC_APB1ENR); /* Disable APB1 Peripheral Clock */ + + regval = getreg32(STM32_RCC_CR); /* Set the HSION bit */ + regval |= RCC_CR_HSION; + putreg32(regval, STM32_RCC_CR); + + regval = getreg32(STM32_RCC_CFGR); /* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */ + regval &= ~(RCC_CFGR_SW_MASK|RCC_CFGR_HPRE_MASK|RCC_CFGR_PPRE1_MASK|RCC_CFGR_PPRE2_MASK|RCC_CFGR_ADCPRE_MASK|RCC_CFGR_MCO_MASK); + putreg32(regval, STM32_RCC_CFGR); + + regval = getreg32(STM32_RCC_CR); /* Reset HSEON, CSSON and PLLON bits */ + regval &= ~(RCC_CR_HSEON|RCC_CR_CSSON|RCC_CR_PLLON); + putreg32(regval, STM32_RCC_CR); + + regval = getreg32(STM32_RCC_CR); /* Reset HSEBYP bit */ + regval &= ~RCC_CR_HSEBYP; + putreg32(regval, STM32_RCC_CR); + + regval = getreg32(STM32_RCC_CFGR); /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */ + regval &= ~(RCC_CFGR_PLLSRC|RCC_CFGR_PLLXTPRE|RCC_CFGR_PLLMUL_MASK|RCC_CFGR_USBPRE); + putreg32(regval, STM32_RCC_CFGR); + + putreg32(0, STM32_RCC_CIR); /* Disable all interrupts */ +} + +static inline void rcc_enableapb1(void) +{ + uint32 regval; + + regval = getreg32(STM32_RCC_APB1ENR); +#if CONFIG_STM32_TIM2 + /* Timer 2 clock enable */ + + regval |= RCC_APB1ENR_TIM2EN; +#endif + +#if CONFIG_STM32_TIM3 + /* Timer 3 clock enable */ + + regval |= RCC_APB1ENR_TIM3EN; +#endif + +#if CONFIG_STM32_TIM4 + /* Timer 4 clock enable */ + + regval |= RCC_APB1ENR_TIM4EN; +#endif + +#if CONFIG_STM32_TIM5 + /* Timer 5 clock enable */ + + regval |= RCC_APB1ENR_TIM5EN; +#endif + +#if CONFIG_STM32_TIM6 + /* Timer 6 clock enable */ + + regval |= RCC_APB1ENR_TIM6EN; +#endif + +#if CONFIG_STM32_TIM7 + /* Timer 7 clock enable */ + + regval |= RCC_APB1ENR_TIM7EN; +#endif + +#if CONFIG_STM32_WWDG + /* Window Watchdog clock enable */ + + regval |= RCC_APB1ENR_WWDGEN; +#endif + +#if CONFIG_STM32_SPI2 + /* SPI 2 clock enable */ + + regval |= RCC_APB1ENR_SPI2EN; +#endif + +#if CONFIG_STM32_SPI4 + /* SPI 3 clock enable */ + + regval |= RCC_APB1ENR_SPI3EN; +#endif + +#if CONFIG_STM32_USART2 + /* USART 2 clock enable */ + + regval |= RCC_APB1ENR_USART2EN; +#endif + +#if CONFIG_STM32_USART3 + /* USART 3 clock enable */ + + regval |= RCC_APB1ENR_USART3EN; +#endif + +#if CONFIG_STM32_UART4 + /* UART 4 clock enable */ + + regval |= RCC_APB1ENR_UART4EN; +#endif + +#if CONFIG_STM32_UART5 + /* UART 5 clock enable */ + + regval |= RCC_APB1ENR_UART5EN; +#endif + +#if CONFIG_STM32_I2C1 + /* I2C 1 clock enable */ + + regval |= RCC_APB1ENR_I2C1EN; +#endif + +#if CONFIG_STM32_I2C2 + /* I2C 2 clock enable */ + + regval |= RCC_APB1ENR_I2C2EN; +#endif + +#if CONFIG_STM32_USB + /* USB clock enable */ + + regval |= RCC_APB1ENR_USBEN; +#endif + +#if CONFIG_STM32_CAN + /* CAN clock enable */ + + regval |= RCC_APB1ENR_CANEN; +#endif + +#if CONFIG_STM32_BKP + /* Backup interface clock enable */ + + regval |= RCC_APB1ENR_BKPEN; +#endif + +#if CONFIG_STM32_PWR + /* Power interface clock enable */ + + regval |= RCC_APB1ENR_PWREN; +#endif + +#if CONFIG_STM32_DAC + /* DAC interface clock enable */ + + regval |= RCC_APB1ENR_DACEN; +#endif + putreg32(regval, STM32_RCC_APB2ENR); + +#if CONFIG_STM32_USB + /* USB clock divider */ + + regval = getreg32(STM32_RCC_CFGR); + regval &= ~RCC_CFGR_USBPRE; + regval |= STM32_CFGR_USBPRE; + putreg32(regval, STM32_RCC_CFGR); +#endif +} + +static inline void rcc_enableapb2(void) +{ + uint32 regval; + + /* Enable GPIOA, GPIOB, ... and AFIO clocks */ + + regval = getreg32(STM32_RCC_APB2ENR); + regval |= (RCC_APB2ENR_AFIOEN +#if STM32_NGPIO > 0 + |RCC_APB2ENR_IOPAEN +#endif +#if STM32_NGPIO > 1 + |RCC_APB2ENR_IOPBEN +#endif +#if STM32_NGPIO > 2 + |RCC_APB2ENR_IOPCEN +#endif +#if STM32_NGPIO > 3 + |RCC_APB2ENR_IOPDEN +#endif +#if STM32_NGPIO > 4 + |RCC_APB2ENR_IOPEEN +#endif +#if STM32_NGPIO > 5 + |RCC_APB2ENR_IOPFEN +#endif +#if STM32_NGPIO > 6 + |RCC_APB2ENR_IOPEEN +#endif + ); + +#if CONFIG_STM32_ADC1 + /* ADC 1 interface clock enable */ + + regval |= RCC_APB2ENR_ADC1EN; +#endif + +#if CONFIG_STM32_ADC2 + /* ADC 2 interface clock enable */ + + regval |= RCC_APB2ENR_ADC2EN; +#endif + +#if CONFIG_STM32_TIM1 + /* TIM1 Timer clock enable */ + + regval |= RCC_APB2ENR_TIM1EN; +#endif + +#if CONFIG_STM32_SPI1 + /* SPI 1 clock enable */ + + regval |= RCC_APB2ENR_SPI1EN; +#endif + +#if CONFIG_STM32_TIM8 + /* TIM8 Timer clock enable */ + + regval |= RCC_APB2ENR_TIM8EN; +#endif + +#if CONFIG_STM32_USART1 + /* USART1 clock enable */ + + regval |= RCC_APB2ENR_USART1EN; +#endif + +#if CONFIG_STM32_ADC3 + /*ADC3 interface clock enable */ + + regval |= RCC_APB2ENR_ADC3EN; +#endif + putreg32(regval, STM32_RCC_APB2ENR); +} + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_clockconfig + * + * Description: + * Called to change to new clock based on settings in board.h. + * NOTE: This logic needs to be extended so that we can selected low-power + * clocking modes as well! + * + ****************************************************************************/ + +void stm32_clockconfig(void) +{ + uint32 regval; + sint32 timeout; + + /* Make sure that we are starting in the reset state */ + + rcc_reset(); + + /* Enable External High-Speed Clock (HSE) */ + + regval = getreg32(STM32_RCC_CR); + regval &= ~RCC_CR_HSEBYP; /* Disable HSE clock bypass */ + regval |= RCC_CR_HSEON; /* Enable HSE */ + putreg32(regval, STM32_RCC_CR); + + /* Wait until the HSE is ready (or until a timeout elapsed) */ + + for (timeout = HSERDY_TIMEOUT; timeout > 0; timeout--) + { + /* Check if the HSERDY flag is the set in the CR */ + + if ((getreg32(STM32_RCC_CR) & RCC_CR_HSERDY) != 0) + { + /* If so, then break-out with timeout > 0 */ + + break; + } + } + + if( timeout > 0) + { +#if 0 + /* Enable Prefetch Buffer */ + + /* Flash 2 wait state */ +#endif + + /* Set the HCLK source/divider */ + + regval = getreg32(STM32_RCC_CFGR); + regval &= ~RCC_CFGR_HPRE_MASK; + regval |= STM32_RCC_CFGR_HPRE; + putreg32(regval, STM32_RCC_CFGR); + + /* Set the PCLK2 divider */ + + regval = getreg32(STM32_RCC_CFGR); + regval &= ~RCC_CFGR_PPRE2_MASK; + regval |= STM32_RCC_CFGR_PPRE2; + putreg32(regval, STM32_RCC_CFGR); + + /* Set the PCLK1 divider */ + + regval = getreg32(STM32_RCC_CFGR); + regval &= ~RCC_CFGR_PPRE1_MASK; + regval |= STM32_RCC_CFGR_PPRE1; + putreg32(regval, STM32_RCC_CFGR); + + /* Set the PLL divider and multipler */ + + regval = getreg32(STM32_RCC_CFGR); + regval &= ~(RCC_CFGR_PLLSRC|RCC_CFGR_PLLXTPRE|RCC_CFGR_PLLMUL_MASK); + regval |= (STM32_CFGR_PLLSRC|STM32_CFGR_PLLXTPRE|STM32_CFGR_PLLMUL); + putreg32(regval, STM32_RCC_CFGR); + + /* Enable the PLL */ + + regval = getreg32(STM32_RCC_CR); + regval |= RCC_CR_PLLON; + putreg32(regval, STM32_RCC_CR); + + /* Wait until the PLL is ready */ + + while ((getreg32(STM32_RCC_CR) & RCC_CR_PLLRDY) == 0); + + /* Select the system clock source (probably the PLL) */ + + regval = getreg32(STM32_RCC_CFGR); + regval &= ~RCC_CFGR_SW_MASK; + regval |= STM32_SYSCLK_SW; + putreg32(regval, STM32_RCC_CFGR); + + /* Wait until the selected source is used as the system clock source */ + + while ((getreg32(STM32_RCC_CFGR) & RCC_CFGR_SWS_MASK) != STM32_SYSCLK_SWS); + } + + /* Enable periperal clocking */ + + rcc_enableapb2(); + rcc_enableapb1(); +} diff --git a/nuttx/arch/arm/src/stm32/stm32_rcc.h b/nuttx/arch/arm/src/stm32/stm32_rcc.h index 21dd0efc5..a7227cd79 100755 --- a/nuttx/arch/arm/src/stm32/stm32_rcc.h +++ b/nuttx/arch/arm/src/stm32/stm32_rcc.h @@ -63,16 +63,16 @@ /* Register Addresses ***************************************************************/ -#define STM32_RCC_CR (STM32_RCC_OFFSET+STM32_RCC_CR_OFFSET) -#define STM32_RCC_CFGR (STM32_RCC_OFFSET+STM32_RCC_CFGR_OFFSET) -#define STM32_RCC_CIR (STM32_RCC_OFFSET+STM32_RCC_CIR_OFFSET) -#define STM32_RCC_APB2RSTR (STM32_RCC_OFFSET+STM32_RCC_APB2RSTR_OFFSET) -#define STM32_RCC_APB1RSTR (STM32_RCC_OFFSET+STM32_RCC_APB1RSTR_OFFSET) -#define STM32_RCC_AHBENR (STM32_RCC_OFFSET+STM32_RCC_AHBENR_OFFSET) -#define STM32_RCC_APB2ENR (STM32_RCC_OFFSET+STM32_RCC_APB2ENR_OFFSET) -#define STM32_RCC_APB1ENR (STM32_RCC_OFFSET+STM32_RCC_APB1ENR_OFFSET) -#define STM32_RCC_BDCR (STM32_RCC_OFFSET+STM32_RCC_BDCR_OFFSET) -#define STM32_RCC_CSR (STM32_RCC_OFFSET+STM32_RCC_CSR_OFFSET) +#define STM32_RCC_CR (STM32_RCC_BASE+STM32_RCC_CR_OFFSET) +#define STM32_RCC_CFGR (STM32_RCC_BASE+STM32_RCC_CFGR_OFFSET) +#define STM32_RCC_CIR (STM32_RCC_BASE+STM32_RCC_CIR_OFFSET) +#define STM32_RCC_APB2RSTR (STM32_RCC_BASE+STM32_RCC_APB2RSTR_OFFSET) +#define STM32_RCC_APB1RSTR (STM32_RCC_BASE+STM32_RCC_APB1RSTR_OFFSET) +#define STM32_RCC_AHBENR (STM32_RCC_BASE+STM32_RCC_AHBENR_OFFSET) +#define STM32_RCC_APB2ENR (STM32_RCC_BASE+STM32_RCC_APB2ENR_OFFSET) +#define STM32_RCC_APB1ENR (STM32_RCC_BASE+STM32_RCC_APB1ENR_OFFSET) +#define STM32_RCC_BDCR (STM32_RCC_BASE+STM32_RCC_BDCR_OFFSET) +#define STM32_RCC_CSR (STM32_RCC_BASE+STM32_RCC_CSR_OFFSET) /* Register Bitfield Definitions ****************************************************/ diff --git a/nuttx/arch/arm/src/stm32/stm32_timerisr.c b/nuttx/arch/arm/src/stm32/stm32_timerisr.c index d25448391..32c51de59 100644 --- a/nuttx/arch/arm/src/stm32/stm32_timerisr.c +++ b/nuttx/arch/arm/src/stm32/stm32_timerisr.c @@ -61,11 +61,13 @@ * system clock ticks per second. That value is a user configurable setting * that defaults to 100 (100 ticks per second = 10 MS interval). * - * The timer counts at the rate SYSCLK_FREQUENCY as defined in the board.h - * header file. + * The RCC feeds the Cortex System Timer (SysTick) with the AHB clock (HCLK) + * divided by 8. The SysTick can work either with this clock or with the + * Cortex clock (HCLK), configurable in the SysTick Control and Status + * register. */ -#define SYSTICK_RELOAD ((SYSCLK_FREQUENCY / CLK_TCK) - 1) +#define SYSTICK_RELOAD ((STM32_HCLK_FREQUENCY / 8 / CLK_TCK) - 1) /* The size of the reload field is 24 bits. Verify taht the reload value * will fit in the reload register. diff --git a/nuttx/configs/stm3210e-eval/include/board.h b/nuttx/configs/stm3210e-eval/include/board.h index 43bf0cf0d..919c3f880 100755 --- a/nuttx/configs/stm3210e-eval/include/board.h +++ b/nuttx/configs/stm3210e-eval/include/board.h @@ -44,6 +44,7 @@ #ifndef __ASSEMBLY__ # include #endif +#include "stm32_rcc.h" #include "stm32_internal.h" /************************************************************************************ @@ -52,10 +53,41 @@ /* Clocking *************************************************************************/ -# warning "These frequencies are still needed" -#define SYSCLK_FREQUENCY 1 -#define STM32_PCLK1_FREQUENCY 1 -#define STM32_PCLK2_FREQUENCY 1 +/* On-board crystal frequency is 8MHz (HSE) */ + +#define STM32_BOARD_XTAL 8000000ul + +/* PLL source is HSE/1, PLL multipler is 9: PLL frequency is 8MHz (XTAL) x 9 = 72MHz */ + +#define STM32_CFGR_PLLSRC RCC_CFGR_PLLSRC +#define STM32_CFGR_PLLXTPRE 0 +#define STM32_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx9 +#define STM32_PLL_FREQUENCY (9*STM32_BOARD_XTAL) + +/* Use the PLL and set the SYSCLK source to be the PLL */ + +#define STM32_SYSCLK_SW RCC_CFGR_SW_PLL +#define STM32_SYSCLK_SWS RCC_CFGR_SWS_PLL +#define STM32_SYSCLK_FREQUENCY STM32_PLL_FREQUENCY + +/* AHB clock (HCLK) is SYSCLK (72MHz) */ + +#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK +#define STM32_HCLK_FREQUENCY STM32_PLL_FREQUENCY + +/* APB2 clock (PCLK2) is HCLK (72MHz) */ + +#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK +#define STM32_PCLK_FREQUENCY STM32_HCLK_FREQUENCY + +/* APB1 clock (PCLK1) is HCLK/2 (36MHz) */ + +#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd2 +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* USB divider */ + +#define STM32_CFGR_USBPRE 0 /* LED definitions ******************************************************************/ -- cgit v1.2.3