2 ******************************************************************************
3 * @file system_stm32f4xx.c
4 * @author MCD Application Team
6 * @date 21-October-2015
7 * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
8 * This file contains the system clock configuration for STM32F4xx devices.
10 * 1. This file provides two functions and one global variable to be called from
12 * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
13 * and Divider factors, AHB/APBx prescalers and Flash settings),
14 * depending on the configuration made in the clock xls tool.
15 * This function is called at startup just after reset and
16 * before branch to main program. This call is made inside
17 * the "startup_stm32f4xx.s" file.
19 * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
20 * by the user application to setup the SysTick
21 * timer or configure other parameters.
23 * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
24 * be called whenever the core clock is changed
25 * during program execution.
27 * 2. After each device reset the HSI (16 MHz) is used as system clock source.
28 * Then SystemInit() function is called, in "startup_stm32f4xx.s" file, to
29 * configure the system clock before to branch to main program.
31 * 3. If the system clock source selected by user fails to startup, the SystemInit()
32 * function will do nothing and HSI still used as system clock source. User can
33 * add some code to deal with this issue inside the SetSysClock() function.
35 * 4. The default value of HSE crystal is set to 25MHz, refer to "HSE_VALUE" define
36 * in "stm32f4xx.h" file. When HSE is used as system clock source, directly or
37 * through PLL, and you are using different crystal you have to adapt the HSE
38 * value to your own configuration.
40 * 5. This file configures the system clock as follows:
41 *=============================================================================
42 *=============================================================================
43 * Supported STM32F40xxx/41xxx devices
44 *-----------------------------------------------------------------------------
45 * System Clock source | PLL (HSE)
46 *-----------------------------------------------------------------------------
47 * SYSCLK(Hz) | 168000000
48 *-----------------------------------------------------------------------------
49 * HCLK(Hz) | 168000000
50 *-----------------------------------------------------------------------------
52 *-----------------------------------------------------------------------------
54 *-----------------------------------------------------------------------------
56 *-----------------------------------------------------------------------------
57 * HSE Frequency(Hz) | 8000000
58 *-----------------------------------------------------------------------------
60 *-----------------------------------------------------------------------------
62 *-----------------------------------------------------------------------------
64 *-----------------------------------------------------------------------------
66 *-----------------------------------------------------------------------------
68 *-----------------------------------------------------------------------------
70 *-----------------------------------------------------------------------------
71 * I2S input clock | NA
72 *-----------------------------------------------------------------------------
74 *-----------------------------------------------------------------------------
75 * Main regulator output voltage | Scale1 mode
76 *-----------------------------------------------------------------------------
77 * Flash Latency(WS) | 5
78 *-----------------------------------------------------------------------------
79 * Prefetch Buffer | ON
80 *-----------------------------------------------------------------------------
81 * Instruction cache | ON
82 *-----------------------------------------------------------------------------
84 *-----------------------------------------------------------------------------
85 * Require 48MHz for USB OTG FS, | Disabled
86 * SDIO and RNG clock |
87 *-----------------------------------------------------------------------------
88 *=============================================================================
89 *=============================================================================
90 * Supported STM32F42xxx/43xxx devices
91 *-----------------------------------------------------------------------------
92 * System Clock source | PLL (HSE)
93 *-----------------------------------------------------------------------------
94 * SYSCLK(Hz) | 180000000
95 *-----------------------------------------------------------------------------
96 * HCLK(Hz) | 180000000
97 *-----------------------------------------------------------------------------
99 *-----------------------------------------------------------------------------
101 *-----------------------------------------------------------------------------
103 *-----------------------------------------------------------------------------
104 * HSE Frequency(Hz) | 25000000
105 *-----------------------------------------------------------------------------
107 *-----------------------------------------------------------------------------
109 *-----------------------------------------------------------------------------
111 *-----------------------------------------------------------------------------
113 *-----------------------------------------------------------------------------
115 *-----------------------------------------------------------------------------
117 *-----------------------------------------------------------------------------
118 * I2S input clock | NA
119 *-----------------------------------------------------------------------------
121 *-----------------------------------------------------------------------------
122 * Main regulator output voltage | Scale1 mode
123 *-----------------------------------------------------------------------------
124 * Flash Latency(WS) | 5
125 *-----------------------------------------------------------------------------
126 * Prefetch Buffer | ON
127 *-----------------------------------------------------------------------------
128 * Instruction cache | ON
129 *-----------------------------------------------------------------------------
131 *-----------------------------------------------------------------------------
132 * Require 48MHz for USB OTG FS, | Disabled
133 * SDIO and RNG clock |
134 *-----------------------------------------------------------------------------
135 *=============================================================================
136 *=============================================================================
137 * Supported STM32F401xx devices
138 *-----------------------------------------------------------------------------
139 * System Clock source | PLL (HSE)
140 *-----------------------------------------------------------------------------
141 * SYSCLK(Hz) | 84000000
142 *-----------------------------------------------------------------------------
143 * HCLK(Hz) | 84000000
144 *-----------------------------------------------------------------------------
146 *-----------------------------------------------------------------------------
148 *-----------------------------------------------------------------------------
150 *-----------------------------------------------------------------------------
151 * HSE Frequency(Hz) | 25000000
152 *-----------------------------------------------------------------------------
154 *-----------------------------------------------------------------------------
156 *-----------------------------------------------------------------------------
158 *-----------------------------------------------------------------------------
160 *-----------------------------------------------------------------------------
162 *-----------------------------------------------------------------------------
164 *-----------------------------------------------------------------------------
165 * I2S input clock | NA
166 *-----------------------------------------------------------------------------
168 *-----------------------------------------------------------------------------
169 * Main regulator output voltage | Scale1 mode
170 *-----------------------------------------------------------------------------
171 * Flash Latency(WS) | 2
172 *-----------------------------------------------------------------------------
173 * Prefetch Buffer | ON
174 *-----------------------------------------------------------------------------
175 * Instruction cache | ON
176 *-----------------------------------------------------------------------------
178 *-----------------------------------------------------------------------------
179 * Require 48MHz for USB OTG FS, | Disabled
180 * SDIO and RNG clock |
181 *-----------------------------------------------------------------------------
182 *=============================================================================
183 *=============================================================================
184 * Supported STM32F411xx/STM32F410xx devices
185 *-----------------------------------------------------------------------------
186 * System Clock source | PLL (HSI)
187 *-----------------------------------------------------------------------------
188 * SYSCLK(Hz) | 100000000
189 *-----------------------------------------------------------------------------
190 * HCLK(Hz) | 100000000
191 *-----------------------------------------------------------------------------
193 *-----------------------------------------------------------------------------
195 *-----------------------------------------------------------------------------
197 *-----------------------------------------------------------------------------
198 * HSI Frequency(Hz) | 16000000
199 *-----------------------------------------------------------------------------
201 *-----------------------------------------------------------------------------
203 *-----------------------------------------------------------------------------
205 *-----------------------------------------------------------------------------
207 *-----------------------------------------------------------------------------
209 *-----------------------------------------------------------------------------
211 *-----------------------------------------------------------------------------
212 * I2S input clock | NA
213 *-----------------------------------------------------------------------------
215 *-----------------------------------------------------------------------------
216 * Main regulator output voltage | Scale1 mode
217 *-----------------------------------------------------------------------------
218 * Flash Latency(WS) | 3
219 *-----------------------------------------------------------------------------
220 * Prefetch Buffer | ON
221 *-----------------------------------------------------------------------------
222 * Instruction cache | ON
223 *-----------------------------------------------------------------------------
225 *-----------------------------------------------------------------------------
226 * Require 48MHz for USB OTG FS, | Disabled
227 * SDIO and RNG clock |
228 *-----------------------------------------------------------------------------
229 *=============================================================================
230 *=============================================================================
231 * Supported STM32F446xx devices
232 *-----------------------------------------------------------------------------
233 * System Clock source | PLL (HSE)
234 *-----------------------------------------------------------------------------
235 * SYSCLK(Hz) | 180000000
236 *-----------------------------------------------------------------------------
237 * HCLK(Hz) | 180000000
238 *-----------------------------------------------------------------------------
240 *-----------------------------------------------------------------------------
242 *-----------------------------------------------------------------------------
244 *-----------------------------------------------------------------------------
245 * HSE Frequency(Hz) | 8000000
246 *-----------------------------------------------------------------------------
248 *-----------------------------------------------------------------------------
250 *-----------------------------------------------------------------------------
252 *-----------------------------------------------------------------------------
254 *-----------------------------------------------------------------------------
256 *-----------------------------------------------------------------------------
258 *-----------------------------------------------------------------------------
260 *-----------------------------------------------------------------------------
262 *-----------------------------------------------------------------------------
264 *-----------------------------------------------------------------------------
266 *-----------------------------------------------------------------------------
267 * I2S input clock | NA
268 *-----------------------------------------------------------------------------
270 *-----------------------------------------------------------------------------
271 * Main regulator output voltage | Scale1 mode
272 *-----------------------------------------------------------------------------
273 * Flash Latency(WS) | 5
274 *-----------------------------------------------------------------------------
275 * Prefetch Buffer | ON
276 *-----------------------------------------------------------------------------
277 * Instruction cache | ON
278 *-----------------------------------------------------------------------------
280 *-----------------------------------------------------------------------------
281 * Require 48MHz for USB OTG FS, | Disabled
282 * SDIO and RNG clock |
283 *-----------------------------------------------------------------------------
284 *=============================================================================
285 ******************************************************************************
288 * <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
290 * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
291 * You may not use this file except in compliance with the License.
292 * You may obtain a copy of the License at:
294 * http://www.st.com/software_license_agreement_liberty_v2
296 * Unless required by applicable law or agreed to in writing, software
297 * distributed under the License is distributed on an "AS IS" BASIS,
298 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
299 * See the License for the specific language governing permissions and
300 * limitations under the License.
302 ******************************************************************************
305 /** @addtogroup CMSIS
309 /** @addtogroup stm32f4xx_system
313 /** @addtogroup STM32F4xx_System_Private_Includes
317 #include "stm32f4xx.h"
319 #include "system_stm32f4xx.h"
320 #include "drivers/system.h"
322 uint32_t hse_value
= HSE_VALUE
;
328 /** @addtogroup STM32F4xx_System_Private_TypesDefinitions
336 /** @addtogroup STM32F4xx_System_Private_Defines
340 /************************* Miscellaneous Configuration ************************/
341 /*!< Uncomment the following line if you need to use external SRAM or SDRAM mounted
342 on STM324xG_EVAL/STM324x7I_EVAL/STM324x9I_EVAL boards as data memory */
343 #if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx)
344 /* #define DATA_IN_ExtSRAM */
345 #endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx || STM32F469_479xx */
347 #if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
348 /* #define DATA_IN_ExtSDRAM */
349 #endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
351 #if defined(STM32F410xx) || defined(STM32F411xE)
352 /*!< Uncomment the following line if you need to clock the STM32F410xx/STM32F411xE by HSE Bypass
353 through STLINK MCO pin of STM32F103 microcontroller. The frequency cannot be changed
354 and is fixed at 8 MHz.
355 Hardware configuration needed for Nucleo Board:
359 /* #define USE_HSE_BYPASS */
361 #if defined(USE_HSE_BYPASS)
362 #define HSE_BYPASS_INPUT_FREQUENCY 8000000
363 #endif /* USE_HSE_BYPASS */
364 #endif /* STM32F410xx || STM32F411xE */
366 /*!< Uncomment the following line if you need to relocate your vector Table in
368 /* #define VECT_TAB_SRAM */
369 #define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field.
370 This value must be a multiple of 0x200. */
371 /******************************************************************************/
373 /************************* PLL Parameters *************************************/
374 #if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F469_479xx) || defined (STM32F446xx) || defined (STM32F410xx) || defined (STM32F411xE)
375 #if HSE_VALUE == 24000000
377 #elif HSE_VALUE == 16000000
379 #elif HSE_VALUE == 8000000
382 #error Invalid HSE_VALUE
386 #endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F469_479xx */
388 #if defined(STM32F446xx)
389 /* PLL division factor for I2S, SAI, SYSTEM and SPDIF: Clock = PLL_VCO / PLLR */
391 #endif /* STM32F446xx */
393 #if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
395 /* SYSCLK = PLL_VCO / PLL_P */
397 /* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
399 #endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
401 #if defined (STM32F40_41xxx)
403 /* SYSCLK = PLL_VCO / PLL_P */
405 /* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
407 #endif /* STM32F40_41xxx */
409 #if defined(STM32F401xx)
411 /* SYSCLK = PLL_VCO / PLL_P */
413 /* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
415 #endif /* STM32F401xx */
417 #if defined(STM32F410xx) || defined(STM32F411xE)
419 /* SYSCLK = PLL_VCO / PLL_P */
421 /* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
423 #endif /* STM32F410xx || STM32F411xE */
425 /******************************************************************************/
431 /** @addtogroup STM32F4xx_System_Private_Macros
439 /** @addtogroup STM32F4xx_System_Private_Variables
443 /* core clock is simply a mhz of PLL_N / PLL_P */
444 uint32_t SystemCoreClock
= 1000000 * PLL_N
/ PLL_P
;
446 __I
uint8_t AHBPrescTable
[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
452 /** @addtogroup STM32F4xx_System_Private_FunctionPrototypes
456 void SetSysClock(void);
458 #if defined(DATA_IN_ExtSRAM) || defined(DATA_IN_ExtSDRAM)
459 static void SystemInit_ExtMemCtl(void);
460 #endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
466 /** @addtogroup STM32F4xx_System_Private_Functions
471 * @brief Setup the microcontroller system
472 * Initialize the Embedded Flash Interface, the PLL and update the
473 * SystemFrequency variable.
477 void SystemInit(void)
479 initialiseMemorySections();
481 /* FPU settings ------------------------------------------------------------*/
482 #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
483 SCB
->CPACR
|= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
485 /* Reset the RCC clock configuration to the default reset state ------------*/
487 RCC
->CR
|= (uint32_t)0x00000001;
489 /* Reset CFGR register */
490 RCC
->CFGR
= 0x00000000;
492 /* Reset HSEON, CSSON and PLLON bits */
493 RCC
->CR
&= (uint32_t)0xFEF6FFFF;
495 /* Reset PLLCFGR register */
496 RCC
->PLLCFGR
= 0x24003010;
498 /* Reset HSEBYP bit */
499 RCC
->CR
&= (uint32_t)0xFFFBFFFF;
501 /* Disable all interrupts */
502 RCC
->CIR
= 0x00000000;
504 #if defined(DATA_IN_ExtSRAM) || defined(DATA_IN_ExtSDRAM)
505 SystemInit_ExtMemCtl();
506 #endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
508 /* Configure the System clock source, PLL Multiplier and Divider factors,
509 AHB/APBx prescalers and Flash settings ----------------------------------*/
512 /* Configure the Vector Table location add offset address ------------------*/
514 SCB
->VTOR
= SRAM_BASE
| VECT_TAB_OFFSET
; /* Vector Table Relocation in Internal SRAM */
516 SCB
->VTOR
= (uint32_t) &isr_vector_table_base
; /* Vector Table Relocation in Internal FLASH */
521 * @brief Update SystemCoreClock variable according to Clock Register Values.
522 * The SystemCoreClock variable contains the core clock (HCLK), it can
523 * be used by the user application to setup the SysTick timer or configure
526 * @note Each time the core clock (HCLK) changes, this function must be called
527 * to update SystemCoreClock variable value. Otherwise, any configuration
528 * based on this variable will be incorrect.
530 * @note - The system frequency computed by this function is not the real
531 * frequency in the chip. It is calculated based on the predefined
532 * constant and the selected clock source:
534 * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
536 * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
538 * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
539 * or HSI_VALUE(*) multiplied/divided by the PLL factors.
541 * (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value
542 * 16 MHz) but the real value may vary depending on the variations
543 * in voltage and temperature.
545 * (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value
546 * 25 MHz), user has to ensure that HSE_VALUE is same as the real
547 * frequency of the crystal used. Otherwise, this function may
550 * - The result of this function could be not correct when using fractional
551 * value for HSE crystal.
556 void SystemCoreClockUpdate(void)
558 uint32_t tmp
= 0, pllvco
= 0, pllp
= 2, pllsource
= 0, pllm
= 2;
559 #if defined(STM32F446xx)
561 #endif /* STM32F446xx */
562 /* Get SYSCLK source -------------------------------------------------------*/
563 tmp
= RCC
->CFGR
& RCC_CFGR_SWS
;
567 case 0x00: /* HSI used as system clock source */
568 SystemCoreClock
= HSI_VALUE
;
570 case 0x04: /* HSE used as system clock source */
571 SystemCoreClock
= HSE_VALUE
;
573 case 0x08: /* PLL P used as system clock source */
574 /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
575 SYSCLK = PLL_VCO / PLL_P
577 pllsource
= (RCC
->PLLCFGR
& RCC_PLLCFGR_PLLSRC
) >> 22;
578 pllm
= RCC
->PLLCFGR
& RCC_PLLCFGR_PLLM
;
582 /* HSE used as PLL clock source */
583 pllvco
= (HSE_VALUE
/ pllm
) * ((RCC
->PLLCFGR
& RCC_PLLCFGR_PLLN
) >> 6);
587 /* HSI used as PLL clock source */
588 pllvco
= (HSI_VALUE
/ pllm
) * ((RCC
->PLLCFGR
& RCC_PLLCFGR_PLLN
) >> 6);
591 pllp
= (((RCC
->PLLCFGR
& RCC_PLLCFGR_PLLP
) >>16) + 1 ) *2;
592 SystemCoreClock
= pllvco
/pllp
;
594 #if defined(STM32F446xx)
595 case 0x0C: /* PLL R used as system clock source */
596 /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
597 SYSCLK = PLL_VCO / PLL_R
599 pllsource
= (RCC
->PLLCFGR
& RCC_PLLCFGR_PLLSRC
) >> 22;
600 pllm
= RCC
->PLLCFGR
& RCC_PLLCFGR_PLLM
;
603 /* HSE used as PLL clock source */
604 pllvco
= (HSE_VALUE
/ pllm
) * ((RCC
->PLLCFGR
& RCC_PLLCFGR_PLLN
) >> 6);
608 /* HSI used as PLL clock source */
609 pllvco
= (HSI_VALUE
/ pllm
) * ((RCC
->PLLCFGR
& RCC_PLLCFGR_PLLN
) >> 6);
612 pllr
= (((RCC
->PLLCFGR
& RCC_PLLCFGR_PLLR
) >>28) + 1 ) *2;
613 SystemCoreClock
= pllvco
/pllr
;
615 #endif /* STM32F446xx */
617 SystemCoreClock
= HSI_VALUE
;
620 /* Compute HCLK frequency --------------------------------------------------*/
621 /* Get HCLK prescaler */
622 tmp
= AHBPrescTable
[((RCC
->CFGR
& RCC_CFGR_HPRE
) >> 4)];
624 SystemCoreClock
>>= tmp
;
628 * @brief Configures the System clock source, PLL Multiplier and Divider factors,
629 * AHB/APBx prescalers and Flash settings
630 * @Note This function should be called only once the RCC clock configuration
631 * is reset to the default reset state (done in SystemInit() function).
635 void SetSysClock(void)
637 /******************************************************************************/
638 /* PLL (clocked by HSE) used as System clock source */
639 /******************************************************************************/
640 __IO
uint32_t StartUpCounter
= 0, HSEStatus
= 0;
643 RCC
->CR
|= ((uint32_t)RCC_CR_HSEON
);
645 /* Wait till HSE is ready and if Time out is reached exit */
648 HSEStatus
= RCC
->CR
& RCC_CR_HSERDY
;
650 } while ((HSEStatus
== 0) && (StartUpCounter
!= HSE_STARTUP_TIMEOUT
));
652 if ((RCC
->CR
& RCC_CR_HSERDY
) != RESET
)
654 HSEStatus
= (uint32_t)0x01;
658 HSEStatus
= (uint32_t)0x00;
661 if (HSEStatus
== (uint32_t)0x01)
663 /* Select regulator voltage output Scale 1 mode */
664 RCC
->APB1ENR
|= RCC_APB1ENR_PWREN
;
665 PWR
->CR
|= PWR_CR_VOS
;
667 /* HCLK = SYSCLK / 1*/
668 RCC
->CFGR
|= RCC_CFGR_HPRE_DIV1
;
670 #if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
671 /* PCLK2 = HCLK / 2*/
672 RCC
->CFGR
|= RCC_CFGR_PPRE2_DIV2
;
674 /* PCLK1 = HCLK / 4*/
675 RCC
->CFGR
|= RCC_CFGR_PPRE1_DIV4
;
676 #endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
678 #if defined(STM32F401xx)
679 /* PCLK2 = HCLK / 2*/
680 RCC
->CFGR
|= RCC_CFGR_PPRE2_DIV1
;
682 /* PCLK1 = HCLK / 4*/
683 RCC
->CFGR
|= RCC_CFGR_PPRE1_DIV2
;
684 #endif /* STM32F401xx */
686 #if defined(STM32F410xx) || defined(STM32F411xE)
687 /* PCLK2 = HCLK / 2*/
688 RCC
->CFGR
|= RCC_CFGR_PPRE2_DIV1
;
690 /* PCLK1 = HCLK / 4*/
691 RCC
->CFGR
|= RCC_CFGR_PPRE1_DIV2
;
692 #endif /* STM32F410xx || STM32F411xE */
694 #if defined(STM32F446xx)
695 /* Configure the main PLL */
696 RCC
->PLLCFGR
= PLL_M
| (PLL_N
<< 6) | (((PLL_P
>> 1) -1) << 16) |
697 (RCC_PLLCFGR_PLLSRC_HSE
) | (PLL_Q
<< 24) | (PLL_R
<< 28);
699 /* Configure the main PLL */
700 RCC
->PLLCFGR
= PLL_M
| (PLL_N
<< 6) | (((PLL_P
>> 1) -1) << 16) |
701 (RCC_PLLCFGR_PLLSRC_HSE
) | (PLL_Q
<< 24);
702 #endif /* STM32F446xx */
704 /* Enable the main PLL */
705 RCC
->CR
|= RCC_CR_PLLON
;
707 /* Wait till the main PLL is ready */
708 while ((RCC
->CR
& RCC_CR_PLLRDY
) == 0)
712 #if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
713 /* Enable the Over-drive to extend the clock frequency to 180 Mhz */
714 PWR
->CR
|= PWR_CR_ODEN
;
715 while ((PWR
->CSR
& PWR_CSR_ODRDY
) == 0)
718 PWR
->CR
|= PWR_CR_ODSWEN
;
719 while ((PWR
->CSR
& PWR_CSR_ODSWRDY
) == 0)
722 #endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
724 #if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
725 /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
726 FLASH
->ACR
= FLASH_ACR_PRFTEN
| FLASH_ACR_ICEN
|FLASH_ACR_DCEN
|FLASH_ACR_LATENCY_5WS
;
727 #endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
729 #if defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE)
730 /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
731 FLASH
->ACR
= FLASH_ACR_PRFTEN
| FLASH_ACR_ICEN
|FLASH_ACR_DCEN
|FLASH_ACR_LATENCY_2WS
;
732 #endif /* STM32F401xx || STM32F410xx || STM32F411xE*/
734 /* Select the main PLL as system clock source */
735 RCC
->CFGR
&= (uint32_t)((uint32_t)~(RCC_CFGR_SW
));
736 RCC
->CFGR
|= RCC_CFGR_SW_PLL
;
738 /* Wait till the main PLL is used as system clock source */
739 while ((RCC
->CFGR
& (uint32_t)RCC_CFGR_SWS
) != RCC_CFGR_SWS_PLL
)
744 { /* If HSE fails to start-up, the application will have wrong clock
745 configuration. User can add here some code to deal with this error */
746 while(1) { __NOP(); }
749 SystemCoreClockUpdate();
753 * @brief Setup the external memory controller. Called in startup_stm32f4xx.s
754 * before jump to __main
758 #ifdef DATA_IN_ExtSRAM
760 * @brief Setup the external memory controller.
761 * Called in startup_stm32f4xx.s before jump to main.
762 * This function configures the external SRAM mounted on STM324xG_EVAL/STM324x7I boards
763 * This SRAM will be used as program data memory (including heap and stack).
767 void SystemInit_ExtMemCtl(void)
769 /*-- GPIOs Configuration -----------------------------------------------------*/
771 +-------------------+--------------------+------------------+--------------+
772 + SRAM pins assignment +
773 +-------------------+--------------------+------------------+--------------+
774 | PD0 <-> FMC_D2 | PE0 <-> FMC_NBL0 | PF0 <-> FMC_A0 | PG0 <-> FMC_A10 |
775 | PD1 <-> FMC_D3 | PE1 <-> FMC_NBL1 | PF1 <-> FMC_A1 | PG1 <-> FMC_A11 |
776 | PD4 <-> FMC_NOE | PE3 <-> FMC_A19 | PF2 <-> FMC_A2 | PG2 <-> FMC_A12 |
777 | PD5 <-> FMC_NWE | PE4 <-> FMC_A20 | PF3 <-> FMC_A3 | PG3 <-> FMC_A13 |
778 | PD8 <-> FMC_D13 | PE7 <-> FMC_D4 | PF4 <-> FMC_A4 | PG4 <-> FMC_A14 |
779 | PD9 <-> FMC_D14 | PE8 <-> FMC_D5 | PF5 <-> FMC_A5 | PG5 <-> FMC_A15 |
780 | PD10 <-> FMC_D15 | PE9 <-> FMC_D6 | PF12 <-> FMC_A6 | PG9 <-> FMC_NE2 |
781 | PD11 <-> FMC_A16 | PE10 <-> FMC_D7 | PF13 <-> FMC_A7 |-----------------+
782 | PD12 <-> FMC_A17 | PE11 <-> FMC_D8 | PF14 <-> FMC_A8 |
783 | PD13 <-> FMC_A18 | PE12 <-> FMC_D9 | PF15 <-> FMC_A9 |
784 | PD14 <-> FMC_D0 | PE13 <-> FMC_D10 |-----------------+
785 | PD15 <-> FMC_D1 | PE14 <-> FMC_D11 |
786 | | PE15 <-> FMC_D12 |
787 +------------------+------------------+
789 /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */
790 RCC
->AHB1ENR
|= 0x00000078;
792 /* Connect PDx pins to FMC Alternate function */
793 GPIOD
->AFR
[0] = 0x00cc00cc;
794 GPIOD
->AFR
[1] = 0xcccccccc;
795 /* Configure PDx pins in Alternate function mode */
796 GPIOD
->MODER
= 0xaaaa0a0a;
797 /* Configure PDx pins speed to 100 MHz */
798 GPIOD
->OSPEEDR
= 0xffff0f0f;
799 /* Configure PDx pins Output type to push-pull */
800 GPIOD
->OTYPER
= 0x00000000;
801 /* No pull-up, pull-down for PDx pins */
802 GPIOD
->PUPDR
= 0x00000000;
804 /* Connect PEx pins to FMC Alternate function */
805 GPIOE
->AFR
[0] = 0xcccccccc;
806 GPIOE
->AFR
[1] = 0xcccccccc;
807 /* Configure PEx pins in Alternate function mode */
808 GPIOE
->MODER
= 0xaaaaaaaa;
809 /* Configure PEx pins speed to 100 MHz */
810 GPIOE
->OSPEEDR
= 0xffffffff;
811 /* Configure PEx pins Output type to push-pull */
812 GPIOE
->OTYPER
= 0x00000000;
813 /* No pull-up, pull-down for PEx pins */
814 GPIOE
->PUPDR
= 0x00000000;
816 /* Connect PFx pins to FMC Alternate function */
817 GPIOF
->AFR
[0] = 0x00cccccc;
818 GPIOF
->AFR
[1] = 0xcccc0000;
819 /* Configure PFx pins in Alternate function mode */
820 GPIOF
->MODER
= 0xaa000aaa;
821 /* Configure PFx pins speed to 100 MHz */
822 GPIOF
->OSPEEDR
= 0xff000fff;
823 /* Configure PFx pins Output type to push-pull */
824 GPIOF
->OTYPER
= 0x00000000;
825 /* No pull-up, pull-down for PFx pins */
826 GPIOF
->PUPDR
= 0x00000000;
828 /* Connect PGx pins to FMC Alternate function */
829 GPIOG
->AFR
[0] = 0x00cccccc;
830 GPIOG
->AFR
[1] = 0x000000c0;
831 /* Configure PGx pins in Alternate function mode */
832 GPIOG
->MODER
= 0x00080aaa;
833 /* Configure PGx pins speed to 100 MHz */
834 GPIOG
->OSPEEDR
= 0x000c0fff;
835 /* Configure PGx pins Output type to push-pull */
836 GPIOG
->OTYPER
= 0x00000000;
837 /* No pull-up, pull-down for PGx pins */
838 GPIOG
->PUPDR
= 0x00000000;
840 /*-- FMC Configuration ------------------------------------------------------*/
841 /* Enable the FMC/FSMC interface clock */
842 RCC
->AHB3ENR
|= 0x00000001;
844 #if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
845 /* Configure and enable Bank1_SRAM2 */
846 FMC_Bank1
->BTCR
[2] = 0x00001011;
847 FMC_Bank1
->BTCR
[3] = 0x00000201;
848 FMC_Bank1E
->BWTR
[2] = 0x0fffffff;
849 #endif /* STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
851 #if defined(STM32F40_41xxx)
852 /* Configure and enable Bank1_SRAM2 */
853 FSMC_Bank1
->BTCR
[2] = 0x00001011;
854 FSMC_Bank1
->BTCR
[3] = 0x00000201;
855 FSMC_Bank1E
->BWTR
[2] = 0x0fffffff;
856 #endif /* STM32F40_41xxx */
859 Bank1_SRAM2 is configured as follow:
860 In case of FSMC configuration
861 NORSRAMTimingStructure.FSMC_AddressSetupTime = 1;
862 NORSRAMTimingStructure.FSMC_AddressHoldTime = 0;
863 NORSRAMTimingStructure.FSMC_DataSetupTime = 2;
864 NORSRAMTimingStructure.FSMC_BusTurnAroundDuration = 0;
865 NORSRAMTimingStructure.FSMC_CLKDivision = 0;
866 NORSRAMTimingStructure.FSMC_DataLatency = 0;
867 NORSRAMTimingStructure.FSMC_AccessMode = FMC_AccessMode_A;
869 FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM2;
870 FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable;
871 FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_SRAM;
872 FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b;
873 FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
874 FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable;
875 FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
876 FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable;
877 FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
878 FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable;
879 FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable;
880 FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
881 FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable;
882 FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &NORSRAMTimingStructure;
883 FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &NORSRAMTimingStructure;
885 In case of FMC configuration
886 NORSRAMTimingStructure.FMC_AddressSetupTime = 1;
887 NORSRAMTimingStructure.FMC_AddressHoldTime = 0;
888 NORSRAMTimingStructure.FMC_DataSetupTime = 2;
889 NORSRAMTimingStructure.FMC_BusTurnAroundDuration = 0;
890 NORSRAMTimingStructure.FMC_CLKDivision = 0;
891 NORSRAMTimingStructure.FMC_DataLatency = 0;
892 NORSRAMTimingStructure.FMC_AccessMode = FMC_AccessMode_A;
894 FMC_NORSRAMInitStructure.FMC_Bank = FMC_Bank1_NORSRAM2;
895 FMC_NORSRAMInitStructure.FMC_DataAddressMux = FMC_DataAddressMux_Disable;
896 FMC_NORSRAMInitStructure.FMC_MemoryType = FMC_MemoryType_SRAM;
897 FMC_NORSRAMInitStructure.FMC_MemoryDataWidth = FMC_MemoryDataWidth_16b;
898 FMC_NORSRAMInitStructure.FMC_BurstAccessMode = FMC_BurstAccessMode_Disable;
899 FMC_NORSRAMInitStructure.FMC_AsynchronousWait = FMC_AsynchronousWait_Disable;
900 FMC_NORSRAMInitStructure.FMC_WaitSignalPolarity = FMC_WaitSignalPolarity_Low;
901 FMC_NORSRAMInitStructure.FMC_WrapMode = FMC_WrapMode_Disable;
902 FMC_NORSRAMInitStructure.FMC_WaitSignalActive = FMC_WaitSignalActive_BeforeWaitState;
903 FMC_NORSRAMInitStructure.FMC_WriteOperation = FMC_WriteOperation_Enable;
904 FMC_NORSRAMInitStructure.FMC_WaitSignal = FMC_WaitSignal_Disable;
905 FMC_NORSRAMInitStructure.FMC_ExtendedMode = FMC_ExtendedMode_Disable;
906 FMC_NORSRAMInitStructure.FMC_WriteBurst = FMC_WriteBurst_Disable;
907 FMC_NORSRAMInitStructure.FMC_ContinousClock = FMC_CClock_SyncOnly;
908 FMC_NORSRAMInitStructure.FMC_ReadWriteTimingStruct = &NORSRAMTimingStructure;
909 FMC_NORSRAMInitStructure.FMC_WriteTimingStruct = &NORSRAMTimingStructure;
913 #endif /* DATA_IN_ExtSRAM */
915 #ifdef DATA_IN_ExtSDRAM
917 * @brief Setup the external memory controller.
918 * Called in startup_stm32f4xx.s before jump to main.
919 * This function configures the external SDRAM mounted on STM324x9I_EVAL board
920 * This SDRAM will be used as program data memory (including heap and stack).
924 void SystemInit_ExtMemCtl(void)
926 register uint32_t tmpreg
= 0, timeout
= 0xFFFF;
927 register uint32_t index
;
929 /* Enable GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH and GPIOI interface
931 RCC
->AHB1ENR
|= 0x000001FC;
933 /* Connect PCx pins to FMC Alternate function */
934 GPIOC
->AFR
[0] = 0x0000000c;
935 GPIOC
->AFR
[1] = 0x00007700;
936 /* Configure PCx pins in Alternate function mode */
937 GPIOC
->MODER
= 0x00a00002;
938 /* Configure PCx pins speed to 50 MHz */
939 GPIOC
->OSPEEDR
= 0x00a00002;
940 /* Configure PCx pins Output type to push-pull */
941 GPIOC
->OTYPER
= 0x00000000;
942 /* No pull-up, pull-down for PCx pins */
943 GPIOC
->PUPDR
= 0x00500000;
945 /* Connect PDx pins to FMC Alternate function */
946 GPIOD
->AFR
[0] = 0x000000CC;
947 GPIOD
->AFR
[1] = 0xCC000CCC;
948 /* Configure PDx pins in Alternate function mode */
949 GPIOD
->MODER
= 0xA02A000A;
950 /* Configure PDx pins speed to 50 MHz */
951 GPIOD
->OSPEEDR
= 0xA02A000A;
952 /* Configure PDx pins Output type to push-pull */
953 GPIOD
->OTYPER
= 0x00000000;
954 /* No pull-up, pull-down for PDx pins */
955 GPIOD
->PUPDR
= 0x00000000;
957 /* Connect PEx pins to FMC Alternate function */
958 GPIOE
->AFR
[0] = 0xC00000CC;
959 GPIOE
->AFR
[1] = 0xCCCCCCCC;
960 /* Configure PEx pins in Alternate function mode */
961 GPIOE
->MODER
= 0xAAAA800A;
962 /* Configure PEx pins speed to 50 MHz */
963 GPIOE
->OSPEEDR
= 0xAAAA800A;
964 /* Configure PEx pins Output type to push-pull */
965 GPIOE
->OTYPER
= 0x00000000;
966 /* No pull-up, pull-down for PEx pins */
967 GPIOE
->PUPDR
= 0x00000000;
969 /* Connect PFx pins to FMC Alternate function */
970 GPIOF
->AFR
[0] = 0xcccccccc;
971 GPIOF
->AFR
[1] = 0xcccccccc;
972 /* Configure PFx pins in Alternate function mode */
973 GPIOF
->MODER
= 0xAA800AAA;
974 /* Configure PFx pins speed to 50 MHz */
975 GPIOF
->OSPEEDR
= 0xAA800AAA;
976 /* Configure PFx pins Output type to push-pull */
977 GPIOF
->OTYPER
= 0x00000000;
978 /* No pull-up, pull-down for PFx pins */
979 GPIOF
->PUPDR
= 0x00000000;
981 /* Connect PGx pins to FMC Alternate function */
982 GPIOG
->AFR
[0] = 0xcccccccc;
983 GPIOG
->AFR
[1] = 0xcccccccc;
984 /* Configure PGx pins in Alternate function mode */
985 GPIOG
->MODER
= 0xaaaaaaaa;
986 /* Configure PGx pins speed to 50 MHz */
987 GPIOG
->OSPEEDR
= 0xaaaaaaaa;
988 /* Configure PGx pins Output type to push-pull */
989 GPIOG
->OTYPER
= 0x00000000;
990 /* No pull-up, pull-down for PGx pins */
991 GPIOG
->PUPDR
= 0x00000000;
993 /* Connect PHx pins to FMC Alternate function */
994 GPIOH
->AFR
[0] = 0x00C0CC00;
995 GPIOH
->AFR
[1] = 0xCCCCCCCC;
996 /* Configure PHx pins in Alternate function mode */
997 GPIOH
->MODER
= 0xAAAA08A0;
998 /* Configure PHx pins speed to 50 MHz */
999 GPIOH
->OSPEEDR
= 0xAAAA08A0;
1000 /* Configure PHx pins Output type to push-pull */
1001 GPIOH
->OTYPER
= 0x00000000;
1002 /* No pull-up, pull-down for PHx pins */
1003 GPIOH
->PUPDR
= 0x00000000;
1005 /* Connect PIx pins to FMC Alternate function */
1006 GPIOI
->AFR
[0] = 0xCCCCCCCC;
1007 GPIOI
->AFR
[1] = 0x00000CC0;
1008 /* Configure PIx pins in Alternate function mode */
1009 GPIOI
->MODER
= 0x0028AAAA;
1010 /* Configure PIx pins speed to 50 MHz */
1011 GPIOI
->OSPEEDR
= 0x0028AAAA;
1012 /* Configure PIx pins Output type to push-pull */
1013 GPIOI
->OTYPER
= 0x00000000;
1014 /* No pull-up, pull-down for PIx pins */
1015 GPIOI
->PUPDR
= 0x00000000;
1017 /*-- FMC Configuration ------------------------------------------------------*/
1018 /* Enable the FMC interface clock */
1019 RCC
->AHB3ENR
|= 0x00000001;
1021 /* Configure and enable SDRAM bank1 */
1022 FMC_Bank5_6
->SDCR
[0] = 0x000039D0;
1023 FMC_Bank5_6
->SDTR
[0] = 0x01115351;
1025 /* SDRAM initialization sequence */
1026 /* Clock enable command */
1027 FMC_Bank5_6
->SDCMR
= 0x00000011;
1028 tmpreg
= FMC_Bank5_6
->SDSR
& 0x00000020;
1029 while((tmpreg
!= 0) & (timeout
-- > 0))
1031 tmpreg
= FMC_Bank5_6
->SDSR
& 0x00000020;
1035 for (index
= 0; index
<1000; index
++);
1038 FMC_Bank5_6
->SDCMR
= 0x00000012;
1040 while((tmpreg
!= 0) & (timeout
-- > 0))
1042 tmpreg
= FMC_Bank5_6
->SDSR
& 0x00000020;
1045 /* Auto refresh command */
1046 FMC_Bank5_6
->SDCMR
= 0x00000073;
1048 while((tmpreg
!= 0) & (timeout
-- > 0))
1050 tmpreg
= FMC_Bank5_6
->SDSR
& 0x00000020;
1053 /* MRD register program */
1054 FMC_Bank5_6
->SDCMR
= 0x00046014;
1056 while((tmpreg
!= 0) & (timeout
-- > 0))
1058 tmpreg
= FMC_Bank5_6
->SDSR
& 0x00000020;
1061 /* Set refresh count */
1062 tmpreg
= FMC_Bank5_6
->SDRTR
;
1063 FMC_Bank5_6
->SDRTR
= (tmpreg
| (0x0000027C<<1));
1065 /* Disable write protection */
1066 tmpreg
= FMC_Bank5_6
->SDCR
[0];
1067 FMC_Bank5_6
->SDCR
[0] = (tmpreg
& 0xFFFFFDFF);
1070 Bank1_SDRAM is configured as follow:
1072 FMC_SDRAMTimingInitStructure.FMC_LoadToActiveDelay = 2;
1073 FMC_SDRAMTimingInitStructure.FMC_ExitSelfRefreshDelay = 6;
1074 FMC_SDRAMTimingInitStructure.FMC_SelfRefreshTime = 4;
1075 FMC_SDRAMTimingInitStructure.FMC_RowCycleDelay = 6;
1076 FMC_SDRAMTimingInitStructure.FMC_WriteRecoveryTime = 2;
1077 FMC_SDRAMTimingInitStructure.FMC_RPDelay = 2;
1078 FMC_SDRAMTimingInitStructure.FMC_RCDDelay = 2;
1080 FMC_SDRAMInitStructure.FMC_Bank = SDRAM_BANK;
1081 FMC_SDRAMInitStructure.FMC_ColumnBitsNumber = FMC_ColumnBits_Number_8b;
1082 FMC_SDRAMInitStructure.FMC_RowBitsNumber = FMC_RowBits_Number_11b;
1083 FMC_SDRAMInitStructure.FMC_SDMemoryDataWidth = FMC_SDMemory_Width_16b;
1084 FMC_SDRAMInitStructure.FMC_InternalBankNumber = FMC_InternalBank_Number_4;
1085 FMC_SDRAMInitStructure.FMC_CASLatency = FMC_CAS_Latency_3;
1086 FMC_SDRAMInitStructure.FMC_WriteProtection = FMC_Write_Protection_Disable;
1087 FMC_SDRAMInitStructure.FMC_SDClockPeriod = FMC_SDClock_Period_2;
1088 FMC_SDRAMInitStructure.FMC_ReadBurst = FMC_Read_Burst_disable;
1089 FMC_SDRAMInitStructure.FMC_ReadPipeDelay = FMC_ReadPipe_Delay_1;
1090 FMC_SDRAMInitStructure.FMC_SDRAMTimingStruct = &FMC_SDRAMTimingInitStructure;
1094 #endif /* DATA_IN_ExtSDRAM */
1108 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/