STM32H7 - SDMMC Fix the short busy loop being compiled out by newer
[betaflight.git] / src / main / startup / system_stm32h7xx.c
blob367f3625307aa2aad0a0eeefbfce9f5e64d436e3
1 /**
2 ******************************************************************************
3 * @file system_stm32h7xx.c
4 * @author MCD Application Team
5 * @brief CMSIS Cortex-Mx Device Peripheral Access Layer System Source File.
7 * This file provides two functions and one global variable to be called from
8 * user application:
9 * - SystemInit(): This function is called at startup just after reset and
10 * before branch to main program. This call is made inside
11 * the "startup_stm32h7xx.s" file.
13 * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
14 * by the user application to setup the SysTick
15 * timer or configure other parameters.
17 * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
18 * be called whenever the core clock is changed
19 * during program execution.
22 ******************************************************************************
23 * @attention
25 * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
27 * Redistribution and use in source and binary forms, with or without modification,
28 * are permitted provided that the following conditions are met:
29 * 1. Redistributions of source code must retain the above copyright notice,
30 * this list of conditions and the following disclaimer.
31 * 2. Redistributions in binary form must reproduce the above copyright notice,
32 * this list of conditions and the following disclaimer in the documentation
33 * and/or other materials provided with the distribution.
34 * 3. Neither the name of STMicroelectronics nor the names of its contributors
35 * may be used to endorse or promote products derived from this software
36 * without specific prior written permission.
38 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
39 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
40 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
41 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
42 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
43 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
44 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
45 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
46 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
47 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
49 ******************************************************************************
52 /** @addtogroup CMSIS
53 * @{
56 /** @addtogroup stm32h7xx_system
57 * @{
60 /** @addtogroup STM32H7xx_System_Private_Includes
61 * @{
64 #include "stm32h7xx.h"
65 #include "drivers/system.h"
66 #include "platform.h"
67 #include "string.h"
68 #include "common/utils.h"
70 #include "build/debug.h"
72 void systemResetWithoutDisablingCaches(void);
74 #if !defined (HSE_VALUE)
75 #define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */
76 #endif /* HSE_VALUE */
78 #if !defined (CSI_VALUE)
79 #define CSI_VALUE ((uint32_t)4000000) /*!< Value of the Internal oscillator in Hz*/
80 #endif /* CSI_VALUE */
82 #if !defined (HSI_VALUE)
83 #define HSI_VALUE ((uint32_t)64000000) /*!< Value of the Internal oscillator in Hz*/
84 #endif /* HSI_VALUE */
87 /**
88 * @}
91 /** @addtogroup STM32H7xx_System_Private_TypesDefinitions
92 * @{
95 /**
96 * @}
99 /** @addtogroup STM32H7xx_System_Private_Defines
100 * @{
103 /************************* Miscellaneous Configuration ************************/
104 /*!< Uncomment the following line if you need to use external SRAM or SDRAM mounted
105 on EVAL board as data memory */
106 /*#define DATA_IN_ExtSRAM */
107 /*#define DATA_IN_ExtSDRAM*/
109 #if defined(DATA_IN_ExtSRAM) && defined(DATA_IN_ExtSDRAM)
110 #error "Please select DATA_IN_ExtSRAM or DATA_IN_ExtSDRAM "
111 #endif /* DATA_IN_ExtSRAM && DATA_IN_ExtSDRAM */
113 /*!< Uncomment the following line if you need to relocate your vector Table in
114 Internal SRAM. */
115 /* #define VECT_TAB_SRAM */
116 #define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field.
117 This value must be a multiple of 0x200. */
118 /******************************************************************************/
121 * @}
124 /** @addtogroup STM32H7xx_System_Private_Macros
125 * @{
129 * @}
132 /** @addtogroup STM32H7xx_System_Private_Variables
133 * @{
135 /* This variable is updated in three ways:
136 1) by calling CMSIS function SystemCoreClockUpdate()
137 2) by calling HAL API function HAL_RCC_GetHCLKFreq()
138 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
139 Note: If you use this function to configure the system clock; then there
140 is no need to call the 2 first functions listed above, since SystemCoreClock
141 variable is updated automatically.
143 uint32_t SystemCoreClock = 64000000;
144 uint32_t SystemD2Clock = 64000000;
145 const uint8_t D1CorePrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};
148 * @}
151 /** @addtogroup STM32H7xx_System_Private_FunctionPrototypes
152 * @{
154 #if defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
155 static void SystemInit_ExtMemCtl(void);
156 #endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
159 * @}
162 /** @addtogroup STM32H7xx_System_Private_Functions
163 * @{
166 static void ErrorHandler(void)
168 while (1);
171 void HandleStuckSysTick(void)
173 uint32_t tickStart = HAL_GetTick();
174 uint32_t tickEnd = 0;
176 // H7 at 480Mhz requires a loop count of 160000. Double this for the timeout to be safe.
177 int attemptsRemaining = 320000;
178 while (((tickEnd = HAL_GetTick()) == tickStart) && --attemptsRemaining) {
181 if (tickStart == tickEnd) {
182 systemResetWithoutDisablingCaches();
186 typedef struct pllConfig_s {
187 uint16_t clockMhz;
188 uint8_t m;
189 uint16_t n;
190 uint8_t p;
191 uint8_t q;
192 uint8_t r;
193 uint32_t vos;
194 uint32_t vciRange;
195 } pllConfig_t;
197 #if defined(STM32H743xx) || defined(STM32H750xx)
199 PLL1 configuration for different silicon revisions of H743 and H750.
201 Note for future overclocking support.
203 - Rev.Y (and Rev.X), nominal max at 400MHz, runs stably overclocked to 480MHz.
204 - Rev.V, nominal max at 480MHz, runs stably at 540MHz, but not to 600MHz (VCO probably out of operating range)
206 - A possible frequency table would look something like this, and a revision
207 check logic would place a cap for Rev.Y and V.
209 400 420 440 460 (Rev.Y & V ends here) 480 500 520 540
212 // 400MHz for Rev.Y (and Rev.X)
213 pllConfig_t pll1ConfigRevY = {
214 .clockMhz = 400,
215 .m = 4,
216 .n = 400,
217 .p = 2,
218 .q = 8,
219 .r = 5,
220 .vos = PWR_REGULATOR_VOLTAGE_SCALE1,
221 .vciRange = RCC_PLL1VCIRANGE_2,
224 // 480MHz for Rev.V
225 pllConfig_t pll1ConfigRevV = {
226 .clockMhz = 480,
227 .m = 4,
228 .n = 480,
229 .p = 2,
230 .q = 8,
231 .r = 5,
232 .vos = PWR_REGULATOR_VOLTAGE_SCALE0,
233 .vciRange = RCC_PLL1VCIRANGE_2,
236 #define MCU_HCLK_DIVIDER RCC_HCLK_DIV2
238 // H743 and H750
239 // For HCLK=200MHz with VOS1 range, ST recommended flash latency is 2WS.
240 // RM0433 (Rev.5) Table 12. FLASH recommended number of wait states and programming delay
242 // For higher HCLK frequency, VOS0 is available on RevV silicons, with FLASH wait states 4WS
243 // AN5312 (Rev.1) Section 1.2.1 Voltage scaling Table.1
245 // XXX Check if Rev.V requires a different value
247 #define MCU_FLASH_LATENCY FLASH_LATENCY_2
249 // Source for CRS input
250 #define MCU_RCC_CRS_SYNC_SOURCE RCC_CRS_SYNC_SOURCE_USB2
252 // Workaround for weird HSE behaviors
253 // (Observed only on Rev.V H750, but may also apply to H743 and Rev.V.)
254 #define USE_H7_HSERDY_SLOW_WORKAROUND
255 #define USE_H7_HSE_TIMEOUT_WORKAROUND
257 #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
259 // Nominal max 280MHz with 8MHz HSE
260 // (340 is okay, 360 doesn't work.)
263 pllConfig_t pll1Config7A3 = {
264 .clockMhz = 280,
265 .m = 4,
266 .n = 280,
267 .p = 2,
268 .q = 8,
269 .r = 5,
270 .vos = PWR_REGULATOR_VOLTAGE_SCALE0,
271 .vciRange = RCC_PLL1VCIRANGE_1,
274 // Unlike H743/H750, HCLK can be directly fed with SYSCLK.
275 #define MCU_HCLK_DIVIDER RCC_HCLK_DIV1
277 // RM0455 (Rev.6) Table 15. FLASH recommended number of wait states and programming delay
278 // 280MHz at VOS0 is 6WS
280 #define MCU_FLASH_LATENCY FLASH_LATENCY_6
282 // Source for CRS input
283 #define MCU_RCC_CRS_SYNC_SOURCE RCC_CRS_SYNC_SOURCE_USB1
285 #elif defined(STM32H723xx) || defined(STM32H725xx)
287 // Nominal max 550MHz
289 pllConfig_t pll1Config72x = {
290 .clockMhz = 550,
291 .m = 4,
292 .n = 275,
293 .p = 1,
294 .q = 2,
295 .r = 2,
296 .vos = PWR_REGULATOR_VOLTAGE_SCALE0,
297 .vciRange = RCC_PLL1VCIRANGE_1,
300 #define MCU_HCLK_DIVIDER RCC_HCLK_DIV2
302 // RM0468 (Rev.2) Table 16.
303 // 550MHz (AXI Interface clock) at VOS0 is 3WS
304 #define MCU_FLASH_LATENCY FLASH_LATENCY_3
306 #define MCU_RCC_CRS_SYNC_SOURCE RCC_CRS_SYNC_SOURCE_USB1
308 #else
309 #error Unknown MCU type
310 #endif
312 // HSE clock configuration, originally taken from
313 // STM32Cube_FW_H7_V1.3.0/Projects/STM32H743ZI-Nucleo/Examples/RCC/RCC_ClockConfig/Src/main.c
314 static void SystemClockHSE_Config(void)
316 RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
317 RCC_OscInitTypeDef RCC_OscInitStruct = {0};
319 #ifdef notdef
320 // CSI has been disabled at SystemInit().
321 // HAL_RCC_ClockConfig() will fail because CSIRDY is off.
323 /* -1- Select CSI as system clock source to allow modification of the PLL configuration */
325 RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_SYSCLK;
326 RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_CSI;
327 if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1) != HAL_OK) {
328 /* Initialization Error */
329 ErrorHandler();
331 #endif
333 pllConfig_t *pll1Config;
335 #if defined(STM32H743xx) || defined(STM32H750xx)
336 pll1Config = (HAL_GetREVID() == REV_ID_V) ? &pll1ConfigRevV : &pll1ConfigRevY;
337 #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
338 pll1Config = &pll1Config7A3;
339 #elif defined(STM32H723xx) || defined(STM32H725xx)
340 pll1Config = &pll1Config72x;
341 #else
342 #error Unknown MCU type
343 #endif
345 // Configure voltage scale.
346 // It has been pre-configured at PWR_REGULATOR_VOLTAGE_SCALE1,
347 // and it may stay or overridden by PWR_REGULATOR_VOLTAGE_SCALE0 depending on the clock config.
349 __HAL_PWR_VOLTAGESCALING_CONFIG(pll1Config->vos);
351 while (!__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY)) {
352 // Empty
355 /* -2- Enable HSE Oscillator, select it as PLL source and finally activate the PLL */
357 #ifdef USE_H7_HSERDY_SLOW_WORKAROUND
358 // With reference to 2.3.22 in the ES0250 Errata for the L476.
359 // Applying the same workaround here in the vain hopes that it improves startup times.
360 // Randomly the HSERDY bit takes AGES, over 10 seconds, to be set.
362 __HAL_RCC_GPIOH_CLK_ENABLE();
364 HAL_GPIO_WritePin(GPIOH, GPIO_PIN_0 | GPIO_PIN_1, GPIO_PIN_RESET);
366 GPIO_InitTypeDef gpio_initstruct;
367 gpio_initstruct.Pin = GPIO_PIN_0 | GPIO_PIN_1;
368 gpio_initstruct.Mode = GPIO_MODE_OUTPUT_PP;
369 gpio_initstruct.Pull = GPIO_NOPULL;
370 gpio_initstruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
372 HAL_GPIO_Init(GPIOH, &gpio_initstruct);
373 #endif
375 RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
376 RCC_OscInitStruct.HSEState = RCC_HSE_ON; // Even Nucleo-H473ZI and Nucleo-H7A3ZI work without RCC_HSE_BYPASS
378 RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
379 RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
380 RCC_OscInitStruct.PLL.PLLM = pll1Config->m;
381 RCC_OscInitStruct.PLL.PLLN = pll1Config->n;
382 RCC_OscInitStruct.PLL.PLLP = pll1Config->p;
383 RCC_OscInitStruct.PLL.PLLQ = pll1Config->q;
384 RCC_OscInitStruct.PLL.PLLR = pll1Config->r;
386 RCC_OscInitStruct.PLL.PLLVCOSEL = RCC_PLL1VCOWIDE;
387 RCC_OscInitStruct.PLL.PLLRGE = pll1Config->vciRange;
388 HAL_StatusTypeDef status = HAL_RCC_OscConfig(&RCC_OscInitStruct);
390 #ifdef USE_H7_HSE_TIMEOUT_WORKAROUND
391 if (status == HAL_TIMEOUT) {
392 systemResetWithoutDisablingCaches(); // DC - sometimes HSERDY gets stuck, waiting longer doesn't help.
394 #endif
396 if (status != HAL_OK) {
397 /* Initialization Error */
398 ErrorHandler();
401 // Configure PLL2 and PLL3
402 // Use of PLL2 and PLL3 are not determined yet.
403 // A review of total system wide clock requirements is necessary.
406 // Configure SCGU (System Clock Generation Unit)
407 // Select PLL as system clock source and configure bus clock dividers.
409 // Clock type and divider member names do not have direct visual correspondence.
410 // Here is how these correspond:
411 // RCC_CLOCKTYPE_SYSCLK sys_ck
412 // RCC_CLOCKTYPE_HCLK AHBx (rcc_hclk1,rcc_hclk2,rcc_hclk3,rcc_hclk4)
413 // RCC_CLOCKTYPE_D1PCLK1 APB3 (rcc_pclk3)
414 // RCC_CLOCKTYPE_PCLK1 APB1 (rcc_pclk1)
415 // RCC_CLOCKTYPE_PCLK2 APB2 (rcc_pclk2)
416 // RCC_CLOCKTYPE_D3PCLK1 APB4 (rcc_pclk4)
418 RCC_ClkInitStruct.ClockType = ( \
419 RCC_CLOCKTYPE_SYSCLK | \
420 RCC_CLOCKTYPE_HCLK | \
421 RCC_CLOCKTYPE_D1PCLK1 | \
422 RCC_CLOCKTYPE_PCLK1 | \
423 RCC_CLOCKTYPE_PCLK2 | \
424 RCC_CLOCKTYPE_D3PCLK1);
425 RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
426 RCC_ClkInitStruct.SYSCLKDivider = RCC_SYSCLK_DIV1;
428 RCC_ClkInitStruct.AHBCLKDivider = MCU_HCLK_DIVIDER;
429 RCC_ClkInitStruct.APB3CLKDivider = RCC_APB3_DIV2;
430 RCC_ClkInitStruct.APB1CLKDivider = RCC_APB1_DIV2;
431 RCC_ClkInitStruct.APB2CLKDivider = RCC_APB2_DIV2;
432 RCC_ClkInitStruct.APB4CLKDivider = RCC_APB4_DIV2;
434 if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, MCU_FLASH_LATENCY) != HAL_OK) {
435 /* Initialization Error */
436 ErrorHandler();
439 /* -4- Optional: Disable CSI Oscillator (if the HSI is no more needed by the application)*/
440 RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_CSI;
441 RCC_OscInitStruct.CSIState = RCC_CSI_OFF;
442 RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
443 if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
444 /* Initialization Error */
445 ErrorHandler();
449 void SystemClock_Config(void)
451 // Configure power supply
453 #if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H7A3xx)
454 // Legacy H7 devices (H743, H750) and newer but SMPS-less devices(H7A3, H723)
456 HAL_PWREx_ConfigSupply(PWR_LDO_SUPPLY);
458 // Pre-configure voltage scale to PWR_REGULATOR_VOLTAGE_SCALE1.
459 // SystemClockHSE_Config may configure PWR_REGULATOR_VOLTAGE_SCALE0.
461 __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
463 #elif defined(STM32H7A3xxQ) || defined(STM32H725xx)
465 // We assume all SMPS equipped devices use this mode (Direct SMPS).
466 // - All STM32H7A3xxQ devices.
467 // - All STM32H725xx devices (Note STM32H725RG is Direct SMPS only - no LDO).
469 // Note that:
470 // - Nucleo-H7A3ZI-Q is preconfigured for power supply configuration 2 (Direct SMPS).
471 // - Nucleo-H723ZI-Q transplanted with STM32H725ZG is the same as above.
473 HAL_PWREx_ConfigSupply(PWR_DIRECT_SMPS_SUPPLY);
475 __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE0);
477 #else
478 #error Unknown MCU
479 #endif
481 while (!__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY)) {
482 // Empty
485 SystemClockHSE_Config();
487 /*activate CSI clock mondatory for I/O Compensation Cell*/
489 __HAL_RCC_CSI_ENABLE() ;
491 /* Enable SYSCFG clock mondatory for I/O Compensation Cell */
493 __HAL_RCC_SYSCFG_CLK_ENABLE() ;
495 /* Enables the I/O Compensation Cell */
497 HAL_EnableCompensationCell();
499 HandleStuckSysTick();
501 HAL_Delay(10);
503 // Configure peripheral clocks
505 RCC_PeriphCLKInitTypeDef RCC_PeriphClkInit;
507 // Configure HSI48 as peripheral clock for USB
509 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USB;
510 RCC_PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_HSI48;
511 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
513 // Configure CRS for dynamic calibration of HSI48
514 // While ES0392 Rev 5 "STM32H742xI/G and STM32H743xI/G device limitations" states CRS not working for REV.Y,
515 // it is always turned on as it seems that it has no negative effect on clock accuracy.
517 RCC_CRSInitTypeDef crsInit = {
518 .Prescaler = RCC_CRS_SYNC_DIV1,
519 .Source = MCU_RCC_CRS_SYNC_SOURCE,
520 .Polarity = RCC_CRS_SYNC_POLARITY_RISING,
521 .ReloadValue = RCC_CRS_RELOADVALUE_DEFAULT,
522 .ErrorLimitValue = RCC_CRS_ERRORLIMIT_DEFAULT,
523 .HSI48CalibrationValue = RCC_CRS_HSI48CALIBRATION_DEFAULT,
526 __HAL_RCC_CRS_CLK_ENABLE();
527 HAL_RCCEx_CRSConfig(&crsInit);
529 #ifdef USE_CRS_INTERRUPTS
530 // Turn on USE_CRS_INTERRUPTS to see CRS in action
531 HAL_NVIC_SetPriority(CRS_IRQn, 6, 0);
532 HAL_NVIC_EnableIRQ(CRS_IRQn);
533 __HAL_RCC_CRS_ENABLE_IT(RCC_CRS_IT_SYNCOK|RCC_CRS_IT_SYNCWARN|RCC_CRS_IT_ESYNC|RCC_CRS_IT_ERR);
534 #endif
536 // Configure UART peripheral clock sources
538 // Possible sources:
539 // D2PCLK1 (pclk1 for APB1 = USART234578)
540 // D2PCLK2 (pclk2 for APB2 = USART16)
541 // PLL2 (pll2_q_ck)
542 // PLL3 (pll3_q_ck),
543 // HSI (hsi_ck),
544 // CSI (csi_ck),LSE(lse_ck);
546 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART16|RCC_PERIPHCLK_USART234578;
547 RCC_PeriphClkInit.Usart16ClockSelection = RCC_USART16CLKSOURCE_D2PCLK2;
548 RCC_PeriphClkInit.Usart234578ClockSelection = RCC_USART234578CLKSOURCE_D2PCLK1;
549 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
551 // Configure SPI peripheral clock sources
553 // Possible sources for SPI123:
554 // PLL (pll1_q_ck)
555 // PLL2 (pll2_p_ck)
556 // PLL3 (pll3_p_ck)
557 // PIN (I2S_CKIN)
558 // CLKP (per_ck)
559 // Possible sources for SPI45:
560 // D2PCLK1 (rcc_pclk2 = APB1) 100MHz
561 // PLL2 (pll2_q_ck)
562 // PLL3 (pll3_q_ck)
563 // HSI (hsi_ker_ck)
564 // CSI (csi_ker_ck)
565 // HSE (hse_ck)
566 // Possible sources for SPI6:
567 // D3PCLK1 (rcc_pclk4 = APB4) 100MHz
568 // PLL2 (pll2_q_ck)
569 // PLL3 (pll3_q_ck)
570 // HSI (hsi_ker_ck)
571 // CSI (csi_ker_ck)
572 // HSE (hse_ck)
574 // We use 100MHz for Rev.Y and 120MHz for Rev.V from various sources
576 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_SPI123|RCC_PERIPHCLK_SPI45|RCC_PERIPHCLK_SPI6;
577 RCC_PeriphClkInit.Spi123ClockSelection = RCC_SPI123CLKSOURCE_PLL;
578 RCC_PeriphClkInit.Spi45ClockSelection = RCC_SPI45CLKSOURCE_D2PCLK1;
579 RCC_PeriphClkInit.Spi6ClockSelection = RCC_SPI6CLKSOURCE_D3PCLK1;
580 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
582 // Configure I2C peripheral clock sources
584 // Current source for I2C123:
585 // D2PCLK1 (rcc_pclk1 = APB1 peripheral clock)
587 // Current source for I2C4:
588 // D3PCLK1 (rcc_pclk4 = APB4 peripheral clock)
590 // Note that peripheral clock determination in bus_i2c_hal_init.c must be modified when the sources are modified.
592 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_I2C123|RCC_PERIPHCLK_I2C4;
593 RCC_PeriphClkInit.I2c123ClockSelection = RCC_I2C123CLKSOURCE_D2PCLK1;
594 RCC_PeriphClkInit.I2c4ClockSelection = RCC_I2C4CLKSOURCE_D3PCLK1;
595 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
597 #ifdef USE_SDCARD_SDIO
598 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_SDMMC;
600 #if (HSE_VALUE != 8000000)
601 #error Unsupported external oscillator speed. The calculations below are based on 8Mhz resonators
602 // if you are seeing this, then calculate the PLL2 settings for your resonator and add support as required.
603 #else
604 RCC_PeriphClkInit.PLL2.PLL2M = 5;
605 RCC_PeriphClkInit.PLL2.PLL2N = 500;
606 RCC_PeriphClkInit.PLL2.PLL2P = 2; // 500Mhz
607 RCC_PeriphClkInit.PLL2.PLL2Q = 3; // 266Mhz - 133Mhz can be derived from this for for QSPI if flash chip supports the speed.
608 RCC_PeriphClkInit.PLL2.PLL2R = 4; // 200Mhz HAL LIBS REQUIRE 200MHZ SDMMC CLOCK, see HAL_SD_ConfigWideBusOperation, SDMMC_HSpeed_CLK_DIV, SDMMC_NSpeed_CLK_DIV
609 RCC_PeriphClkInit.PLL2.PLL2RGE = RCC_PLL2VCIRANGE_0;
610 RCC_PeriphClkInit.PLL2.PLL2VCOSEL = RCC_PLL2VCOWIDE;
611 RCC_PeriphClkInit.PLL2.PLL2FRACN = 0;
612 RCC_PeriphClkInit.SdmmcClockSelection = RCC_SDMMCCLKSOURCE_PLL2;
613 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
614 #endif // 8Mhz HSE_VALUE
616 #endif
618 // Configure MCO clocks for clock test/verification
620 // Possible sources for MCO1:
621 // RCC_MCO1SOURCE_HSI (hsi_ck)
622 // RCC_MCO1SOURCE_LSE (?)
623 // RCC_MCO1SOURCE_HSE (hse_ck)
624 // RCC_MCO1SOURCE_PLL1QCLK (pll1_q_ck)
625 // RCC_MCO1SOURCE_HSI48 (hsi48_ck)
627 // HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSE, RCC_MCODIV_1); // HSE(8M) / 1 = 1M
628 HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSI48, RCC_MCODIV_4); // HSI48(48M) / 4 = 12M
630 // Possible sources for MCO2:
631 // RCC_MCO2SOURCE_SYSCLK (sys_ck)
632 // RCC_MCO2SOURCE_PLL2PCLK (pll2_p_ck)
633 // RCC_MCO2SOURCE_HSE (hse_ck)
634 // RCC_MCO2SOURCE_PLLCLK (pll1_p_ck)
635 // RCC_MCO2SOURCE_CSICLK (csi_ck)
636 // RCC_MCO2SOURCE_LSICLK (lsi_ck)
638 HAL_RCC_MCOConfig(RCC_MCO2, RCC_MCO2SOURCE_PLLCLK, RCC_MCODIV_15); // PLL1P(400M) / 15 = 26.67M
641 #ifdef USE_CRS_INTERRUPTS
642 static uint32_t crs_syncok = 0;
643 static uint32_t crs_syncwarn = 0;
644 static uint32_t crs_expectedsync = 0;
645 static uint32_t crs_error = 0;
647 void HAL_RCCEx_CRS_SyncOkCallback(void)
649 ++crs_syncok;
652 void HAL_RCCEx_CRS_SyncWarnCallback(void)
654 ++crs_syncwarn;
657 void HAL_RCCEx_CRS_ExpectedSyncCallback(void)
659 ++crs_expectedsync;
662 void HAL_RCCEx_CRS_ErrorCallback(uint32_t Error)
664 ++crs_error;
667 void CRS_IRQHandler(void)
669 HAL_RCCEx_CRS_IRQHandler();
671 #endif
673 #include "build/debug.h"
675 void systemCheckResetReason(void);
677 #include "drivers/memprot.h"
679 void SystemInit (void)
681 memProtReset();
683 initialiseMemorySections();
685 #if !defined(USE_EXST)
686 // only stand-alone and bootloader firmware needs to do this.
687 // if it's done in the EXST firmware as well as the BOOTLOADER firmware you get a reset loop.
688 systemCheckResetReason();
689 #endif
691 // FPU settings
692 #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
693 SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); // Set CP10 and CP11 Full Access
694 #endif
696 // Reset the RCC clock configuration to the default reset state
697 // Set HSION bit
698 RCC->CR = RCC_CR_HSION;
700 // Reset CFGR register
701 RCC->CFGR = 0x00000000;
703 // Reset HSEON, CSSON , CSION,RC48ON, CSIKERON PLL1ON, PLL2ON and PLL3ON bits
705 // XXX Don't do this until we are established with clock handling
706 // RCC->CR &= (uint32_t)0xEAF6ED7F;
708 // Instead, we explicitly turn those on
709 RCC->CR |= RCC_CR_CSION;
710 RCC->CR |= RCC_CR_HSION;
711 RCC->CR |= RCC_CR_HSEON;
712 RCC->CR |= RCC_CR_HSI48ON;
714 #if defined(STM32H743xx) || defined(STM32H750xx)
715 /* Reset D1CFGR register */
716 RCC->D1CFGR = 0x00000000;
718 /* Reset D2CFGR register */
719 RCC->D2CFGR = 0x00000000;
721 /* Reset D3CFGR register */
722 RCC->D3CFGR = 0x00000000;
723 #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
724 /* Reset CDCFGR1 register */
725 RCC->CDCFGR1 = 0x00000000;
727 /* Reset CDCFGR2 register */
728 RCC->CDCFGR2 = 0x00000000;
730 /* Reset SRDCFGR register */
731 RCC->SRDCFGR = 0x00000000;
732 #endif
734 /* Reset PLLCKSELR register */
735 RCC->PLLCKSELR = 0x00000000;
737 /* Reset PLLCFGR register */
738 RCC->PLLCFGR = 0x00000000;
739 /* Reset PLL1DIVR register */
740 RCC->PLL1DIVR = 0x00000000;
741 /* Reset PLL1FRACR register */
742 RCC->PLL1FRACR = 0x00000000;
744 /* Reset PLL2DIVR register */
745 RCC->PLL2DIVR = 0x00000000;
747 /* Reset PLL2FRACR register */
749 RCC->PLL2FRACR = 0x00000000;
750 /* Reset PLL3DIVR register */
751 RCC->PLL3DIVR = 0x00000000;
753 /* Reset PLL3FRACR register */
754 RCC->PLL3FRACR = 0x00000000;
756 /* Reset HSEBYP bit */
757 RCC->CR &= (uint32_t)0xFFFBFFFF;
759 /* Disable all interrupts */
760 RCC->CIER = 0x00000000;
762 /* Change the switch matrix read issuing capability to 1 for the AXI SRAM target (Target 7) */
763 *((__IO uint32_t*)0x51008108) = 0x00000001;
765 #if defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
766 SystemInit_ExtMemCtl();
767 #endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
769 /* Configure the Vector Table location add offset address ------------------*/
770 #if defined(VECT_TAB_SRAM)
771 #if defined(STM32H743xx) || defined(STM32H750xx)
772 SCB->VTOR = D1_AXISRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal ITCMSRAM */
773 #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
774 SCB->VTOR = CD_AXISRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal ITCMSRAM */
775 #else
776 #error Unknown MCU type
777 #endif
778 #elif defined(USE_EXST)
779 extern void *isr_vector_table_base;
781 SCB->VTOR = (uint32_t)&isr_vector_table_base;
782 #else
783 SCB->VTOR = FLASH_BANK1_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
784 #endif
786 #ifdef USE_HAL_DRIVER
787 HAL_Init();
788 #endif
790 SystemClock_Config();
791 SystemCoreClockUpdate();
793 #ifdef STM32H7
794 initialiseD2MemorySections();
795 #endif
797 // Configure MPU
799 memProtConfigure(mpuRegions, mpuRegionCount);
801 // Enable CPU L1-Cache
802 SCB_EnableICache();
803 SCB_EnableDCache();
807 * @brief Update SystemCoreClock variable according to Clock Register Values.
808 * The SystemCoreClock variable contains the core clock , it can
809 * be used by the user application to setup the SysTick timer or configure
810 * other parameters.
812 * @note Each time the core clock changes, this function must be called
813 * to update SystemCoreClock variable value. Otherwise, any configuration
814 * based on this variable will be incorrect.
816 * @note - The system frequency computed by this function is not the real
817 * frequency in the chip. It is calculated based on the predefined
818 * constant and the selected clock source:
820 * - If SYSCLK source is CSI, SystemCoreClock will contain the CSI_VALUE(*)
821 * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(**)
822 * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(***)
823 * - If SYSCLK source is PLL, SystemCoreClock will contain the CSI_VALUE(*),
824 * HSI_VALUE(**) or HSE_VALUE(***) multiplied/divided by the PLL factors.
826 * (*) CSI_VALUE is a constant defined in stm32h7xx_hal.h file (default value
827 * 4 MHz) but the real value may vary depending on the variations
828 * in voltage and temperature.
829 * (**) HSI_VALUE is a constant defined in stm32h7xx_hal.h file (default value
830 * 64 MHz) but the real value may vary depending on the variations
831 * in voltage and temperature.
833 * (***)HSE_VALUE is a constant defined in stm32h7xx_hal.h file (default value
834 * 25 MHz), user has to ensure that HSE_VALUE is same as the real
835 * frequency of the crystal used. Otherwise, this function may
836 * have wrong result.
838 * - The result of this function could be not correct when using fractional
839 * value for HSE crystal.
840 * @param None
841 * @retval None
844 void SystemCoreClockUpdate (void)
846 SystemCoreClock = HAL_RCC_GetSysClockFreq();
849 #if defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
851 * @brief Setup the external memory controller.
852 * Called in startup_stm32h7xx.s before jump to main.
853 * This function configures the external memories (SRAM/SDRAM)
854 * This SRAM/SDRAM will be used as program data memory (including heap and stack).
855 * @param None
856 * @retval None
858 void SystemInit_ExtMemCtl(void)
860 #if defined (DATA_IN_ExtSDRAM)
861 register uint32_t tmpreg = 0, timeout = 0xFFFF;
862 register __IO uint32_t index;
864 /* Enable GPIOD, GPIOE, GPIOF, GPIOG, GPIOH and GPIOI interface clock */
865 RCC->AHB4ENR |= 0x000001F8;
866 /* Connect PDx pins to FMC Alternate function */
867 GPIOD->AFR[0] = 0x000000CC;
868 GPIOD->AFR[1] = 0xCC000CCC;
869 /* Configure PDx pins in Alternate function mode */
870 GPIOD->MODER = 0xAFEAFFFA;
871 /* Configure PDx pins speed to 50 MHz */
872 GPIOD->OSPEEDR = 0xA02A000A;
873 /* Configure PDx pins Output type to push-pull */
874 GPIOD->OTYPER = 0x00000000;
875 /* No pull-up, pull-down for PDx pins */
876 GPIOD->PUPDR = 0x55555505;
877 /* Connect PEx pins to FMC Alternate function */
878 GPIOE->AFR[0] = 0xC00000CC;
879 GPIOE->AFR[1] = 0xCCCCCCCC;
880 /* Configure PEx pins in Alternate function mode */
881 GPIOE->MODER = 0xAAAABFFA;
882 /* Configure PEx pins speed to 50 MHz */
883 GPIOE->OSPEEDR = 0xAAAA800A;
884 /* Configure PEx pins Output type to push-pull */
885 GPIOE->OTYPER = 0x00000000;
886 /* No pull-up, pull-down for PEx pins */
887 GPIOE->PUPDR = 0x55554005;
888 /* Connect PFx pins to FMC Alternate function */
889 GPIOF->AFR[0] = 0x00CCCCCC;
890 GPIOF->AFR[1] = 0xCCCCC000;
891 /* Configure PFx pins in Alternate function mode */
892 GPIOF->MODER = 0xAABFFAAA;
893 /* Configure PFx pins speed to 50 MHz */
894 GPIOF->OSPEEDR = 0xAA800AAA;
895 /* Configure PFx pins Output type to push-pull */
896 GPIOF->OTYPER = 0x00000000;
897 /* No pull-up, pull-down for PFx pins */
898 GPIOF->PUPDR = 0x55400555;
899 /* Connect PGx pins to FMC Alternate function */
900 GPIOG->AFR[0] = 0x00CCCCCC;
901 GPIOG->AFR[1] = 0xC000000C;
902 /* Configure PGx pins in Alternate function mode */
903 GPIOG->MODER = 0xBFFEFAAA;
904 /* Configure PGx pins speed to 50 MHz */
905 GPIOG->OSPEEDR = 0x80020AAA;
906 /* Configure PGx pins Output type to push-pull */
907 GPIOG->OTYPER = 0x00000000;
908 /* No pull-up, pull-down for PGx pins */
909 GPIOG->PUPDR = 0x40010515;
910 /* Connect PHx pins to FMC Alternate function */
911 GPIOH->AFR[0] = 0xCCC00000;
912 GPIOH->AFR[1] = 0xCCCCCCCC;
913 /* Configure PHx pins in Alternate function mode */
914 GPIOH->MODER = 0xAAAAABFF;
915 /* Configure PHx pins speed to 50 MHz */
916 GPIOH->OSPEEDR = 0xAAAAA800;
917 /* Configure PHx pins Output type to push-pull */
918 GPIOH->OTYPER = 0x00000000;
919 /* No pull-up, pull-down for PHx pins */
920 GPIOH->PUPDR = 0x55555400;
921 /* Connect PIx pins to FMC Alternate function */
922 GPIOI->AFR[0] = 0xCCCCCCCC;
923 GPIOI->AFR[1] = 0x00000CC0;
924 /* Configure PIx pins in Alternate function mode */
925 GPIOI->MODER = 0xFFEBAAAA;
926 /* Configure PIx pins speed to 50 MHz */
927 GPIOI->OSPEEDR = 0x0028AAAA;
928 /* Configure PIx pins Output type to push-pull */
929 GPIOI->OTYPER = 0x00000000;
930 /* No pull-up, pull-down for PIx pins */
931 GPIOI->PUPDR = 0x00145555;
932 /*-- FMC Configuration ------------------------------------------------------*/
933 /* Enable the FMC interface clock */
934 (RCC->AHB3ENR |= (RCC_AHB3ENR_FMCEN));
935 /*SDRAM Timing and access interface configuration*/
936 /*LoadToActiveDelay = 2
937 ExitSelfRefreshDelay = 6
938 SelfRefreshTime = 4
939 RowCycleDelay = 6
940 WriteRecoveryTime = 2
941 RPDelay = 2
942 RCDDelay = 2
943 SDBank = FMC_SDRAM_BANK2
944 ColumnBitsNumber = FMC_SDRAM_COLUMN_BITS_NUM_9
945 RowBitsNumber = FMC_SDRAM_ROW_BITS_NUM_12
946 MemoryDataWidth = FMC_SDRAM_MEM_BUS_WIDTH_32
947 InternalBankNumber = FMC_SDRAM_INTERN_BANKS_NUM_4
948 CASLatency = FMC_SDRAM_CAS_LATENCY_2
949 WriteProtection = FMC_SDRAM_WRITE_PROTECTION_DISABLE
950 SDClockPeriod = FMC_SDRAM_CLOCK_PERIOD_2
951 ReadBurst = FMC_SDRAM_RBURST_ENABLE
952 ReadPipeDelay = FMC_SDRAM_RPIPE_DELAY_0*/
954 FMC_Bank5_6->SDCR[0] = 0x00001800;
955 FMC_Bank5_6->SDCR[1] = 0x00000165;
956 FMC_Bank5_6->SDTR[0] = 0x00105000;
957 FMC_Bank5_6->SDTR[1] = 0x01010351;
959 /* SDRAM initialization sequence */
960 /* Clock enable command */
961 FMC_Bank5_6->SDCMR = 0x00000009;
962 tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
963 while((tmpreg != 0) && (timeout-- > 0))
965 tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
968 /* Delay */
969 for (index = 0; index<1000; index++);
971 /* PALL command */
972 FMC_Bank5_6->SDCMR = 0x0000000A;
973 timeout = 0xFFFF;
974 while((tmpreg != 0) && (timeout-- > 0))
976 tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
979 FMC_Bank5_6->SDCMR = 0x000000EB;
980 timeout = 0xFFFF;
981 while((tmpreg != 0) && (timeout-- > 0))
983 tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
986 FMC_Bank5_6->SDCMR = 0x0004400C;
987 timeout = 0xFFFF;
988 while((tmpreg != 0) && (timeout-- > 0))
990 tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
992 /* Set refresh count */
993 tmpreg = FMC_Bank5_6->SDRTR;
994 FMC_Bank5_6->SDRTR = (tmpreg | (0x00000603<<1));
996 /* Disable write protection */
997 tmpreg = FMC_Bank5_6->SDCR[1];
998 FMC_Bank5_6->SDCR[1] = (tmpreg & 0xFFFFFDFF);
1000 /*FMC controller Enable*/
1001 FMC_Bank1->BTCR[0] |= 0x80000000;
1004 #endif /* DATA_IN_ExtSDRAM */
1006 #if defined(DATA_IN_ExtSRAM)
1007 /*-- GPIOs Configuration -----------------------------------------------------*/
1008 /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */
1009 RCC->AHB4ENR |= 0x00000078;
1011 /* Connect PDx pins to FMC Alternate function */
1012 GPIOD->AFR[0] = 0x00CCC0CC;
1013 GPIOD->AFR[1] = 0xCCCCCCCC;
1014 /* Configure PDx pins in Alternate function mode */
1015 GPIOD->MODER = 0xAAAA0A8A;
1016 /* Configure PDx pins speed to 100 MHz */
1017 GPIOD->OSPEEDR = 0xFFFF0FCF;
1018 /* Configure PDx pins Output type to push-pull */
1019 GPIOD->OTYPER = 0x00000000;
1020 /* No pull-up, pull-down for PDx pins */
1021 GPIOD->PUPDR = 0x55550545;
1023 /* Connect PEx pins to FMC Alternate function */
1024 GPIOE->AFR[0] = 0xC00CC0CC;
1025 GPIOE->AFR[1] = 0xCCCCCCCC;
1026 /* Configure PEx pins in Alternate function mode */
1027 GPIOE->MODER = 0xAAAA828A;
1028 /* Configure PEx pins speed to 100 MHz */
1029 GPIOE->OSPEEDR = 0xFFFFC3CF;
1030 /* Configure PEx pins Output type to push-pull */
1031 GPIOE->OTYPER = 0x00000000;
1032 /* No pull-up, pull-down for PEx pins */
1033 GPIOE->PUPDR = 0x55554145;
1035 /* Connect PFx pins to FMC Alternate function */
1036 GPIOF->AFR[0] = 0x00CCCCCC;
1037 GPIOF->AFR[1] = 0xCCCC0000;
1038 /* Configure PFx pins in Alternate function mode */
1039 GPIOF->MODER = 0xAA000AAA;
1040 /* Configure PFx pins speed to 100 MHz */
1041 GPIOF->OSPEEDR = 0xFF000FFF;
1042 /* Configure PFx pins Output type to push-pull */
1043 GPIOF->OTYPER = 0x00000000;
1044 /* No pull-up, pull-down for PFx pins */
1045 GPIOF->PUPDR = 0x55000555;
1047 /* Connect PGx pins to FMC Alternate function */
1048 GPIOG->AFR[0] = 0x00CCCCCC;
1049 GPIOG->AFR[1] = 0x000000C0;
1050 /* Configure PGx pins in Alternate function mode */
1051 GPIOG->MODER = 0x00200AAA;
1052 /* Configure PGx pins speed to 100 MHz */
1053 GPIOG->OSPEEDR = 0x00300FFF;
1054 /* Configure PGx pins Output type to push-pull */
1055 GPIOG->OTYPER = 0x00000000;
1056 /* No pull-up, pull-down for PGx pins */
1057 GPIOG->PUPDR = 0x00100555;
1059 /*-- FMC/FSMC Configuration --------------------------------------------------*/
1060 /* Enable the FMC/FSMC interface clock */
1061 (RCC->AHB3ENR |= (RCC_AHB3ENR_FMCEN));
1063 /* Configure and enable Bank1_SRAM2 */
1064 FMC_Bank1->BTCR[4] = 0x00001091;
1065 FMC_Bank1->BTCR[5] = 0x00110212;
1066 FMC_Bank1E->BWTR[4] = 0x0FFFFFFF;
1068 /*FMC controller Enable*/
1069 FMC_Bank1->BTCR[0] |= 0x80000000;
1071 #endif /* DATA_IN_ExtSRAM */
1073 #endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
1077 * @}
1081 * @}
1085 * @}
1087 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/