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
318 #include "stm32f4xx.h"
319 #include "drivers/system.h"
320 #include "system_stm32f4xx.h"
321 #include "platform.h"
322 #include "drivers/persistent.h"
329 /** @addtogroup STM32F4xx_System_Private_TypesDefinitions
337 /** @addtogroup STM32F4xx_System_Private_Defines
341 /************************* Miscellaneous Configuration ************************/
342 /*!< Uncomment the following line if you need to use external SRAM or SDRAM mounted
343 on STM324xG_EVAL/STM324x7I_EVAL/STM324x9I_EVAL boards as data memory */
344 #if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx)
345 /* #define DATA_IN_ExtSRAM */
346 #endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx || STM32F469_479xx */
348 #if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
349 /* #define DATA_IN_ExtSDRAM */
350 #endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
352 /*!< Uncomment the following line if you need to relocate your vector Table in
354 #define VECT_TAB_SRAM
355 /******************************************************************************/
361 /** @addtogroup STM32F4xx_System_Private_Macros
369 /** @addtogroup STM32F4xx_System_Private_Variables
373 __I
uint8_t AHBPrescTable
[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
379 /** @addtogroup STM32F4xx_System_Private_FunctionPrototypes
383 void SetSysClock(void);
385 #if defined(DATA_IN_ExtSRAM) || defined(DATA_IN_ExtSDRAM)
386 static void SystemInit_ExtMemCtl(void);
387 #endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
393 /** @addtogroup STM32F4xx_System_Private_Functions
398 * @brief Setup the microcontroller system
399 * Initialize the Embedded Flash Interface, the PLL and update the
400 * SystemFrequency variable.
405 uint32_t SystemCoreClock
;
406 uint32_t pll_src
, pll_input
, pll_m
, pll_p
, pll_n
, pll_q
;
408 // SystemSYSCLKSource
412 // 3: PLLR (F446 only)
414 int SystemSYSCLKSource(void)
416 return (RCC
->CFGR
& RCC_CFGR_SWS
) >> 2;
423 int SystemPLLSource(void)
425 return (RCC
->PLLCFGR
& RCC_PLLCFGR_PLLSRC
) >> 22;
428 typedef struct pllConfig_s
{
429 uint16_t mhz
; // target SYSCLK
435 // PLL parameters for PLL input = 1MHz.
436 // For PLL input = 2MHz, divide n by 2; see SystemInitPLLParameters below.
438 static const pllConfig_t overclockLevels
[] = {
439 #if defined(STM32F40_41xxx)
440 { 168, 336, 2, 7 }, // 168 MHz
441 { 192, 384, 2, 8 }, // 192 MHz
442 { 216, 432, 2, 9 }, // 216 MHz
443 { 240, 480, 2, 10 } // 240 MHz
444 #elif defined(STM32F411xE)
445 { 96, 384, 4, 8 }, // 96 MHz
446 { 108, 432, 4, 9 }, // 108 MHz
447 { 120, 480, 4, 10 }, // 120 MHz
448 #elif defined(STM32F446xx)
449 // Main PLL for F446 is not constrained by USB clock generation,
450 // as we generate it with PLLSAI.
451 // Here, for the moment, we start with default 180MHz and increment in steps of 24MHz.
452 // May be made variable in steps of 1MHz in the future...
453 { 180, 360, 2, 2 }, // 180 MHz
454 { 202, 404, 2, 2 }, // 202 MHz
455 { 226, 452, 2, 2 }, // 226 MHz
456 { 250, 500, 2, 2 }, // 250 MHz, operation not verified
460 #if defined(STM32F446xx)
461 #define PLL_R 7 // PLL_R output is not used, can be any descent number
464 void SystemInitPLLParameters(void)
466 /* PLL setting for overclocking */
468 uint32_t currentOverclockLevel
= persistentObjectRead(PERSISTENT_OBJECT_OVERCLOCK_LEVEL
);
470 if (currentOverclockLevel
>= ARRAYLEN(overclockLevels
)) {
474 const pllConfig_t
* const pll
= overclockLevels
+ currentOverclockLevel
;
476 pll_n
= pll
->n
/ pll_input
;
481 void OverclockRebootIfNecessary(uint32_t overclockLevel
)
483 if (overclockLevel
>= ARRAYLEN(overclockLevels
)) {
487 const pllConfig_t
* const pll
= overclockLevels
+ overclockLevel
;
489 // Reboot to adjust overclock frequency
490 if (SystemCoreClock
!= pll
->mhz
* 1000000U) {
491 persistentObjectWrite(PERSISTENT_OBJECT_OVERCLOCK_LEVEL
, overclockLevel
);
497 void systemClockSetHSEValue(uint32_t frequency
)
499 uint32_t hse_value
= persistentObjectRead(PERSISTENT_OBJECT_HSE_VALUE
);
501 if (hse_value
!= frequency
) {
502 persistentObjectWrite(PERSISTENT_OBJECT_HSE_VALUE
, frequency
);
508 void SystemInit(void)
510 initialiseMemorySections();
512 /* FPU settings ------------------------------------------------------------*/
513 #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
514 SCB
->CPACR
|= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
516 /* Reset the RCC clock configuration to the default reset state ------------*/
518 RCC
->CR
|= (uint32_t)0x00000001;
520 /* Reset CFGR register */
521 RCC
->CFGR
= 0x00000000;
523 /* Reset HSEON, CSSON and PLLON bits */
524 RCC
->CR
&= (uint32_t)0xFEF6FFFF;
526 /* Reset PLLCFGR register */
527 RCC
->PLLCFGR
= 0x24003010;
529 /* Reset HSEBYP bit */
530 RCC
->CR
&= (uint32_t)0xFFFBFFFF;
532 /* Disable all interrupts */
533 RCC
->CIR
= 0x00000000;
535 #if defined(DATA_IN_ExtSRAM) || defined(DATA_IN_ExtSDRAM)
536 SystemInit_ExtMemCtl();
537 #endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
539 /* Configure the System clock source, PLL Multiplier and Divider factors,
540 AHB/APBx prescalers and Flash settings ----------------------------------*/
543 /* Configure the Vector Table location add offset address ------------------*/
546 // Copy vector table from isr_vector_table_flash_base to isr_vector_table_base.
547 // If these two regions are the same, the copy will have no effect
548 // (Happens when linker script aliases VECTAB to FLASH).
550 extern uint8_t isr_vector_table_flash_base
;
551 extern uint8_t isr_vector_table_base
;
552 extern uint8_t isr_vector_table_end
;
554 memcpy(&isr_vector_table_base
, &isr_vector_table_flash_base
, &isr_vector_table_end
- &isr_vector_table_base
);
555 SCB
->VTOR
= (uint32_t)&isr_vector_table_base
;
557 SCB
->VTOR
= (uint32_t)&isr_vector_table_flash_base
;
560 #ifdef USE_HAL_DRIVER
564 SystemCoreClockUpdate();
568 * @brief Update SystemCoreClock variable according to Clock Register Values.
569 * The SystemCoreClock variable contains the core clock (HCLK), it can
570 * be used by the user application to setup the SysTick timer or configure
573 * @note Each time the core clock (HCLK) changes, this function must be called
574 * to update SystemCoreClock variable value. Otherwise, any configuration
575 * based on this variable will be incorrect.
577 * @note - The system frequency computed by this function is not the real
578 * frequency in the chip. It is calculated based on the predefined
579 * constant and the selected clock source:
581 * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
583 * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
585 * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
586 * or HSI_VALUE(*) multiplied/divided by the PLL factors.
588 * (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value
589 * 16 MHz) but the real value may vary depending on the variations
590 * in voltage and temperature.
592 * (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value
593 * 25 MHz), user has to ensure that HSE_VALUE is same as the real
594 * frequency of the crystal used. Otherwise, this function may
597 * - The result of this function could be not correct when using fractional
598 * value for HSE crystal.
603 void SystemCoreClockUpdate(void)
605 uint32_t hse_value
= persistentObjectRead(PERSISTENT_OBJECT_HSE_VALUE
);
607 uint32_t tmp
= 0, pllvco
= 0, pllp
= 2, pllsource
= 0, pllm
= 2;
608 #if defined(STM32F446xx)
610 #endif /* STM32F446xx */
611 /* Get SYSCLK source -------------------------------------------------------*/
612 tmp
= RCC
->CFGR
& RCC_CFGR_SWS
;
616 case 0x00: /* HSI used as system clock source */
617 SystemCoreClock
= HSI_VALUE
;
619 case 0x04: /* HSE used as system clock source */
620 SystemCoreClock
= hse_value
;
622 case 0x08: /* PLL P used as system clock source */
623 /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
624 SYSCLK = PLL_VCO / PLL_P
626 pllsource
= (RCC
->PLLCFGR
& RCC_PLLCFGR_PLLSRC
) >> 22;
627 pllm
= RCC
->PLLCFGR
& RCC_PLLCFGR_PLLM
;
631 /* HSE used as PLL clock source */
632 pllvco
= (hse_value
/ pllm
) * ((RCC
->PLLCFGR
& RCC_PLLCFGR_PLLN
) >> 6);
636 /* HSI used as PLL clock source */
637 pllvco
= (HSI_VALUE
/ pllm
) * ((RCC
->PLLCFGR
& RCC_PLLCFGR_PLLN
) >> 6);
640 pllp
= (((RCC
->PLLCFGR
& RCC_PLLCFGR_PLLP
) >>16) + 1 ) *2;
641 SystemCoreClock
= pllvco
/pllp
;
643 #if defined(STM32F446xx)
644 case 0x0C: /* PLL R used as system clock source */
645 /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
646 SYSCLK = PLL_VCO / PLL_R
648 pllsource
= (RCC
->PLLCFGR
& RCC_PLLCFGR_PLLSRC
) >> 22;
649 pllm
= RCC
->PLLCFGR
& RCC_PLLCFGR_PLLM
;
652 /* HSE used as PLL clock source */
653 pllvco
= (hse_value
/ pllm
) * ((RCC
->PLLCFGR
& RCC_PLLCFGR_PLLN
) >> 6);
657 /* HSI used as PLL clock source */
658 pllvco
= (HSI_VALUE
/ pllm
) * ((RCC
->PLLCFGR
& RCC_PLLCFGR_PLLN
) >> 6);
661 pllr
= (((RCC
->PLLCFGR
& RCC_PLLCFGR_PLLR
) >>28) + 1 ) *2;
662 SystemCoreClock
= pllvco
/pllr
;
664 #endif /* STM32F446xx */
666 SystemCoreClock
= HSI_VALUE
;
671 static int StartHSx(uint32_t onBit
, uint32_t readyBit
, int maxWaitCount
)
674 for (int waitCounter
= 0 ; waitCounter
< maxWaitCount
; waitCounter
++) {
675 if (RCC
->CR
& readyBit
) {
683 * @brief Configures the System clock source, PLL Multiplier and Divider factors,
684 * AHB/APBx prescalers and Flash settings
685 * @Note This function should be called only once the RCC clock configuration
686 * is reset to the default reset state (done in SystemInit() function).
690 void SetSysClock(void)
692 uint32_t hse_value
= persistentObjectRead(PERSISTENT_OBJECT_HSE_VALUE
);
693 uint32_t hse_mhz
= hse_value
/ 1000000;
695 // Switch to HSI during clock manipulation
697 RCC
->CFGR
= (RCC
->CFGR
& ~RCC_CFGR_SW
) | RCC_CFGR_SW_HSI
;
698 while ((RCC
->CFGR
& (uint32_t)RCC_CFGR_SWS
) != RCC_CFGR_SWS_HSI
);
700 // We want to use 2MHz input to PLL, as it will provide greater
701 // flexibility in choice of PLL_N and compatible with generation
702 // of 48MHz for USB requirement at the same time.
704 // Here, if the frequency (in MHz) is multiples of 2, then pll_m is
705 // set to a value that derives 2MHz as input to PLL.
706 // Otherwise, pll_m is set to the frequency (in MHz) to derive
707 // 1MHz as input to PLL.
709 if (hse_value
== 0) {
710 // HSE frequency unknown; use PLL with HSI as source
711 if (!StartHSx(RCC_CR_HSION
, RCC_CR_HSIRDY
, 5000)) {
715 pll_src
= RCC_PLLCFGR_PLLSRC_HSI
;
717 // HSI is fixed at 16MHz.
721 // HSE frequency is given.
723 if (!StartHSx(RCC_CR_HSEON
, RCC_CR_HSERDY
, 5000)) {
727 pll_src
= RCC_PLLCFGR_PLLSRC_HSE
;
730 if (pll_m
* 2 != hse_mhz
) {
733 pll_input
= hse_mhz
/ pll_m
;
736 SystemInitPLLParameters();
738 /* Select regulator voltage output Scale 1 mode */
739 RCC
->APB1ENR
|= RCC_APB1ENR_PWREN
;
740 PWR
->CR
|= PWR_CR_VOS
;
742 /* HCLK = SYSCLK / 1*/
743 RCC
->CFGR
|= RCC_CFGR_HPRE_DIV1
;
745 #if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
746 /* PCLK2 = HCLK / 2*/
747 RCC
->CFGR
|= RCC_CFGR_PPRE2_DIV2
;
749 /* PCLK1 = HCLK / 4*/
750 RCC
->CFGR
|= RCC_CFGR_PPRE1_DIV4
;
751 #endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
753 #if defined(STM32F401xx)
754 /* PCLK2 = HCLK / 2*/
755 RCC
->CFGR
|= RCC_CFGR_PPRE2_DIV1
;
757 /* PCLK1 = HCLK / 4*/
758 RCC
->CFGR
|= RCC_CFGR_PPRE1_DIV2
;
759 #endif /* STM32F401xx */
761 #if defined(STM32F410xx) || defined(STM32F411xE)
762 /* PCLK2 = HCLK / 2*/
763 RCC
->CFGR
|= RCC_CFGR_PPRE2_DIV1
;
765 /* PCLK1 = HCLK / 4*/
766 RCC
->CFGR
|= RCC_CFGR_PPRE1_DIV2
;
767 #endif /* STM32F410xx || STM32F411xE */
769 #if defined(STM32F446xx)
770 /* Configure the main PLL */
771 RCC
->PLLCFGR
= pll_m
| (pll_n
<< 6) | (((pll_p
>> 1) -1) << 16) |
772 (pll_src
) | (pll_q
<< 24) | (PLL_R
<< 28);
774 /* Configure the main PLL */
775 RCC
->PLLCFGR
= pll_m
| (pll_n
<< 6) | (((pll_p
>> 1) -1) << 16) |
776 (pll_src
) | (pll_q
<< 24);
777 #endif /* STM32F446xx */
779 /* Enable the main PLL */
780 RCC
->CR
|= RCC_CR_PLLON
;
782 /* Wait till the main PLL is ready */
783 while ((RCC
->CR
& RCC_CR_PLLRDY
) == 0)
787 #if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
788 /* Enable the Over-drive to extend the clock frequency to 180 Mhz */
789 PWR
->CR
|= PWR_CR_ODEN
;
790 while ((PWR
->CSR
& PWR_CSR_ODRDY
) == 0)
793 PWR
->CR
|= PWR_CR_ODSWEN
;
794 while ((PWR
->CSR
& PWR_CSR_ODSWRDY
) == 0)
797 #endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
799 #if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
800 /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
801 FLASH
->ACR
= FLASH_ACR_PRFTEN
| FLASH_ACR_ICEN
|FLASH_ACR_DCEN
|FLASH_ACR_LATENCY_5WS
;
802 #endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
804 #if defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE)
805 /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
806 FLASH
->ACR
= FLASH_ACR_PRFTEN
| FLASH_ACR_ICEN
|FLASH_ACR_DCEN
|FLASH_ACR_LATENCY_2WS
;
807 #endif /* STM32F401xx || STM32F410xx || STM32F411xE*/
809 /* Select the main PLL as system clock source */
810 RCC
->CFGR
&= (uint32_t)((uint32_t)~(RCC_CFGR_SW
));
811 RCC
->CFGR
|= RCC_CFGR_SW_PLL
;
813 /* Wait till the main PLL is used as system clock source */
814 while ((RCC
->CFGR
& (uint32_t)RCC_CFGR_SWS
) != RCC_CFGR_SWS_PLL
);
818 #if defined(STM32F446xx)
819 // Always use PLLSAI to derive USB 48MHz clock.
820 // - This also works under arbitral overclocking situations.
821 // - Only handles HSE case.
825 #ifdef TARGET_XTAL_MHZ
826 #define PLLSAI_M TARGET_XTAL_MHZ
834 #define RCC_PLLSAI_IS_READY() ((RCC->CR & (RCC_CR_PLLSAIRDY)) == (RCC_CR_PLLSAIRDY))
836 // Scale PLLSAI input to 1MHz.
838 pllsai_m
= hse_value
/ 1000000U;
843 // Set 48MHz clock source
844 RCC_48MHzClockSourceConfig(RCC_48MHZCLKSource_PLLSAI
);
847 RCC_PLLSAICmd(DISABLE
);
849 // wait for PLLSAI to be disabled
850 while (RCC_PLLSAI_IS_READY()) {}
852 RCC_PLLSAIConfig(pllsai_m
, PLLSAI_N
, PLLSAI_P
, PLLSAI_Q
);
854 RCC_PLLSAICmd(ENABLE
);
856 // wait for PLLSAI to be enabled
857 while (!RCC_PLLSAI_IS_READY()) {}
859 RCC
->DCKCFGR2
|= RCC_DCKCFGR2_CK48MSEL
;
861 #undef RCC_PLLSAI_GET_FLAG
862 #endif /* STM32F446xx */
864 // Configure PLLI2S for 27MHz operation
865 // Use pll_input (1 or 2) to derive multiplier N for
866 // 108MHz (27 * 4) PLLI2SCLK with R divider fixed at 2.
867 // 108MHz will further be prescaled by 4 by mcoInit.
869 #define PLLI2S_TARGET_FREQ_MHZ (27 * 4)
872 uint32_t plli2s_n
= (PLLI2S_TARGET_FREQ_MHZ
* PLLI2S_R
) / pll_input
;
874 #ifdef STM32F40_41xxx
875 RCC_PLLI2SConfig(plli2s_n
, PLLI2S_R
);
876 #elif defined(STM32F411xE)
877 RCC_PLLI2SConfig(plli2s_n
, PLLI2S_R
, pll_m
);
878 #elif defined(STM32F446xx)
879 RCC_PLLI2SConfig(pll_m
, plli2s_n
, 2, 2, PLLI2S_R
); // M, N, P, Q, R
881 #error Unsupported MCU
884 RCC_PLLI2SCmd(ENABLE
);
886 SystemCoreClockUpdate();
890 * @brief Setup the external memory controller. Called in startup_stm32f4xx.s
891 * before jump to __main
895 #ifdef DATA_IN_ExtSRAM
897 * @brief Setup the external memory controller.
898 * Called in startup_stm32f4xx.s before jump to main.
899 * This function configures the external SRAM mounted on STM324xG_EVAL/STM324x7I boards
900 * This SRAM will be used as program data memory (including heap and stack).
904 void SystemInit_ExtMemCtl(void)
906 /*-- GPIOs Configuration -----------------------------------------------------*/
908 +-------------------+--------------------+------------------+--------------+
909 + SRAM pins assignment +
910 +-------------------+--------------------+------------------+--------------+
911 | PD0 <-> FMC_D2 | PE0 <-> FMC_NBL0 | PF0 <-> FMC_A0 | PG0 <-> FMC_A10 |
912 | PD1 <-> FMC_D3 | PE1 <-> FMC_NBL1 | PF1 <-> FMC_A1 | PG1 <-> FMC_A11 |
913 | PD4 <-> FMC_NOE | PE3 <-> FMC_A19 | PF2 <-> FMC_A2 | PG2 <-> FMC_A12 |
914 | PD5 <-> FMC_NWE | PE4 <-> FMC_A20 | PF3 <-> FMC_A3 | PG3 <-> FMC_A13 |
915 | PD8 <-> FMC_D13 | PE7 <-> FMC_D4 | PF4 <-> FMC_A4 | PG4 <-> FMC_A14 |
916 | PD9 <-> FMC_D14 | PE8 <-> FMC_D5 | PF5 <-> FMC_A5 | PG5 <-> FMC_A15 |
917 | PD10 <-> FMC_D15 | PE9 <-> FMC_D6 | PF12 <-> FMC_A6 | PG9 <-> FMC_NE2 |
918 | PD11 <-> FMC_A16 | PE10 <-> FMC_D7 | PF13 <-> FMC_A7 |-----------------+
919 | PD12 <-> FMC_A17 | PE11 <-> FMC_D8 | PF14 <-> FMC_A8 |
920 | PD13 <-> FMC_A18 | PE12 <-> FMC_D9 | PF15 <-> FMC_A9 |
921 | PD14 <-> FMC_D0 | PE13 <-> FMC_D10 |-----------------+
922 | PD15 <-> FMC_D1 | PE14 <-> FMC_D11 |
923 | | PE15 <-> FMC_D12 |
924 +------------------+------------------+
926 /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */
927 RCC
->AHB1ENR
|= 0x00000078;
929 /* Connect PDx pins to FMC Alternate function */
930 GPIOD
->AFR
[0] = 0x00cc00cc;
931 GPIOD
->AFR
[1] = 0xcccccccc;
932 /* Configure PDx pins in Alternate function mode */
933 GPIOD
->MODER
= 0xaaaa0a0a;
934 /* Configure PDx pins speed to 100 MHz */
935 GPIOD
->OSPEEDR
= 0xffff0f0f;
936 /* Configure PDx pins Output type to push-pull */
937 GPIOD
->OTYPER
= 0x00000000;
938 /* No pull-up, pull-down for PDx pins */
939 GPIOD
->PUPDR
= 0x00000000;
941 /* Connect PEx pins to FMC Alternate function */
942 GPIOE
->AFR
[0] = 0xcccccccc;
943 GPIOE
->AFR
[1] = 0xcccccccc;
944 /* Configure PEx pins in Alternate function mode */
945 GPIOE
->MODER
= 0xaaaaaaaa;
946 /* Configure PEx pins speed to 100 MHz */
947 GPIOE
->OSPEEDR
= 0xffffffff;
948 /* Configure PEx pins Output type to push-pull */
949 GPIOE
->OTYPER
= 0x00000000;
950 /* No pull-up, pull-down for PEx pins */
951 GPIOE
->PUPDR
= 0x00000000;
953 /* Connect PFx pins to FMC Alternate function */
954 GPIOF
->AFR
[0] = 0x00cccccc;
955 GPIOF
->AFR
[1] = 0xcccc0000;
956 /* Configure PFx pins in Alternate function mode */
957 GPIOF
->MODER
= 0xaa000aaa;
958 /* Configure PFx pins speed to 100 MHz */
959 GPIOF
->OSPEEDR
= 0xff000fff;
960 /* Configure PFx pins Output type to push-pull */
961 GPIOF
->OTYPER
= 0x00000000;
962 /* No pull-up, pull-down for PFx pins */
963 GPIOF
->PUPDR
= 0x00000000;
965 /* Connect PGx pins to FMC Alternate function */
966 GPIOG
->AFR
[0] = 0x00cccccc;
967 GPIOG
->AFR
[1] = 0x000000c0;
968 /* Configure PGx pins in Alternate function mode */
969 GPIOG
->MODER
= 0x00080aaa;
970 /* Configure PGx pins speed to 100 MHz */
971 GPIOG
->OSPEEDR
= 0x000c0fff;
972 /* Configure PGx pins Output type to push-pull */
973 GPIOG
->OTYPER
= 0x00000000;
974 /* No pull-up, pull-down for PGx pins */
975 GPIOG
->PUPDR
= 0x00000000;
977 /*-- FMC Configuration ------------------------------------------------------*/
978 /* Enable the FMC/FSMC interface clock */
979 RCC
->AHB3ENR
|= 0x00000001;
981 #if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
982 /* Configure and enable Bank1_SRAM2 */
983 FMC_Bank1
->BTCR
[2] = 0x00001011;
984 FMC_Bank1
->BTCR
[3] = 0x00000201;
985 FMC_Bank1E
->BWTR
[2] = 0x0fffffff;
986 #endif /* STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
988 #if defined(STM32F40_41xxx)
989 /* Configure and enable Bank1_SRAM2 */
990 FSMC_Bank1
->BTCR
[2] = 0x00001011;
991 FSMC_Bank1
->BTCR
[3] = 0x00000201;
992 FSMC_Bank1E
->BWTR
[2] = 0x0fffffff;
993 #endif /* STM32F40_41xxx */
996 Bank1_SRAM2 is configured as follow:
997 In case of FSMC configuration
998 NORSRAMTimingStructure.FSMC_AddressSetupTime = 1;
999 NORSRAMTimingStructure.FSMC_AddressHoldTime = 0;
1000 NORSRAMTimingStructure.FSMC_DataSetupTime = 2;
1001 NORSRAMTimingStructure.FSMC_BusTurnAroundDuration = 0;
1002 NORSRAMTimingStructure.FSMC_CLKDivision = 0;
1003 NORSRAMTimingStructure.FSMC_DataLatency = 0;
1004 NORSRAMTimingStructure.FSMC_AccessMode = FMC_AccessMode_A;
1006 FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM2;
1007 FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable;
1008 FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_SRAM;
1009 FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b;
1010 FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
1011 FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable;
1012 FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
1013 FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable;
1014 FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
1015 FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable;
1016 FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable;
1017 FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
1018 FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable;
1019 FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &NORSRAMTimingStructure;
1020 FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &NORSRAMTimingStructure;
1022 In case of FMC configuration
1023 NORSRAMTimingStructure.FMC_AddressSetupTime = 1;
1024 NORSRAMTimingStructure.FMC_AddressHoldTime = 0;
1025 NORSRAMTimingStructure.FMC_DataSetupTime = 2;
1026 NORSRAMTimingStructure.FMC_BusTurnAroundDuration = 0;
1027 NORSRAMTimingStructure.FMC_CLKDivision = 0;
1028 NORSRAMTimingStructure.FMC_DataLatency = 0;
1029 NORSRAMTimingStructure.FMC_AccessMode = FMC_AccessMode_A;
1031 FMC_NORSRAMInitStructure.FMC_Bank = FMC_Bank1_NORSRAM2;
1032 FMC_NORSRAMInitStructure.FMC_DataAddressMux = FMC_DataAddressMux_Disable;
1033 FMC_NORSRAMInitStructure.FMC_MemoryType = FMC_MemoryType_SRAM;
1034 FMC_NORSRAMInitStructure.FMC_MemoryDataWidth = FMC_MemoryDataWidth_16b;
1035 FMC_NORSRAMInitStructure.FMC_BurstAccessMode = FMC_BurstAccessMode_Disable;
1036 FMC_NORSRAMInitStructure.FMC_AsynchronousWait = FMC_AsynchronousWait_Disable;
1037 FMC_NORSRAMInitStructure.FMC_WaitSignalPolarity = FMC_WaitSignalPolarity_Low;
1038 FMC_NORSRAMInitStructure.FMC_WrapMode = FMC_WrapMode_Disable;
1039 FMC_NORSRAMInitStructure.FMC_WaitSignalActive = FMC_WaitSignalActive_BeforeWaitState;
1040 FMC_NORSRAMInitStructure.FMC_WriteOperation = FMC_WriteOperation_Enable;
1041 FMC_NORSRAMInitStructure.FMC_WaitSignal = FMC_WaitSignal_Disable;
1042 FMC_NORSRAMInitStructure.FMC_ExtendedMode = FMC_ExtendedMode_Disable;
1043 FMC_NORSRAMInitStructure.FMC_WriteBurst = FMC_WriteBurst_Disable;
1044 FMC_NORSRAMInitStructure.FMC_ContinousClock = FMC_CClock_SyncOnly;
1045 FMC_NORSRAMInitStructure.FMC_ReadWriteTimingStruct = &NORSRAMTimingStructure;
1046 FMC_NORSRAMInitStructure.FMC_WriteTimingStruct = &NORSRAMTimingStructure;
1050 #endif /* DATA_IN_ExtSRAM */
1052 #ifdef DATA_IN_ExtSDRAM
1054 * @brief Setup the external memory controller.
1055 * Called in startup_stm32f4xx.s before jump to main.
1056 * This function configures the external SDRAM mounted on STM324x9I_EVAL board
1057 * This SDRAM will be used as program data memory (including heap and stack).
1061 void SystemInit_ExtMemCtl(void)
1063 register uint32_t tmpreg
= 0, timeout
= 0xFFFF;
1064 register uint32_t index
;
1066 /* Enable GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH and GPIOI interface
1068 RCC
->AHB1ENR
|= 0x000001FC;
1070 /* Connect PCx pins to FMC Alternate function */
1071 GPIOC
->AFR
[0] = 0x0000000c;
1072 GPIOC
->AFR
[1] = 0x00007700;
1073 /* Configure PCx pins in Alternate function mode */
1074 GPIOC
->MODER
= 0x00a00002;
1075 /* Configure PCx pins speed to 50 MHz */
1076 GPIOC
->OSPEEDR
= 0x00a00002;
1077 /* Configure PCx pins Output type to push-pull */
1078 GPIOC
->OTYPER
= 0x00000000;
1079 /* No pull-up, pull-down for PCx pins */
1080 GPIOC
->PUPDR
= 0x00500000;
1082 /* Connect PDx pins to FMC Alternate function */
1083 GPIOD
->AFR
[0] = 0x000000CC;
1084 GPIOD
->AFR
[1] = 0xCC000CCC;
1085 /* Configure PDx pins in Alternate function mode */
1086 GPIOD
->MODER
= 0xA02A000A;
1087 /* Configure PDx pins speed to 50 MHz */
1088 GPIOD
->OSPEEDR
= 0xA02A000A;
1089 /* Configure PDx pins Output type to push-pull */
1090 GPIOD
->OTYPER
= 0x00000000;
1091 /* No pull-up, pull-down for PDx pins */
1092 GPIOD
->PUPDR
= 0x00000000;
1094 /* Connect PEx pins to FMC Alternate function */
1095 GPIOE
->AFR
[0] = 0xC00000CC;
1096 GPIOE
->AFR
[1] = 0xCCCCCCCC;
1097 /* Configure PEx pins in Alternate function mode */
1098 GPIOE
->MODER
= 0xAAAA800A;
1099 /* Configure PEx pins speed to 50 MHz */
1100 GPIOE
->OSPEEDR
= 0xAAAA800A;
1101 /* Configure PEx pins Output type to push-pull */
1102 GPIOE
->OTYPER
= 0x00000000;
1103 /* No pull-up, pull-down for PEx pins */
1104 GPIOE
->PUPDR
= 0x00000000;
1106 /* Connect PFx pins to FMC Alternate function */
1107 GPIOF
->AFR
[0] = 0xcccccccc;
1108 GPIOF
->AFR
[1] = 0xcccccccc;
1109 /* Configure PFx pins in Alternate function mode */
1110 GPIOF
->MODER
= 0xAA800AAA;
1111 /* Configure PFx pins speed to 50 MHz */
1112 GPIOF
->OSPEEDR
= 0xAA800AAA;
1113 /* Configure PFx pins Output type to push-pull */
1114 GPIOF
->OTYPER
= 0x00000000;
1115 /* No pull-up, pull-down for PFx pins */
1116 GPIOF
->PUPDR
= 0x00000000;
1118 /* Connect PGx pins to FMC Alternate function */
1119 GPIOG
->AFR
[0] = 0xcccccccc;
1120 GPIOG
->AFR
[1] = 0xcccccccc;
1121 /* Configure PGx pins in Alternate function mode */
1122 GPIOG
->MODER
= 0xaaaaaaaa;
1123 /* Configure PGx pins speed to 50 MHz */
1124 GPIOG
->OSPEEDR
= 0xaaaaaaaa;
1125 /* Configure PGx pins Output type to push-pull */
1126 GPIOG
->OTYPER
= 0x00000000;
1127 /* No pull-up, pull-down for PGx pins */
1128 GPIOG
->PUPDR
= 0x00000000;
1130 /* Connect PHx pins to FMC Alternate function */
1131 GPIOH
->AFR
[0] = 0x00C0CC00;
1132 GPIOH
->AFR
[1] = 0xCCCCCCCC;
1133 /* Configure PHx pins in Alternate function mode */
1134 GPIOH
->MODER
= 0xAAAA08A0;
1135 /* Configure PHx pins speed to 50 MHz */
1136 GPIOH
->OSPEEDR
= 0xAAAA08A0;
1137 /* Configure PHx pins Output type to push-pull */
1138 GPIOH
->OTYPER
= 0x00000000;
1139 /* No pull-up, pull-down for PHx pins */
1140 GPIOH
->PUPDR
= 0x00000000;
1142 /* Connect PIx pins to FMC Alternate function */
1143 GPIOI
->AFR
[0] = 0xCCCCCCCC;
1144 GPIOI
->AFR
[1] = 0x00000CC0;
1145 /* Configure PIx pins in Alternate function mode */
1146 GPIOI
->MODER
= 0x0028AAAA;
1147 /* Configure PIx pins speed to 50 MHz */
1148 GPIOI
->OSPEEDR
= 0x0028AAAA;
1149 /* Configure PIx pins Output type to push-pull */
1150 GPIOI
->OTYPER
= 0x00000000;
1151 /* No pull-up, pull-down for PIx pins */
1152 GPIOI
->PUPDR
= 0x00000000;
1154 /*-- FMC Configuration ------------------------------------------------------*/
1155 /* Enable the FMC interface clock */
1156 RCC
->AHB3ENR
|= 0x00000001;
1158 /* Configure and enable SDRAM bank1 */
1159 FMC_Bank5_6
->SDCR
[0] = 0x000039D0;
1160 FMC_Bank5_6
->SDTR
[0] = 0x01115351;
1162 /* SDRAM initialization sequence */
1163 /* Clock enable command */
1164 FMC_Bank5_6
->SDCMR
= 0x00000011;
1165 tmpreg
= FMC_Bank5_6
->SDSR
& 0x00000020;
1166 while ((tmpreg
!= 0) & (timeout
-- > 0))
1168 tmpreg
= FMC_Bank5_6
->SDSR
& 0x00000020;
1172 for (index
= 0; index
<1000; index
++);
1175 FMC_Bank5_6
->SDCMR
= 0x00000012;
1177 while ((tmpreg
!= 0) & (timeout
-- > 0))
1179 tmpreg
= FMC_Bank5_6
->SDSR
& 0x00000020;
1182 /* Auto refresh command */
1183 FMC_Bank5_6
->SDCMR
= 0x00000073;
1185 while ((tmpreg
!= 0) & (timeout
-- > 0))
1187 tmpreg
= FMC_Bank5_6
->SDSR
& 0x00000020;
1190 /* MRD register program */
1191 FMC_Bank5_6
->SDCMR
= 0x00046014;
1193 while ((tmpreg
!= 0) & (timeout
-- > 0))
1195 tmpreg
= FMC_Bank5_6
->SDSR
& 0x00000020;
1198 /* Set refresh count */
1199 tmpreg
= FMC_Bank5_6
->SDRTR
;
1200 FMC_Bank5_6
->SDRTR
= (tmpreg
| (0x0000027C<<1));
1202 /* Disable write protection */
1203 tmpreg
= FMC_Bank5_6
->SDCR
[0];
1204 FMC_Bank5_6
->SDCR
[0] = (tmpreg
& 0xFFFFFDFF);
1207 Bank1_SDRAM is configured as follow:
1209 FMC_SDRAMTimingInitStructure.FMC_LoadToActiveDelay = 2;
1210 FMC_SDRAMTimingInitStructure.FMC_ExitSelfRefreshDelay = 6;
1211 FMC_SDRAMTimingInitStructure.FMC_SelfRefreshTime = 4;
1212 FMC_SDRAMTimingInitStructure.FMC_RowCycleDelay = 6;
1213 FMC_SDRAMTimingInitStructure.FMC_WriteRecoveryTime = 2;
1214 FMC_SDRAMTimingInitStructure.FMC_RPDelay = 2;
1215 FMC_SDRAMTimingInitStructure.FMC_RCDDelay = 2;
1217 FMC_SDRAMInitStructure.FMC_Bank = SDRAM_BANK;
1218 FMC_SDRAMInitStructure.FMC_ColumnBitsNumber = FMC_ColumnBits_Number_8b;
1219 FMC_SDRAMInitStructure.FMC_RowBitsNumber = FMC_RowBits_Number_11b;
1220 FMC_SDRAMInitStructure.FMC_SDMemoryDataWidth = FMC_SDMemory_Width_16b;
1221 FMC_SDRAMInitStructure.FMC_InternalBankNumber = FMC_InternalBank_Number_4;
1222 FMC_SDRAMInitStructure.FMC_CASLatency = FMC_CAS_Latency_3;
1223 FMC_SDRAMInitStructure.FMC_WriteProtection = FMC_Write_Protection_Disable;
1224 FMC_SDRAMInitStructure.FMC_SDClockPeriod = FMC_SDClock_Period_2;
1225 FMC_SDRAMInitStructure.FMC_ReadBurst = FMC_Read_Burst_disable;
1226 FMC_SDRAMInitStructure.FMC_ReadPipeDelay = FMC_ReadPipe_Delay_1;
1227 FMC_SDRAMInitStructure.FMC_SDRAMTimingStruct = &FMC_SDRAMTimingInitStructure;
1231 #endif /* DATA_IN_ExtSDRAM */
1245 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/