Refactor missing prototypes 2 (#14170)
[betaflight.git] / src / platform / STM32 / startup / system_stm32h7xx.c
blob809bbea326d3693a2ae0a461b728364ee62ab27c
1 // This module contains initialization code specific to STM32H7 MCUs.
2 // It configures the RCC peripheral (system clocks) including scalars, and
3 // enables RCC clocks for peripherals.
5 /**
6 ******************************************************************************
7 * @file system_stm32h7xx.c
8 * @author MCD Application Team
9 * @brief CMSIS Cortex-Mx Device Peripheral Access Layer System Source File.
11 * This file provides two functions and one global variable to be called from
12 * user application:
13 * - SystemInit(): This function is called at startup just after reset and
14 * before branch to main program. This call is made inside
15 * the "startup_stm32h7xx.s" file.
17 * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
18 * by the user application to setup the SysTick
19 * timer or configure other parameters.
21 * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
22 * be called whenever the core clock is changed
23 * during program execution.
26 ******************************************************************************
27 * @attention
29 * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
31 * Redistribution and use in source and binary forms, with or without modification,
32 * are permitted provided that the following conditions are met:
33 * 1. Redistributions of source code must retain the above copyright notice,
34 * this list of conditions and the following disclaimer.
35 * 2. Redistributions in binary form must reproduce the above copyright notice,
36 * this list of conditions and the following disclaimer in the documentation
37 * and/or other materials provided with the distribution.
38 * 3. Neither the name of STMicroelectronics nor the names of its contributors
39 * may be used to endorse or promote products derived from this software
40 * without specific prior written permission.
42 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
43 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
44 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
45 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
46 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
47 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
48 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
49 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
50 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
51 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
53 ******************************************************************************
56 /** @addtogroup CMSIS
57 * @{
60 /** @addtogroup stm32h7xx_system
61 * @{
64 /** @addtogroup STM32H7xx_System_Private_Includes
65 * @{
68 #include <string.h>
70 #include "platform.h"
72 #include "common/utils.h"
74 #include "build/debug.h"
76 #include "drivers/memprot.h"
77 #include "drivers/system.h"
79 #include "system_stm32f7xx.h"
81 #define HSI_FREQ ((uint32_t)64000000) // Frequency of HSI is 64Mhz on all H7 variants.
83 // If `HSE_VALUE` isn't specified, use HSI. This allows HSI to be selected as the PLL source
84 // later in this file, and adjusts PLL scalers to use the HSI's frequency as the timing source.
85 #if !defined (HSE_VALUE)
86 #define PLL_SRC RCC_PLLSOURCE_HSI
87 #define PLL_SRC_FREQ HSI_FREQ
88 #else
89 #define PLL_SRC RCC_PLLSOURCE_HSE
90 #define PLL_SRC_FREQ HSE_VALUE
91 #endif
93 #if !defined (CSI_VALUE)
94 #define CSI_VALUE ((uint32_t)4000000) /*!< Value of the Internal oscillator in Hz*/
95 #endif /* CSI_VALUE */
97 /**
98 * @}
101 /** @addtogroup STM32H7xx_System_Private_TypesDefinitions
102 * @{
106 * @}
109 /** @addtogroup STM32H7xx_System_Private_Defines
110 * @{
113 /************************* Miscellaneous Configuration ************************/
114 /*!< Uncomment the following line if you need to use external SRAM or SDRAM mounted
115 on EVAL board as data memory */
116 /*#define DATA_IN_ExtSRAM */
117 /*#define DATA_IN_ExtSDRAM*/
119 #if defined(DATA_IN_ExtSRAM) && defined(DATA_IN_ExtSDRAM)
120 #error "Please select DATA_IN_ExtSRAM or DATA_IN_ExtSDRAM "
121 #endif /* DATA_IN_ExtSRAM && DATA_IN_ExtSDRAM */
123 /*!< Uncomment the following line if you need to relocate your vector Table in
124 Internal SRAM. */
125 /* #define VECT_TAB_SRAM */
126 #define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field.
127 This value must be a multiple of 0x200. */
128 /******************************************************************************/
131 * @}
134 /** @addtogroup STM32H7xx_System_Private_Macros
135 * @{
139 * @}
142 /** @addtogroup STM32H7xx_System_Private_Variables
143 * @{
145 /* This variable is updated in three ways:
146 1) by calling CMSIS function SystemCoreClockUpdate()
147 2) by calling HAL API function HAL_RCC_GetHCLKFreq()
148 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
149 Note: If you use this function to configure the system clock; then there
150 is no need to call the 2 first functions listed above, since SystemCoreClock
151 variable is updated automatically.
153 uint32_t SystemCoreClock = 64000000;
154 uint32_t SystemD2Clock = 64000000;
155 const uint8_t D1CorePrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};
158 * @}
161 /** @addtogroup STM32H7xx_System_Private_FunctionPrototypes
162 * @{
164 #if defined(DATA_IN_ExtSRAM) || defined(DATA_IN_ExtSDRAM)
165 static void SystemInit_ExtMemCtl(void);
166 #endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
169 * @}
172 /** @addtogroup STM32H7xx_System_Private_Functions
173 * @{
176 static void ErrorHandler(void)
178 while (1);
181 static void HandleStuckSysTick(void)
183 uint32_t tickStart = HAL_GetTick();
184 uint32_t tickEnd = 0;
186 // H7 at 480Mhz requires a loop count of 160000. Double this for the timeout to be safe.
187 int attemptsRemaining = 320000;
188 while (((tickEnd = HAL_GetTick()) == tickStart) && --attemptsRemaining) {
191 if (tickStart == tickEnd) {
192 systemResetWithoutDisablingCaches();
196 typedef struct pllConfig_s {
197 uint16_t clockMhz;
198 uint8_t m;
199 uint16_t n;
200 uint8_t p;
201 uint8_t q;
202 uint8_t r;
203 uint32_t vos;
204 uint32_t vciRange;
205 } pllConfig_t;
207 #if defined(STM32H743xx) || defined(STM32H750xx)
209 PLL1 configuration for different silicon revisions of H743 and H750.
211 Note for future overclocking support.
213 - Rev.Y (and Rev.X), nominal max at 400MHz, runs stably overclocked to 480MHz.
214 - Rev.V, nominal max at 480MHz, runs stably at 540MHz, but not to 600MHz (VCO probably out of operating range)
216 - A possible frequency table would look something like this, and a revision
217 check logic would place a cap for Rev.Y and V.
219 400 420 440 460 (Rev.Y & V ends here) 480 500 520 540
222 // 400MHz for Rev.Y (and Rev.X)
223 pllConfig_t pll1ConfigRevY = {
224 .clockMhz = 400,
225 .m = 4,
226 .n = 800000000 / PLL_SRC_FREQ * 4, // Holds DIVN's output to DIVP at 800Mhz.
227 .p = 2,
228 // Dividing PLLQ here by 8 keeps PLLQ1, used for SPI, below 200Mhz, required per the spec.
229 .q = 8,
230 .r = 5,
231 .vos = PWR_REGULATOR_VOLTAGE_SCALE1,
232 .vciRange = RCC_PLL1VCIRANGE_2,
235 // 480MHz for Rev.V
236 pllConfig_t pll1ConfigRevV = {
237 .clockMhz = 480,
238 .m = 4,
239 .n = 960000000 / PLL_SRC_FREQ * 4, // Holds DIVN's output to DIVP at 960Mhz.
240 .p = 2,
241 // Dividing PLLQ here by 8 keeps PLLQ1, used for SPI, below 200Mhz, required per the spec.
242 .q = 8,
243 .r = 5,
244 .vos = PWR_REGULATOR_VOLTAGE_SCALE0,
245 .vciRange = RCC_PLL1VCIRANGE_2,
248 #define MCU_HCLK_DIVIDER RCC_HCLK_DIV2
250 // H743 and H750
251 // For HCLK=200MHz with VOS1 range, ST recommended flash latency is 2WS.
252 // RM0433 (Rev.5) Table 12. FLASH recommended number of wait states and programming delay
254 // For higher HCLK frequency, VOS0 is available on RevV silicons, with FLASH wait states 4WS
255 // AN5312 (Rev.1) Section 1.2.1 Voltage scaling Table.1
257 // XXX Check if Rev.V requires a different value
259 #define MCU_FLASH_LATENCY FLASH_LATENCY_2
261 // Source for CRS input
262 #define MCU_RCC_CRS_SYNC_SOURCE RCC_CRS_SYNC_SOURCE_USB2
264 // Workaround for weird HSE behaviors
265 // (Observed only on Rev.V H750, but may also apply to H743 and Rev.V.)
266 #define USE_H7_HSERDY_SLOW_WORKAROUND
267 #define USE_H7_HSE_TIMEOUT_WORKAROUND
269 #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
271 // Nominal max 280MHz with 8MHz HSE
272 // (340 is okay, 360 doesn't work.)
275 pllConfig_t pll1Config7A3 = {
276 .clockMhz = 280,
277 .m = 4,
278 .n = 560000000 / PLL_SRC_FREQ * 4, // Holds DIVN's output to DIVP at 560Mhz.
279 .p = 2,
280 // Dividing PLLQ here by 8 keeps PLLQ1, used for SPI, below 200Mhz, required per the spec.
281 .q = 8,
282 .r = 5,
283 .vos = PWR_REGULATOR_VOLTAGE_SCALE0,
284 .vciRange = RCC_PLL1VCIRANGE_1,
287 // Unlike H743/H750, HCLK can be directly fed with SYSCLK.
288 #define MCU_HCLK_DIVIDER RCC_HCLK_DIV1
290 // RM0455 (Rev.6) Table 15. FLASH recommended number of wait states and programming delay
291 // 280MHz at VOS0 is 6WS
293 #define MCU_FLASH_LATENCY FLASH_LATENCY_6
295 // Source for CRS input
296 #define MCU_RCC_CRS_SYNC_SOURCE RCC_CRS_SYNC_SOURCE_USB1
298 #elif defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx)
300 // Nominal max 550MHz, but >520Mhz requires ECC to be disabled, CPUFREQ_BOOST set in option bytes and prevents OCTOSPI clock from running at the correct clock speed.
301 // Unless CPUFREQ_BOOST in option bytes is enabled maximum CPU speed is limited to 520Mhz in VOS0. VOS1 is limited to 400Mhz
302 // References:
303 // RM0468 Rev 3 "6.6.2 Voltage scaling".
304 // RM0468 Rev 3 "4.9.24 FLASH option status register 2 (FLASH_OPTSR2_CUR)"
305 // DS13312 Rev 2 "Table 13. General operating conditions (continued)"
307 // "Bit 2CPUFREQ_BOOST: CPU frequency boost status bit. This bit indicates whether the CPU frequency can be boosted or not. When it is set, the ECC on ITCM and DTCM are no more used"
308 // ...
309 // So use 520Mhz so that OCTOSPI clk can be 200Mhz with OCTOPSI prescaler 2 via PLL2R or 130Mhz with OCTOPSI prescaler 1 via PLL1Q
311 pllConfig_t pll1Config72x73x = {
312 .clockMhz = 520,
313 .m = 4,
314 .n = 520000000 / PLL_SRC_FREQ * 4, // Holds DIVN's output to DIVP at 520Mhz.
315 .p = 1,
316 // Dividing PLLQ here by 4 keeps PLLQ1, used for SPI, below 200Mhz, required per the spec.
317 .q = 4,
318 .r = 2,
319 .vos = PWR_REGULATOR_VOLTAGE_SCALE0,
320 .vciRange = RCC_PLL1VCIRANGE_1,
323 #define MCU_HCLK_DIVIDER RCC_HCLK_DIV2
325 // RM0468 (Rev.2) Table 16.
326 // 520MHz (AXI Interface clock) at VOS0 is 3WS
327 #define MCU_FLASH_LATENCY FLASH_LATENCY_3
329 #define MCU_RCC_CRS_SYNC_SOURCE RCC_CRS_SYNC_SOURCE_USB1
331 #else
332 #error Unknown MCU type
333 #endif
335 // HSE clock configuration, originally taken from
336 // STM32Cube_FW_H7_V1.3.0/Projects/STM32H743ZI-Nucleo/Examples/RCC/RCC_ClockConfig/Src/main.c
337 static void SystemClockHSE_Config(void)
339 RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
340 RCC_OscInitTypeDef RCC_OscInitStruct = {0};
342 #ifdef notdef
343 // CSI has been disabled at SystemInit().
344 // HAL_RCC_ClockConfig() will fail because CSIRDY is off.
346 /* -1- Select CSI as system clock source to allow modification of the PLL configuration */
348 RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_SYSCLK;
349 RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_CSI;
350 if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1) != HAL_OK) {
351 /* Initialization Error */
352 ErrorHandler();
354 #endif
356 pllConfig_t *pll1Config;
358 #if defined(STM32H743xx) || defined(STM32H750xx)
359 pll1Config = (HAL_GetREVID() == REV_ID_V) ? &pll1ConfigRevV : &pll1ConfigRevY;
360 #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
361 pll1Config = &pll1Config7A3;
362 #elif defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx)
363 pll1Config = &pll1Config72x73x;
364 #else
365 #error Unknown MCU type
366 #endif
368 // Configure voltage scale.
369 // It has been pre-configured at PWR_REGULATOR_VOLTAGE_SCALE1,
370 // and it may stay or overridden by PWR_REGULATOR_VOLTAGE_SCALE0 depending on the clock config.
372 __HAL_PWR_VOLTAGESCALING_CONFIG(pll1Config->vos);
374 while (!__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY)) {
375 // Empty
378 /* -2- Enable HSE Oscillator, select it as PLL source and finally activate the PLL */
380 #ifdef USE_H7_HSERDY_SLOW_WORKAROUND
381 // With reference to 2.3.22 in the ES0250 Errata for the L476.
382 // Applying the same workaround here in the vain hopes that it improves startup times.
383 // Randomly the HSERDY bit takes AGES, over 10 seconds, to be set.
385 __HAL_RCC_GPIOH_CLK_ENABLE();
387 HAL_GPIO_WritePin(GPIOH, GPIO_PIN_0 | GPIO_PIN_1, GPIO_PIN_RESET);
389 GPIO_InitTypeDef gpio_initstruct;
390 gpio_initstruct.Pin = GPIO_PIN_0 | GPIO_PIN_1;
391 gpio_initstruct.Mode = GPIO_MODE_OUTPUT_PP;
392 gpio_initstruct.Pull = GPIO_NOPULL;
393 gpio_initstruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
395 HAL_GPIO_Init(GPIOH, &gpio_initstruct);
396 #endif
398 RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
399 RCC_OscInitStruct.HSEState = RCC_HSE_ON; // Even Nucleo-H473ZI and Nucleo-H7A3ZI work without RCC_HSE_BYPASS
401 RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
402 RCC_OscInitStruct.PLL.PLLSource = PLL_SRC;
403 RCC_OscInitStruct.PLL.PLLM = pll1Config->m;
404 RCC_OscInitStruct.PLL.PLLN = pll1Config->n;
405 RCC_OscInitStruct.PLL.PLLP = pll1Config->p;
406 RCC_OscInitStruct.PLL.PLLQ = pll1Config->q;
407 RCC_OscInitStruct.PLL.PLLR = pll1Config->r;
409 RCC_OscInitStruct.PLL.PLLVCOSEL = RCC_PLL1VCOWIDE;
410 RCC_OscInitStruct.PLL.PLLRGE = pll1Config->vciRange;
411 HAL_StatusTypeDef status = HAL_RCC_OscConfig(&RCC_OscInitStruct);
413 #ifdef USE_H7_HSE_TIMEOUT_WORKAROUND
414 if (status == HAL_TIMEOUT) {
415 systemResetWithoutDisablingCaches(); // DC - sometimes HSERDY gets stuck, waiting longer doesn't help.
417 #endif
419 if (status != HAL_OK) {
420 /* Initialization Error */
421 ErrorHandler();
424 // Configure PLL2 and PLL3
425 // Use of PLL2 and PLL3 are not determined yet.
426 // A review of total system wide clock requirements is necessary.
428 // Configure SCGU (System Clock Generation Unit)
429 // Select PLL as system clock source and configure bus clock dividers.
431 // Clock type and divider member names do not have direct visual correspondence.
432 // Here is how these correspond:
433 // RCC_CLOCKTYPE_SYSCLK sys_ck
434 // RCC_CLOCKTYPE_HCLK AHBx (rcc_hclk1,rcc_hclk2,rcc_hclk3,rcc_hclk4)
435 // RCC_CLOCKTYPE_D1PCLK1 APB3 (rcc_pclk3)
436 // RCC_CLOCKTYPE_PCLK1 APB1 (rcc_pclk1)
437 // RCC_CLOCKTYPE_PCLK2 APB2 (rcc_pclk2)
438 // RCC_CLOCKTYPE_D3PCLK1 APB4 (rcc_pclk4)
440 RCC_ClkInitStruct.ClockType = ( \
441 RCC_CLOCKTYPE_SYSCLK | \
442 RCC_CLOCKTYPE_HCLK | \
443 RCC_CLOCKTYPE_D1PCLK1 | \
444 RCC_CLOCKTYPE_PCLK1 | \
445 RCC_CLOCKTYPE_PCLK2 | \
446 RCC_CLOCKTYPE_D3PCLK1);
447 RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
448 RCC_ClkInitStruct.SYSCLKDivider = RCC_SYSCLK_DIV1;
450 RCC_ClkInitStruct.AHBCLKDivider = MCU_HCLK_DIVIDER;
451 RCC_ClkInitStruct.APB3CLKDivider = RCC_APB3_DIV2;
452 RCC_ClkInitStruct.APB1CLKDivider = RCC_APB1_DIV2;
453 RCC_ClkInitStruct.APB2CLKDivider = RCC_APB2_DIV2;
454 RCC_ClkInitStruct.APB4CLKDivider = RCC_APB4_DIV2;
456 if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, MCU_FLASH_LATENCY) != HAL_OK) {
457 /* Initialization Error */
458 ErrorHandler();
461 /* -4- Optional: Disable CSI Oscillator (if the HSI is no more needed by the application)*/
462 RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_CSI;
463 RCC_OscInitStruct.CSIState = RCC_CSI_OFF;
464 RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
465 if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
466 /* Initialization Error */
467 ErrorHandler();
471 void SystemClock_Config(void)
473 // Configure power supply
475 #if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H7A3xx) || defined(STM32H730xx)
476 // Legacy H7 devices (H743, H750) and newer but SMPS-less devices(H7A3, H723, H730)
478 HAL_PWREx_ConfigSupply(PWR_LDO_SUPPLY);
480 // Pre-configure voltage scale to PWR_REGULATOR_VOLTAGE_SCALE1.
481 // SystemClockHSE_Config may configure PWR_REGULATOR_VOLTAGE_SCALE0.
483 __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
485 #elif defined(STM32H7A3xxQ) || defined(STM32H725xx)
487 // We assume all SMPS equipped devices use this mode (Direct SMPS).
488 // - All STM32H7A3xxQ devices.
489 // - All STM32H725xx devices (Note STM32H725RG is Direct SMPS only - no LDO).
491 // Note that:
492 // - Nucleo-H7A3ZI-Q is preconfigured for power supply configuration 2 (Direct SMPS).
493 // - Nucleo-H723ZI-Q transplanted with STM32H725ZG is the same as above.
495 HAL_PWREx_ConfigSupply(PWR_DIRECT_SMPS_SUPPLY);
497 __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE0);
499 #else
500 #error Unknown MCU
501 #endif
503 while (!__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY)) {
504 // Empty
507 SystemClockHSE_Config();
509 /*activate CSI clock mondatory for I/O Compensation Cell*/
511 __HAL_RCC_CSI_ENABLE() ;
513 /* Enable SYSCFG clock mondatory for I/O Compensation Cell */
515 __HAL_RCC_SYSCFG_CLK_ENABLE() ;
517 /* Enables the I/O Compensation Cell */
519 HAL_EnableCompensationCell();
521 HandleStuckSysTick();
523 HAL_Delay(10);
525 // Configure peripheral clocks
527 RCC_PeriphCLKInitTypeDef RCC_PeriphClkInit;
529 // Configure HSI48 as peripheral clock for USB
531 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USB;
532 RCC_PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_HSI48;
533 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
535 // Configure CRS for dynamic calibration of HSI48
536 // While ES0392 Rev 5 "STM32H742xI/G and STM32H743xI/G device limitations" states CRS not working for REV.Y,
537 // it is always turned on as it seems that it has no negative effect on clock accuracy.
539 RCC_CRSInitTypeDef crsInit = {
540 .Prescaler = RCC_CRS_SYNC_DIV1,
541 .Source = MCU_RCC_CRS_SYNC_SOURCE,
542 .Polarity = RCC_CRS_SYNC_POLARITY_RISING,
543 .ReloadValue = RCC_CRS_RELOADVALUE_DEFAULT,
544 .ErrorLimitValue = RCC_CRS_ERRORLIMIT_DEFAULT,
545 .HSI48CalibrationValue = RCC_CRS_HSI48CALIBRATION_DEFAULT,
548 __HAL_RCC_CRS_CLK_ENABLE();
549 HAL_RCCEx_CRSConfig(&crsInit);
551 #ifdef USE_CRS_INTERRUPTS
552 // Turn on USE_CRS_INTERRUPTS to see CRS in action
553 HAL_NVIC_SetPriority(CRS_IRQn, 6, 0);
554 HAL_NVIC_EnableIRQ(CRS_IRQn);
555 __HAL_RCC_CRS_ENABLE_IT(RCC_CRS_IT_SYNCOK|RCC_CRS_IT_SYNCWARN|RCC_CRS_IT_ESYNC|RCC_CRS_IT_ERR);
556 #endif
558 // Configure UART peripheral clock sources
560 // Possible sources:
561 // D2PCLK1 (pclk1 for APB1 = USART234578)
562 // D2PCLK2 (pclk2 for APB2 = USART16)
563 // PLL2 (pll2_q_ck)
564 // PLL3 (pll3_q_ck),
565 // HSI (hsi_ck),
566 // CSI (csi_ck),LSE(lse_ck);
568 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART16|RCC_PERIPHCLK_USART234578;
569 RCC_PeriphClkInit.Usart16ClockSelection = RCC_USART16CLKSOURCE_D2PCLK2;
570 RCC_PeriphClkInit.Usart234578ClockSelection = RCC_USART234578CLKSOURCE_D2PCLK1;
571 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
573 // Configure SPI peripheral clock sources
575 // Possible sources for SPI123:
576 // PLL (pll1_q_ck)
577 // PLL2 (pll2_p_ck)
578 // PLL3 (pll3_p_ck)
579 // PIN (I2S_CKIN)
580 // CLKP (per_ck)
581 // Possible sources for SPI45:
582 // D2PCLK1 (rcc_pclk2 = APB1) 100MHz
583 // PLL2 (pll2_q_ck)
584 // PLL3 (pll3_q_ck)
585 // HSI (hsi_ker_ck)
586 // CSI (csi_ker_ck)
587 // HSE (hse_ck)
588 // Possible sources for SPI6:
589 // D3PCLK1 (rcc_pclk4 = APB4) 100MHz
590 // PLL2 (pll2_q_ck)
591 // PLL3 (pll3_q_ck)
592 // HSI (hsi_ker_ck)
593 // CSI (csi_ker_ck)
594 // HSE (hse_ck)
596 // We use 100MHz for Rev.Y and 120MHz for Rev.V from various sources
598 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_SPI123|RCC_PERIPHCLK_SPI45|RCC_PERIPHCLK_SPI6;
599 RCC_PeriphClkInit.Spi123ClockSelection = RCC_SPI123CLKSOURCE_PLL;
600 RCC_PeriphClkInit.Spi45ClockSelection = RCC_SPI45CLKSOURCE_D2PCLK1;
601 RCC_PeriphClkInit.Spi6ClockSelection = RCC_SPI6CLKSOURCE_D3PCLK1;
602 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
604 // Configure I2C peripheral clock sources
606 // Current source for I2C123:
607 // D2PCLK1 (rcc_pclk1 = APB1 peripheral clock)
609 // Current source for I2C4:
610 // D3PCLK1 (rcc_pclk4 = APB4 peripheral clock)
612 // Note that peripheral clock determination in bus_i2c_hal_init.c must be modified when the sources are modified.
614 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_I2C123|RCC_PERIPHCLK_I2C4;
615 RCC_PeriphClkInit.I2c123ClockSelection = RCC_I2C123CLKSOURCE_D2PCLK1;
616 RCC_PeriphClkInit.I2c4ClockSelection = RCC_I2C4CLKSOURCE_D3PCLK1;
617 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
619 #ifdef USE_SDCARD_SDIO
620 __HAL_RCC_SDMMC1_CLK_ENABLE(); // FIXME enable SDMMC1 or SDMMC2 depending on target.
622 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_SDMMC;
624 # if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H725xx)
625 RCC_PeriphClkInit.PLL2.PLL2M = 5;
626 RCC_PeriphClkInit.PLL2.PLL2N = 800000000 / PLL_SRC_FREQ * 5; // Oscillator Frequency / 5 (PLL2M) = 1.6 * this value (PLL2N) = 800Mhz.
627 RCC_PeriphClkInit.PLL2.PLL2VCOSEL = RCC_PLL2VCOWIDE; // Wide VCO range:192 to 836 MHz
628 RCC_PeriphClkInit.PLL2.PLL2RGE = RCC_PLL2VCIRANGE_0; // PLL2 input between 1 and 2Mhz (1.6)
629 RCC_PeriphClkInit.PLL2.PLL2FRACN = 0;
631 RCC_PeriphClkInit.PLL2.PLL2P = 2; // 800Mhz / 2 = 400Mhz
632 RCC_PeriphClkInit.PLL2.PLL2Q = 3; // 800Mhz / 3 = 266Mhz // 133Mhz can be derived from this for for QSPI if flash chip supports the speed.
633 RCC_PeriphClkInit.PLL2.PLL2R = 4; // 800Mhz / 4 = 200Mhz // HAL LIBS REQUIRE 200MHZ SDMMC CLOCK, see HAL_SD_ConfigWideBusOperation, SDMMC_HSpeed_CLK_DIV, SDMMC_NSpeed_CLK_DIV
634 # elif defined(STM32H730xx)
635 RCC_PeriphClkInit.PLL2.PLL2M = 8;
636 RCC_PeriphClkInit.PLL2.PLL2N = 400000000 / PLL_SRC_FREQ * 8; // HSE frequency / 8 (PLL2M) * 400 (PLL2N) = 400Mhz.
637 RCC_PeriphClkInit.PLL2.PLL2VCOSEL = RCC_PLL2VCOMEDIUM; // Medium VCO range:150 to 420 MHz
638 RCC_PeriphClkInit.PLL2.PLL2RGE = RCC_PLL2VCIRANGE_0; // PLL2 input between 1 and 2Mhz (1.0)
639 RCC_PeriphClkInit.PLL2.PLL2FRACN = 0;
641 RCC_PeriphClkInit.PLL2.PLL2P = 3; // 400Mhz / 3 = 133Mhz // ADC does't like much higher when using PLL2P
642 RCC_PeriphClkInit.PLL2.PLL2Q = 3; // 400Mhz / 3 = 133Mhz // SPI6 does't like much higher when using PLL2Q
643 RCC_PeriphClkInit.PLL2.PLL2R = 2; // 400Mhz / 2 = 200Mhz // HAL LIBS REQUIRE 200MHZ SDMMC CLOCK, see HAL_SD_ConfigWideBusOperation, SDMMC_HSpeed_CLK_DIV, SDMMC_NSpeed_CLK_DIV
644 # else
645 # error Unknown MCU type
646 # endif
647 RCC_PeriphClkInit.SdmmcClockSelection = RCC_SDMMCCLKSOURCE_PLL2;
648 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
649 # endif
651 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC;
652 RCC_PeriphClkInit.AdcClockSelection = RCC_ADCCLKSOURCE_CLKP;
653 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
655 // TODO H730 OCTOSPI clock for 100Mhz flash chips should use PLL2R at 200Mhz
657 // Configure MCO clocks for clock test/verification
659 // Possible sources for MCO1:
660 // RCC_MCO1SOURCE_HSI (hsi_ck)
661 // RCC_MCO1SOURCE_LSE (?)
662 // RCC_MCO1SOURCE_HSE (hse_ck)
663 // RCC_MCO1SOURCE_PLL1QCLK (pll1_q_ck)
664 // RCC_MCO1SOURCE_HSI48 (hsi48_ck)
666 // HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSE, RCC_MCODIV_1); // HSE(8M) / 1 = 1M
667 HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSI48, RCC_MCODIV_4); // HSI48(48M) / 4 = 12M
669 // Possible sources for MCO2:
670 // RCC_MCO2SOURCE_SYSCLK (sys_ck)
671 // RCC_MCO2SOURCE_PLL2PCLK (pll2_p_ck)
672 // RCC_MCO2SOURCE_HSE (hse_ck)
673 // RCC_MCO2SOURCE_PLLCLK (pll1_p_ck)
674 // RCC_MCO2SOURCE_CSICLK (csi_ck)
675 // RCC_MCO2SOURCE_LSICLK (lsi_ck)
677 HAL_RCC_MCOConfig(RCC_MCO2, RCC_MCO2SOURCE_PLLCLK, RCC_MCODIV_15); // PLL1P(400M) / 15 = 26.67M
680 #ifdef USE_CRS_INTERRUPTS
681 static uint32_t crs_syncok = 0;
682 static uint32_t crs_syncwarn = 0;
683 static uint32_t crs_expectedsync = 0;
684 static uint32_t crs_error = 0;
686 void HAL_RCCEx_CRS_SyncOkCallback(void)
688 ++crs_syncok;
691 void HAL_RCCEx_CRS_SyncWarnCallback(void)
693 ++crs_syncwarn;
696 void HAL_RCCEx_CRS_ExpectedSyncCallback(void)
698 ++crs_expectedsync;
701 void HAL_RCCEx_CRS_ErrorCallback(uint32_t Error)
703 ++crs_error;
706 void CRS_IRQHandler(void)
708 HAL_RCCEx_CRS_IRQHandler();
710 #endif
712 static void initialiseD2MemorySections(void)
714 /* Load DMA_DATA variable intializers into D2 RAM */
715 extern uint8_t _sdmaram_bss;
716 extern uint8_t _edmaram_bss;
717 extern uint8_t _sdmaram_data;
718 extern uint8_t _edmaram_data;
719 extern uint8_t _sdmaram_idata;
720 bzero(&_sdmaram_bss, (size_t) (&_edmaram_bss - &_sdmaram_bss));
721 memcpy(&_sdmaram_data, &_sdmaram_idata, (size_t) (&_edmaram_data - &_sdmaram_data));
724 void SystemInit (void)
726 memProtReset();
728 initialiseMemorySections();
730 #if !defined(USE_EXST)
731 // only stand-alone and bootloader firmware needs to do this.
732 // if it's done in the EXST firmware as well as the BOOTLOADER firmware you get a reset loop.
733 systemProcessResetReason();
734 #endif
736 #if defined(USE_FLASH_MEMORY_MAPPED)
737 memoryMappedModeInit();
739 // !IMPORTANT! Do NOT reset peripherals, clocks and GPIO pins used by the MCU to access the memory-mapped flash!!!
740 #endif
742 // FPU settings
743 #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
744 SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); // Set CP10 and CP11 Full Access
745 #endif
747 // Reset the RCC clock configuration to the default reset state
748 // Set HSION bit
749 RCC->CR = RCC_CR_HSION;
751 // Reset CFGR register
752 RCC->CFGR = 0x00000000;
754 // Reset HSEON, CSSON , CSION,RC48ON, CSIKERON PLL1ON, PLL2ON and PLL3ON bits
756 // XXX Don't do this until we are established with clock handling
757 // RCC->CR &= (uint32_t)0xEAF6ED7F;
759 // Instead, we explicitly turn those on
760 RCC->CR |= RCC_CR_CSION;
761 RCC->CR |= RCC_CR_HSION;
762 RCC->CR |= RCC_CR_HSEON;
763 RCC->CR |= RCC_CR_HSI48ON;
765 #if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx)
766 /* Reset D1CFGR register */
767 RCC->D1CFGR = 0x00000000;
769 /* Reset D2CFGR register */
770 RCC->D2CFGR = 0x00000000;
772 /* Reset D3CFGR register */
773 RCC->D3CFGR = 0x00000000;
774 #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
775 /* Reset CDCFGR1 register */
776 RCC->CDCFGR1 = 0x00000000;
778 /* Reset CDCFGR2 register */
779 RCC->CDCFGR2 = 0x00000000;
781 /* Reset SRDCFGR register */
782 RCC->SRDCFGR = 0x00000000;
783 #endif
785 /* Reset PLLCKSELR register */
786 RCC->PLLCKSELR = 0x00000000;
788 /* Reset PLLCFGR register */
789 RCC->PLLCFGR = 0x00000000;
790 /* Reset PLL1DIVR register */
791 RCC->PLL1DIVR = 0x00000000;
792 /* Reset PLL1FRACR register */
793 RCC->PLL1FRACR = 0x00000000;
795 /* Reset PLL2DIVR register */
796 RCC->PLL2DIVR = 0x00000000;
798 /* Reset PLL2FRACR register */
800 RCC->PLL2FRACR = 0x00000000;
801 /* Reset PLL3DIVR register */
802 RCC->PLL3DIVR = 0x00000000;
804 /* Reset PLL3FRACR register */
805 RCC->PLL3FRACR = 0x00000000;
807 /* Reset HSEBYP bit */
808 RCC->CR &= (uint32_t)0xFFFBFFFF;
810 /* Disable all interrupts */
811 RCC->CIER = 0x00000000;
813 /* Change the switch matrix read issuing capability to 1 for the AXI SRAM target (Target 7) */
814 *((__IO uint32_t*)0x51008108) = 0x00000001;
816 #if defined(DATA_IN_ExtSRAM) || defined(DATA_IN_ExtSDRAM)
817 SystemInit_ExtMemCtl();
818 #endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
820 /* Configure the Vector Table location add offset address ------------------*/
821 #if defined(VECT_TAB_SRAM)
822 #if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx)
823 SCB->VTOR = D1_AXISRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal ITCMSRAM */
824 #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
825 SCB->VTOR = CD_AXISRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal ITCMSRAM */
826 #else
827 #error Unknown MCU type
828 #endif
829 #elif defined(USE_EXST)
830 extern uint8_t isr_vector_table_base;
832 SCB->VTOR = (uint32_t)&isr_vector_table_base;
833 #if defined(STM32H730xx)
834 /* Configure the Vector Table location add offset address ------------------*/
836 extern uint8_t isr_vector_table_flash_base;
837 extern uint8_t isr_vector_table_end;
839 extern uint8_t ram_isr_vector_table_base;
841 memcpy(&ram_isr_vector_table_base, &isr_vector_table_flash_base, (size_t) (&isr_vector_table_end - &isr_vector_table_base));
843 SCB->VTOR = (uint32_t)&ram_isr_vector_table_base;
844 #endif
845 #else
846 SCB->VTOR = FLASH_BANK1_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
847 #endif
849 #ifdef USE_HAL_DRIVER
850 HAL_Init();
851 #endif
853 SystemClock_Config();
854 SystemCoreClockUpdate();
856 #ifdef STM32H7
857 initialiseD2MemorySections();
858 #endif
860 // Configure MPU
862 memProtConfigure(mpuRegions, mpuRegionCount);
864 // Enable CPU L1-Cache
865 SCB_EnableICache();
866 SCB_EnableDCache();
870 * @brief Update SystemCoreClock variable according to Clock Register Values.
871 * The SystemCoreClock variable contains the core clock , it can
872 * be used by the user application to setup the SysTick timer or configure
873 * other parameters.
875 * @note Each time the core clock changes, this function must be called
876 * to update SystemCoreClock variable value. Otherwise, any configuration
877 * based on this variable will be incorrect.
879 * @note - The system frequency computed by this function is not the real
880 * frequency in the chip. It is calculated based on the predefined
881 * constant and the selected clock source:
883 * - If SYSCLK source is CSI, SystemCoreClock will contain the CSI_VALUE(*)
884 * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(**)
885 * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(***)
886 * - If SYSCLK source is PLL, SystemCoreClock will contain the CSI_VALUE(*),
887 * HSI_VALUE(**) or HSE_VALUE(***) multiplied/divided by the PLL factors.
889 * (*) CSI_VALUE is a constant defined in stm32h7xx_hal.h file (default value
890 * 4 MHz) but the real value may vary depending on the variations
891 * in voltage and temperature.
892 * (**) HSI_VALUE is a constant defined in stm32h7xx_hal.h file (default value
893 * 64 MHz) but the real value may vary depending on the variations
894 * in voltage and temperature.
896 * (***)HSE_VALUE is a constant defined in stm32h7xx_hal.h file (default value
897 * 25 MHz), user has to ensure that HSE_VALUE is same as the real
898 * frequency of the crystal used. Otherwise, this function may
899 * have wrong result.
901 * - The result of this function could be not correct when using fractional
902 * value for HSE crystal.
903 * @param None
904 * @retval None
907 void SystemCoreClockUpdate (void)
909 SystemCoreClock = HAL_RCC_GetSysClockFreq();
912 #if defined(DATA_IN_ExtSRAM) || defined(DATA_IN_ExtSDRAM)
914 * @brief Setup the external memory controller.
915 * Called in startup_stm32h7xx.s before jump to main.
916 * This function configures the external memories (SRAM/SDRAM)
917 * This SRAM/SDRAM will be used as program data memory (including heap and stack).
918 * @param None
919 * @retval None
921 void SystemInit_ExtMemCtl(void)
923 #if defined(DATA_IN_ExtSDRAM)
924 register uint32_t tmpreg = 0, timeout = 0xFFFF;
925 register __IO uint32_t index;
927 /* Enable GPIOD, GPIOE, GPIOF, GPIOG, GPIOH and GPIOI interface clock */
928 RCC->AHB4ENR |= 0x000001F8;
929 /* Connect PDx pins to FMC Alternate function */
930 GPIOD->AFR[0] = 0x000000CC;
931 GPIOD->AFR[1] = 0xCC000CCC;
932 /* Configure PDx pins in Alternate function mode */
933 GPIOD->MODER = 0xAFEAFFFA;
934 /* Configure PDx pins speed to 50 MHz */
935 GPIOD->OSPEEDR = 0xA02A000A;
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 = 0x55555505;
940 /* Connect PEx pins to FMC Alternate function */
941 GPIOE->AFR[0] = 0xC00000CC;
942 GPIOE->AFR[1] = 0xCCCCCCCC;
943 /* Configure PEx pins in Alternate function mode */
944 GPIOE->MODER = 0xAAAABFFA;
945 /* Configure PEx pins speed to 50 MHz */
946 GPIOE->OSPEEDR = 0xAAAA800A;
947 /* Configure PEx pins Output type to push-pull */
948 GPIOE->OTYPER = 0x00000000;
949 /* No pull-up, pull-down for PEx pins */
950 GPIOE->PUPDR = 0x55554005;
951 /* Connect PFx pins to FMC Alternate function */
952 GPIOF->AFR[0] = 0x00CCCCCC;
953 GPIOF->AFR[1] = 0xCCCCC000;
954 /* Configure PFx pins in Alternate function mode */
955 GPIOF->MODER = 0xAABFFAAA;
956 /* Configure PFx pins speed to 50 MHz */
957 GPIOF->OSPEEDR = 0xAA800AAA;
958 /* Configure PFx pins Output type to push-pull */
959 GPIOF->OTYPER = 0x00000000;
960 /* No pull-up, pull-down for PFx pins */
961 GPIOF->PUPDR = 0x55400555;
962 /* Connect PGx pins to FMC Alternate function */
963 GPIOG->AFR[0] = 0x00CCCCCC;
964 GPIOG->AFR[1] = 0xC000000C;
965 /* Configure PGx pins in Alternate function mode */
966 GPIOG->MODER = 0xBFFEFAAA;
967 /* Configure PGx pins speed to 50 MHz */
968 GPIOG->OSPEEDR = 0x80020AAA;
969 /* Configure PGx pins Output type to push-pull */
970 GPIOG->OTYPER = 0x00000000;
971 /* No pull-up, pull-down for PGx pins */
972 GPIOG->PUPDR = 0x40010515;
973 /* Connect PHx pins to FMC Alternate function */
974 GPIOH->AFR[0] = 0xCCC00000;
975 GPIOH->AFR[1] = 0xCCCCCCCC;
976 /* Configure PHx pins in Alternate function mode */
977 GPIOH->MODER = 0xAAAAABFF;
978 /* Configure PHx pins speed to 50 MHz */
979 GPIOH->OSPEEDR = 0xAAAAA800;
980 /* Configure PHx pins Output type to push-pull */
981 GPIOH->OTYPER = 0x00000000;
982 /* No pull-up, pull-down for PHx pins */
983 GPIOH->PUPDR = 0x55555400;
984 /* Connect PIx pins to FMC Alternate function */
985 GPIOI->AFR[0] = 0xCCCCCCCC;
986 GPIOI->AFR[1] = 0x00000CC0;
987 /* Configure PIx pins in Alternate function mode */
988 GPIOI->MODER = 0xFFEBAAAA;
989 /* Configure PIx pins speed to 50 MHz */
990 GPIOI->OSPEEDR = 0x0028AAAA;
991 /* Configure PIx pins Output type to push-pull */
992 GPIOI->OTYPER = 0x00000000;
993 /* No pull-up, pull-down for PIx pins */
994 GPIOI->PUPDR = 0x00145555;
995 /*-- FMC Configuration ------------------------------------------------------*/
996 /* Enable the FMC interface clock */
997 (RCC->AHB3ENR |= (RCC_AHB3ENR_FMCEN));
998 /*SDRAM Timing and access interface configuration*/
999 /*LoadToActiveDelay = 2
1000 ExitSelfRefreshDelay = 6
1001 SelfRefreshTime = 4
1002 RowCycleDelay = 6
1003 WriteRecoveryTime = 2
1004 RPDelay = 2
1005 RCDDelay = 2
1006 SDBank = FMC_SDRAM_BANK2
1007 ColumnBitsNumber = FMC_SDRAM_COLUMN_BITS_NUM_9
1008 RowBitsNumber = FMC_SDRAM_ROW_BITS_NUM_12
1009 MemoryDataWidth = FMC_SDRAM_MEM_BUS_WIDTH_32
1010 InternalBankNumber = FMC_SDRAM_INTERN_BANKS_NUM_4
1011 CASLatency = FMC_SDRAM_CAS_LATENCY_2
1012 WriteProtection = FMC_SDRAM_WRITE_PROTECTION_DISABLE
1013 SDClockPeriod = FMC_SDRAM_CLOCK_PERIOD_2
1014 ReadBurst = FMC_SDRAM_RBURST_ENABLE
1015 ReadPipeDelay = FMC_SDRAM_RPIPE_DELAY_0*/
1017 FMC_Bank5_6->SDCR[0] = 0x00001800;
1018 FMC_Bank5_6->SDCR[1] = 0x00000165;
1019 FMC_Bank5_6->SDTR[0] = 0x00105000;
1020 FMC_Bank5_6->SDTR[1] = 0x01010351;
1022 /* SDRAM initialization sequence */
1023 /* Clock enable command */
1024 FMC_Bank5_6->SDCMR = 0x00000009;
1025 tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
1026 while((tmpreg != 0) && (timeout-- > 0))
1028 tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
1031 /* Delay */
1032 for (index = 0; index<1000; index++);
1034 /* PALL command */
1035 FMC_Bank5_6->SDCMR = 0x0000000A;
1036 timeout = 0xFFFF;
1037 while((tmpreg != 0) && (timeout-- > 0))
1039 tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
1042 FMC_Bank5_6->SDCMR = 0x000000EB;
1043 timeout = 0xFFFF;
1044 while((tmpreg != 0) && (timeout-- > 0))
1046 tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
1049 FMC_Bank5_6->SDCMR = 0x0004400C;
1050 timeout = 0xFFFF;
1051 while((tmpreg != 0) && (timeout-- > 0))
1053 tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
1055 /* Set refresh count */
1056 tmpreg = FMC_Bank5_6->SDRTR;
1057 FMC_Bank5_6->SDRTR = (tmpreg | (0x00000603<<1));
1059 /* Disable write protection */
1060 tmpreg = FMC_Bank5_6->SDCR[1];
1061 FMC_Bank5_6->SDCR[1] = (tmpreg & 0xFFFFFDFF);
1063 /*FMC controller Enable*/
1064 FMC_Bank1->BTCR[0] |= 0x80000000;
1066 #endif /* DATA_IN_ExtSDRAM */
1068 #if defined(DATA_IN_ExtSRAM)
1069 /*-- GPIOs Configuration -----------------------------------------------------*/
1070 /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */
1071 RCC->AHB4ENR |= 0x00000078;
1073 /* Connect PDx pins to FMC Alternate function */
1074 GPIOD->AFR[0] = 0x00CCC0CC;
1075 GPIOD->AFR[1] = 0xCCCCCCCC;
1076 /* Configure PDx pins in Alternate function mode */
1077 GPIOD->MODER = 0xAAAA0A8A;
1078 /* Configure PDx pins speed to 100 MHz */
1079 GPIOD->OSPEEDR = 0xFFFF0FCF;
1080 /* Configure PDx pins Output type to push-pull */
1081 GPIOD->OTYPER = 0x00000000;
1082 /* No pull-up, pull-down for PDx pins */
1083 GPIOD->PUPDR = 0x55550545;
1085 /* Connect PEx pins to FMC Alternate function */
1086 GPIOE->AFR[0] = 0xC00CC0CC;
1087 GPIOE->AFR[1] = 0xCCCCCCCC;
1088 /* Configure PEx pins in Alternate function mode */
1089 GPIOE->MODER = 0xAAAA828A;
1090 /* Configure PEx pins speed to 100 MHz */
1091 GPIOE->OSPEEDR = 0xFFFFC3CF;
1092 /* Configure PEx pins Output type to push-pull */
1093 GPIOE->OTYPER = 0x00000000;
1094 /* No pull-up, pull-down for PEx pins */
1095 GPIOE->PUPDR = 0x55554145;
1097 /* Connect PFx pins to FMC Alternate function */
1098 GPIOF->AFR[0] = 0x00CCCCCC;
1099 GPIOF->AFR[1] = 0xCCCC0000;
1100 /* Configure PFx pins in Alternate function mode */
1101 GPIOF->MODER = 0xAA000AAA;
1102 /* Configure PFx pins speed to 100 MHz */
1103 GPIOF->OSPEEDR = 0xFF000FFF;
1104 /* Configure PFx pins Output type to push-pull */
1105 GPIOF->OTYPER = 0x00000000;
1106 /* No pull-up, pull-down for PFx pins */
1107 GPIOF->PUPDR = 0x55000555;
1109 /* Connect PGx pins to FMC Alternate function */
1110 GPIOG->AFR[0] = 0x00CCCCCC;
1111 GPIOG->AFR[1] = 0x000000C0;
1112 /* Configure PGx pins in Alternate function mode */
1113 GPIOG->MODER = 0x00200AAA;
1114 /* Configure PGx pins speed to 100 MHz */
1115 GPIOG->OSPEEDR = 0x00300FFF;
1116 /* Configure PGx pins Output type to push-pull */
1117 GPIOG->OTYPER = 0x00000000;
1118 /* No pull-up, pull-down for PGx pins */
1119 GPIOG->PUPDR = 0x00100555;
1121 /*-- FMC/FSMC Configuration --------------------------------------------------*/
1122 /* Enable the FMC/FSMC interface clock */
1123 (RCC->AHB3ENR |= (RCC_AHB3ENR_FMCEN));
1125 /* Configure and enable Bank1_SRAM2 */
1126 FMC_Bank1->BTCR[4] = 0x00001091;
1127 FMC_Bank1->BTCR[5] = 0x00110212;
1128 FMC_Bank1E->BWTR[4] = 0x0FFFFFFF;
1130 /*FMC controller Enable*/
1131 FMC_Bank1->BTCR[0] |= 0x80000000;
1133 #endif /* DATA_IN_ExtSRAM */
1135 #endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
1138 * @}
1142 * @}
1146 * @}
1148 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/