Blackbox device type 'file' (SITL) considered working when file handler is available
[inav.git] / src / main / target / system_stm32h7xx.c
blobcc580320b5a37ed06cb7ff8c63bf301403fb28b3
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 "platform.h"
66 #include "string.h"
67 #include "common/utils.h"
68 #include "drivers/system.h"
69 #include "build/debug.h"
71 void forcedSystemResetWithoutDisablingCaches(void);
73 #if !defined (HSE_VALUE)
74 #define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */
75 #endif /* HSE_VALUE */
77 #if !defined (CSI_VALUE)
78 #define CSI_VALUE ((uint32_t)4000000) /*!< Value of the Internal oscillator in Hz*/
79 #endif /* CSI_VALUE */
81 #if !defined (HSI_VALUE)
82 #define HSI_VALUE ((uint32_t)64000000) /*!< Value of the Internal oscillator in Hz*/
83 #endif /* HSI_VALUE */
86 /**
87 * @}
90 /** @addtogroup STM32H7xx_System_Private_TypesDefinitions
91 * @{
94 /**
95 * @}
98 /** @addtogroup STM32H7xx_System_Private_Defines
99 * @{
102 /************************* Miscellaneous Configuration ************************/
103 /*!< Uncomment the following line if you need to use external SRAM or SDRAM mounted
104 on EVAL board as data memory */
105 /*#define DATA_IN_ExtSRAM */
106 /*#define DATA_IN_ExtSDRAM*/
108 #if defined(DATA_IN_ExtSRAM) && defined(DATA_IN_ExtSDRAM)
109 #error "Please select DATA_IN_ExtSRAM or DATA_IN_ExtSDRAM "
110 #endif /* DATA_IN_ExtSRAM && DATA_IN_ExtSDRAM */
112 /*!< Uncomment the following line if you need to relocate your vector Table in
113 Internal SRAM. */
114 /* #define VECT_TAB_SRAM */
115 #define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field.
116 This value must be a multiple of 0x200. */
117 /******************************************************************************/
120 * @}
123 /** @addtogroup STM32H7xx_System_Private_Macros
124 * @{
128 * @}
131 /** @addtogroup STM32H7xx_System_Private_Variables
132 * @{
134 /* This variable is updated in three ways:
135 1) by calling CMSIS function SystemCoreClockUpdate()
136 2) by calling HAL API function HAL_RCC_GetHCLKFreq()
137 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
138 Note: If you use this function to configure the system clock; then there
139 is no need to call the 2 first functions listed above, since SystemCoreClock
140 variable is updated automatically.
142 uint32_t SystemCoreClock = 64000000;
143 uint32_t SystemD2Clock = 64000000;
144 const uint8_t D1CorePrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};
147 * @}
150 /** @addtogroup STM32H7xx_System_Private_FunctionPrototypes
151 * @{
153 #if defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
154 static void SystemInit_ExtMemCtl(void);
155 #endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
158 * @}
161 /** @addtogroup STM32H7xx_System_Private_Functions
162 * @{
165 static void Error_Handler(void)
167 while (1);
170 void HandleStuckSysTick(void)
172 uint32_t tickStart = HAL_GetTick();
173 uint32_t tickEnd = 0;
175 int attemptsRemaining = 80 * 1000;
176 while (((tickEnd = HAL_GetTick()) == tickStart) && --attemptsRemaining) {
177 // H7 at 400Mhz - attemptsRemaining was reduced by debug build: 5,550, release build: 33,245
180 if (tickStart == tickEnd) {
181 forcedSystemResetWithoutDisablingCaches();
185 typedef struct pllConfig_s {
186 uint16_t clockMhz;
187 uint8_t m;
188 uint16_t n;
189 uint8_t p;
190 uint8_t q;
191 uint8_t r;
192 uint32_t vos;
193 } pllConfig_t;
196 PLL1 configuration for different silicon revisions.
198 Note for future overclocking support.
200 - Rev.Y (and Rev.X), nominal max at 400MHz, runs stably overclocked to 480MHz.
201 - Rev.V, nominal max at 480MHz, runs stably at 540MHz, but not to 600MHz (VCO probably out of operating range)
203 - A possible frequency table would look something like this, and a revision
204 check logic would place a cap for Rev.Y and V.
206 400 420 440 460 (Rev.Y & V ends here) 480 500 520 540
209 // 400MHz for Rev.Y (and Rev.X)
210 pllConfig_t pll1ConfigRevY = {
211 .clockMhz = 400,
212 .m = 4,
213 .n = 400,
214 .p = 2,
215 .q = 8,
216 .r = 5,
217 .vos = PWR_REGULATOR_VOLTAGE_SCALE1
220 // 480MHz for Rev.V
221 pllConfig_t pll1ConfigRevV = {
222 .clockMhz = 480,
223 .m = 4,
224 .n = 480,
225 .p = 2,
226 .q = 8,
227 .r = 5,
228 .vos = PWR_REGULATOR_VOLTAGE_SCALE0
231 // HSE clock configuration, originally taken from
232 // STM32Cube_FW_H7_V1.3.0/Projects/STM32H743ZI-Nucleo/Examples/RCC/RCC_ClockConfig/Src/main.c
234 static void SystemClockHSE_Config(void)
236 RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
237 RCC_OscInitTypeDef RCC_OscInitStruct = {0};
239 #ifdef notdef
240 // CSI has been disabled at SystemInit().
241 // HAL_RCC_ClockConfig() will fail because CSIRDY is off.
243 /* -1- Select CSI as system clock source to allow modification of the PLL configuration */
245 RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_SYSCLK;
246 RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_CSI;
247 if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1) != HAL_OK) {
248 /* Initialization Error */
249 Error_Handler();
251 #endif
253 #ifdef USE_H7_LEGACY_CPU_REVISION_SPEED
254 pllConfig_t *pll1Config = &pll1ConfigRevY;
255 #else
256 pllConfig_t *pll1Config = (HAL_GetREVID() == REV_ID_V) ? &pll1ConfigRevV : &pll1ConfigRevY;
257 #endif
259 pll1Config->m = HSE_VALUE / 1000000 / 2; // correction for different HSE_VALUE
261 // Configure voltage scale.
262 // It has been pre-configured at PWR_REGULATOR_VOLTAGE_SCALE1,
263 // and it may stay or overridden by PWR_REGULATOR_VOLTAGE_SCALE0 depending on the clock config.
265 __HAL_PWR_VOLTAGESCALING_CONFIG(pll1Config->vos);
267 while (!__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY)) {
268 // Empty
271 /* -2- Enable HSE Oscillator, select it as PLL source and finally activate the PLL */
273 #define USE_H7_HSERDY_SLOW_WORKAROUND
274 #ifdef USE_H7_HSERDY_SLOW_WORKAROUND
276 // With reference to 2.3.22 in the ES0250 Errata for the L476.
277 // Applying the same workaround here in the vain hopes that it improves startup times.
278 // Randomly the HSERDY bit takes AGES, over 10 seconds, to be set.
280 __HAL_RCC_GPIOH_CLK_ENABLE();
282 HAL_GPIO_WritePin(GPIOH, GPIO_PIN_0 | GPIO_PIN_1, GPIO_PIN_RESET);
284 GPIO_InitTypeDef gpio_initstruct;
285 gpio_initstruct.Pin = GPIO_PIN_0 | GPIO_PIN_1;
286 gpio_initstruct.Mode = GPIO_MODE_OUTPUT_PP;
287 gpio_initstruct.Pull = GPIO_NOPULL;
288 gpio_initstruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
290 HAL_GPIO_Init(GPIOH, &gpio_initstruct);
291 #endif
293 RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
294 RCC_OscInitStruct.HSEState = RCC_HSE_ON; // Even Nucleo-H473 work without RCC_HSE_BYPASS
296 RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
297 RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
298 RCC_OscInitStruct.PLL.PLLM = pll1Config->m;
299 RCC_OscInitStruct.PLL.PLLN = pll1Config->n;
300 RCC_OscInitStruct.PLL.PLLP = pll1Config->p;
301 RCC_OscInitStruct.PLL.PLLQ = pll1Config->q;
302 RCC_OscInitStruct.PLL.PLLR = pll1Config->r;
304 RCC_OscInitStruct.PLL.PLLVCOSEL = RCC_PLL1VCOWIDE;
305 RCC_OscInitStruct.PLL.PLLRGE = RCC_PLL1VCIRANGE_2;
307 HAL_StatusTypeDef status = HAL_RCC_OscConfig(&RCC_OscInitStruct);
309 #define USE_H7_HSE_TIMEOUT_WORKAROUND
310 #ifdef USE_H7_HSE_TIMEOUT_WORKAROUND
311 if (status == HAL_TIMEOUT) {
312 forcedSystemResetWithoutDisablingCaches(); // DC - sometimes HSERDY gets stuck, waiting longer doesn't help.
314 #endif
316 if (status != HAL_OK) {
317 /* Initialization Error */
318 Error_Handler();
321 // Configure PLL2 and PLL3
322 // Use of PLL2 and PLL3 are not determined yet.
323 // A review of total system wide clock requirements is necessary.
326 // Configure SCGU (System Clock Generation Unit)
327 // Select PLL as system clock source and configure bus clock dividers.
329 // Clock type and divider member names do not have direct visual correspondence.
330 // Here is how these correspond:
331 // RCC_CLOCKTYPE_SYSCLK sys_ck
332 // RCC_CLOCKTYPE_HCLK AHBx (rcc_hclk1,rcc_hclk2,rcc_hclk3,rcc_hclk4)
333 // RCC_CLOCKTYPE_D1PCLK1 APB3 (rcc_pclk3)
334 // RCC_CLOCKTYPE_PCLK1 APB1 (rcc_pclk1)
335 // RCC_CLOCKTYPE_PCLK2 APB2 (rcc_pclk2)
336 // RCC_CLOCKTYPE_D3PCLK1 APB4 (rcc_pclk4)
338 RCC_ClkInitStruct.ClockType = ( \
339 RCC_CLOCKTYPE_SYSCLK | \
340 RCC_CLOCKTYPE_HCLK | \
341 RCC_CLOCKTYPE_D1PCLK1 | \
342 RCC_CLOCKTYPE_PCLK1 | \
343 RCC_CLOCKTYPE_PCLK2 | \
344 RCC_CLOCKTYPE_D3PCLK1);
345 RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; // = PLL1P = 400
346 RCC_ClkInitStruct.SYSCLKDivider = RCC_SYSCLK_DIV1; // = PLL1P(400) / 1 = 400
347 RCC_ClkInitStruct.AHBCLKDivider = RCC_HCLK_DIV2; // = SYSCLK(400) / 2 = 200
348 RCC_ClkInitStruct.APB3CLKDivider = RCC_APB3_DIV2; // = HCLK(200) / 2 = 100
349 RCC_ClkInitStruct.APB1CLKDivider = RCC_APB1_DIV2; // = HCLK(200) / 2 = 100
350 RCC_ClkInitStruct.APB2CLKDivider = RCC_APB2_DIV2; // = HCLK(200) / 2 = 100
351 RCC_ClkInitStruct.APB4CLKDivider = RCC_APB4_DIV2; // = HCLK(200) / 2 = 100
353 // For HCLK=200MHz with VOS1 range, ST recommended flash latency is 2WS.
354 // RM0433 (Rev.5) Table 12. FLASH recommended number of wait states and programming delay
356 // For higher HCLK frequency, VOS0 is available on RevV silicons, with FLASH wait states 4WS
357 // AN5312 (Rev.1) Section 1.2.1 Voltage scaling Table.1
359 if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK) {
360 /* Initialization Error */
361 Error_Handler();
364 /* -4- Optional: Disable CSI Oscillator (if the HSI is no more needed by the application)*/
365 RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_CSI;
366 RCC_OscInitStruct.CSIState = RCC_CSI_OFF;
367 RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
368 if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
369 /* Initialization Error */
370 Error_Handler();
374 void SystemClock_Config(void)
376 // Configure power supply
378 HAL_PWREx_ConfigSupply(PWR_LDO_SUPPLY);
380 // Pre-configure voltage scale to PWR_REGULATOR_VOLTAGE_SCALE1.
381 // SystemClockHSE_Config may configure PWR_REGULATOR_VOLTAGE_SCALE0.
383 __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
385 while (!__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY)) {
386 // Empty
389 SystemClockHSE_Config();
391 /*activate CSI clock mondatory for I/O Compensation Cell*/
393 __HAL_RCC_CSI_ENABLE() ;
395 /* Enable SYSCFG clock mondatory for I/O Compensation Cell */
397 __HAL_RCC_SYSCFG_CLK_ENABLE() ;
399 /* Enables the I/O Compensation Cell */
401 HAL_EnableCompensationCell();
403 HandleStuckSysTick();
405 HAL_Delay(10);
407 // Configure peripheral clocks
409 RCC_PeriphCLKInitTypeDef RCC_PeriphClkInit;
411 // Configure HSI48 as peripheral clock for USB
413 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USB;
414 RCC_PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_HSI48;
415 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
417 // Configure CRS for dynamic calibration of HSI48
418 // While ES0392 Rev 5 "STM32H742xI/G and STM32H743xI/G device limitations" states CRS not working for REV.Y,
419 // it is always turned on as it seems that it has no negative effect on clock accuracy.
421 RCC_CRSInitTypeDef crsInit = {
422 .Prescaler = RCC_CRS_SYNC_DIV1,
423 .Source = RCC_CRS_SYNC_SOURCE_USB2,
424 .Polarity = RCC_CRS_SYNC_POLARITY_RISING,
425 .ReloadValue = RCC_CRS_RELOADVALUE_DEFAULT,
426 .ErrorLimitValue = RCC_CRS_ERRORLIMIT_DEFAULT,
427 .HSI48CalibrationValue = RCC_CRS_HSI48CALIBRATION_DEFAULT,
430 __HAL_RCC_CRS_CLK_ENABLE();
431 HAL_RCCEx_CRSConfig(&crsInit);
433 #ifdef USE_CRS_INTERRUPTS
434 // Turn on USE_CRS_INTERRUPTS to see CRS in action
435 HAL_NVIC_SetPriority(CRS_IRQn, 6, 0);
436 HAL_NVIC_EnableIRQ(CRS_IRQn);
437 __HAL_RCC_CRS_ENABLE_IT(RCC_CRS_IT_SYNCOK|RCC_CRS_IT_SYNCWARN|RCC_CRS_IT_ESYNC|RCC_CRS_IT_ERR);
438 #endif
440 // Configure UART peripheral clock sources
442 // Possible sources:
443 // D2PCLK1 (pclk1 for APB1 = USART234578)
444 // D2PCLK2 (pclk2 for APB2 = USART16)
445 // PLL2 (pll2_q_ck)
446 // PLL3 (pll3_q_ck),
447 // HSI (hsi_ck),
448 // CSI (csi_ck),LSE(lse_ck);
450 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART16|RCC_PERIPHCLK_USART234578;
451 RCC_PeriphClkInit.Usart16ClockSelection = RCC_USART16CLKSOURCE_D2PCLK2;
452 RCC_PeriphClkInit.Usart234578ClockSelection = RCC_USART234578CLKSOURCE_D2PCLK1;
453 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
455 // Configure SPI peripheral clock sources
457 // Possible sources for SPI123:
458 // PLL (pll1_q_ck)
459 // PLL2 (pll2_p_ck)
460 // PLL3 (pll3_p_ck)
461 // PIN (I2S_CKIN)
462 // CLKP (per_ck)
463 // Possible sources for SPI45:
464 // D2PCLK1 (rcc_pclk2 = APB1) 100MHz
465 // PLL2 (pll2_q_ck)
466 // PLL3 (pll3_q_ck)
467 // HSI (hsi_ker_ck)
468 // CSI (csi_ker_ck)
469 // HSE (hse_ck)
470 // Possible sources for SPI6:
471 // D3PCLK1 (rcc_pclk4 = APB4) 100MHz
472 // PLL2 (pll2_q_ck)
473 // PLL3 (pll3_q_ck)
474 // HSI (hsi_ker_ck)
475 // CSI (csi_ker_ck)
476 // HSE (hse_ck)
478 // For the first cut, we use 100MHz from various sources
479 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_SPI123|RCC_PERIPHCLK_SPI45|RCC_PERIPHCLK_SPI6;
480 RCC_PeriphClkInit.Spi123ClockSelection = RCC_SPI123CLKSOURCE_PLL;
481 RCC_PeriphClkInit.Spi45ClockSelection = RCC_SPI45CLKSOURCE_D2PCLK1;
482 RCC_PeriphClkInit.Spi6ClockSelection = RCC_SPI6CLKSOURCE_D3PCLK1;
483 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
485 // Configure I2C peripheral clock sources
487 // Current source for I2C123:
488 // D2PCLK1 (rcc_pclk1 = APB1 peripheral clock)
490 // Current source for I2C4:
491 // D3PCLK1 (rcc_pclk4 = APB4 peripheral clock)
493 // Note that peripheral clock determination in bus_i2c_hal_init.c must be modified when the sources are modified.
495 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_I2C123|RCC_PERIPHCLK_I2C4;
496 RCC_PeriphClkInit.I2c123ClockSelection = RCC_I2C123CLKSOURCE_D2PCLK1;
497 RCC_PeriphClkInit.I2c4ClockSelection = RCC_I2C4CLKSOURCE_D3PCLK1;
498 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
500 #ifdef USE_SDCARD_SDIO
501 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_SDMMC;
502 RCC_PeriphClkInit.PLL2.PLL2M = 5;
503 RCC_PeriphClkInit.PLL2.PLL2N = 500;
504 RCC_PeriphClkInit.PLL2.PLL2P = 2; // 500Mhz
505 RCC_PeriphClkInit.PLL2.PLL2Q = 3; // 266Mhz - 133Mhz can be derived from this for for QSPI if flash chip supports the speed.
506 RCC_PeriphClkInit.PLL2.PLL2R = 4; // 200Mhz HAL LIBS REQUIRE 200MHZ SDMMC CLOCK, see HAL_SD_ConfigWideBusOperation, SDMMC_HSpeed_CLK_DIV, SDMMC_NSpeed_CLK_DIV
507 RCC_PeriphClkInit.PLL2.PLL2RGE = RCC_PLL2VCIRANGE_0;
508 RCC_PeriphClkInit.PLL2.PLL2VCOSEL = RCC_PLL2VCOWIDE;
509 RCC_PeriphClkInit.PLL2.PLL2FRACN = 0;
510 RCC_PeriphClkInit.SdmmcClockSelection = RCC_SDMMCCLKSOURCE_PLL2;
511 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
512 #endif
514 #ifdef USE_QUADSPI
515 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_QSPI;
516 RCC_PeriphClkInit.QspiClockSelection = RCC_QSPICLKSOURCE_D1HCLK;
517 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
518 #endif
520 // Configure MCO clocks for clock test/verification
522 // Possible sources for MCO1:
523 // RCC_MCO1SOURCE_HSI (hsi_ck)
524 // RCC_MCO1SOURCE_LSE (?)
525 // RCC_MCO1SOURCE_HSE (hse_ck)
526 // RCC_MCO1SOURCE_PLL1QCLK (pll1_q_ck)
527 // RCC_MCO1SOURCE_HSI48 (hsi48_ck)
529 // HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSE, RCC_MCODIV_1); // HSE(8M) / 1 = 1M
530 HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSI48, RCC_MCODIV_4); // HSI48(48M) / 4 = 12M
532 // Possible sources for MCO2:
533 // RCC_MCO2SOURCE_SYSCLK (sys_ck)
534 // RCC_MCO2SOURCE_PLL2PCLK (pll2_p_ck)
535 // RCC_MCO2SOURCE_HSE (hse_ck)
536 // RCC_MCO2SOURCE_PLLCLK (pll1_p_ck)
537 // RCC_MCO2SOURCE_CSICLK (csi_ck)
538 // RCC_MCO2SOURCE_LSICLK (lsi_ck)
540 HAL_RCC_MCOConfig(RCC_MCO2, RCC_MCO2SOURCE_PLLCLK, RCC_MCODIV_15); // PLL1P(400M) / 15 = 26.67M
543 #ifdef USE_CRS_INTERRUPTS
544 static uint32_t crs_syncok = 0;
545 static uint32_t crs_syncwarn = 0;
546 static uint32_t crs_expectedsync = 0;
547 static uint32_t crs_error = 0;
549 void HAL_RCCEx_CRS_SyncOkCallback(void)
551 ++crs_syncok;
554 void HAL_RCCEx_CRS_SyncWarnCallback(void)
556 ++crs_syncwarn;
559 void HAL_RCCEx_CRS_ExpectedSyncCallback(void)
561 ++crs_expectedsync;
564 void HAL_RCCEx_CRS_ErrorCallback(uint32_t Error)
566 ++crs_error;
569 void CRS_IRQHandler(void)
571 HAL_RCCEx_CRS_IRQHandler();
573 #endif
575 #include "build/debug.h"
577 void systemCheckResetReason(void);
579 #include "drivers/memprot.h"
581 void SystemInit (void)
583 memProtReset();
585 initialiseMemorySections();
587 // FPU settings
588 #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
589 SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); // Set CP10 and CP11 Full Access
590 #endif
592 // Reset the RCC clock configuration to the default reset state
593 // Set HSION bit
594 RCC->CR = RCC_CR_HSION;
596 // Reset CFGR register
597 RCC->CFGR = 0x00000000;
599 // Reset HSEON, CSSON , CSION,RC48ON, CSIKERON PLL1ON, PLL2ON and PLL3ON bits
601 // XXX Don't do this until we are established with clock handling
602 // RCC->CR &= (uint32_t)0xEAF6ED7F;
604 // Instead, we explicitly turn those on
605 RCC->CR |= RCC_CR_CSION;
606 RCC->CR |= RCC_CR_HSION;
607 RCC->CR |= RCC_CR_HSEON;
608 RCC->CR |= RCC_CR_HSI48ON;
610 /* Reset D1CFGR register */
611 RCC->D1CFGR = 0x00000000;
613 /* Reset D2CFGR register */
614 RCC->D2CFGR = 0x00000000;
616 /* Reset D3CFGR register */
617 RCC->D3CFGR = 0x00000000;
619 /* Reset PLLCKSELR register */
620 RCC->PLLCKSELR = 0x00000000;
622 /* Reset PLLCFGR register */
623 RCC->PLLCFGR = 0x00000000;
624 /* Reset PLL1DIVR register */
625 RCC->PLL1DIVR = 0x00000000;
626 /* Reset PLL1FRACR register */
627 RCC->PLL1FRACR = 0x00000000;
629 /* Reset PLL2DIVR register */
630 RCC->PLL2DIVR = 0x00000000;
632 /* Reset PLL2FRACR register */
634 RCC->PLL2FRACR = 0x00000000;
635 /* Reset PLL3DIVR register */
636 RCC->PLL3DIVR = 0x00000000;
638 /* Reset PLL3FRACR register */
639 RCC->PLL3FRACR = 0x00000000;
641 /* Reset HSEBYP bit */
642 RCC->CR &= (uint32_t)0xFFFBFFFF;
644 /* Disable all interrupts */
645 RCC->CIER = 0x00000000;
647 /* Change the switch matrix read issuing capability to 1 for the AXI SRAM target (Target 7) */
648 *((__IO uint32_t*)0x51008108) = 0x00000001;
650 #if defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
651 SystemInit_ExtMemCtl();
652 #endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
654 /* Configure the Vector Table location add offset address ------------------*/
655 #if defined(VECT_TAB_SRAM)
656 SCB->VTOR = D1_AXISRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal ITCMSRAM */
657 #elif defined(USE_EXST)
658 // Don't touch the vector table, the bootloader will have already set it.
659 #else
660 SCB->VTOR = FLASH_BANK1_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
661 #endif
663 #ifdef USE_HAL_DRIVER
664 HAL_Init();
665 #endif
667 SystemClock_Config();
668 SystemCoreClockUpdate();
670 // Configure MPU
672 memProtConfigure(mpuRegions, mpuRegionCount);
674 // Enable CPU L1-Cache
675 SCB_EnableICache();
676 SCB_EnableDCache();
680 * @brief Update SystemCoreClock variable according to Clock Register Values.
681 * The SystemCoreClock variable contains the core clock , it can
682 * be used by the user application to setup the SysTick timer or configure
683 * other parameters.
685 * @note Each time the core clock changes, this function must be called
686 * to update SystemCoreClock variable value. Otherwise, any configuration
687 * based on this variable will be incorrect.
689 * @note - The system frequency computed by this function is not the real
690 * frequency in the chip. It is calculated based on the predefined
691 * constant and the selected clock source:
693 * - If SYSCLK source is CSI, SystemCoreClock will contain the CSI_VALUE(*)
694 * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(**)
695 * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(***)
696 * - If SYSCLK source is PLL, SystemCoreClock will contain the CSI_VALUE(*),
697 * HSI_VALUE(**) or HSE_VALUE(***) multiplied/divided by the PLL factors.
699 * (*) CSI_VALUE is a constant defined in stm32h7xx_hal.h file (default value
700 * 4 MHz) but the real value may vary depending on the variations
701 * in voltage and temperature.
702 * (**) HSI_VALUE is a constant defined in stm32h7xx_hal.h file (default value
703 * 64 MHz) but the real value may vary depending on the variations
704 * in voltage and temperature.
706 * (***)HSE_VALUE is a constant defined in stm32h7xx_hal.h file (default value
707 * 25 MHz), user has to ensure that HSE_VALUE is same as the real
708 * frequency of the crystal used. Otherwise, this function may
709 * have wrong result.
711 * - The result of this function could be not correct when using fractional
712 * value for HSE crystal.
713 * @param None
714 * @retval None
717 void SystemCoreClockUpdate (void)
719 SystemCoreClock = HAL_RCC_GetSysClockFreq();
722 #if defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
724 * @brief Setup the external memory controller.
725 * Called in startup_stm32h7xx.s before jump to main.
726 * This function configures the external memories (SRAM/SDRAM)
727 * This SRAM/SDRAM will be used as program data memory (including heap and stack).
728 * @param None
729 * @retval None
731 void SystemInit_ExtMemCtl(void)
733 #if defined (DATA_IN_ExtSDRAM)
734 register uint32_t tmpreg = 0, timeout = 0xFFFF;
735 register __IO uint32_t index;
737 /* Enable GPIOD, GPIOE, GPIOF, GPIOG, GPIOH and GPIOI interface clock */
738 RCC->AHB4ENR |= 0x000001F8;
739 /* Connect PDx pins to FMC Alternate function */
740 GPIOD->AFR[0] = 0x000000CC;
741 GPIOD->AFR[1] = 0xCC000CCC;
742 /* Configure PDx pins in Alternate function mode */
743 GPIOD->MODER = 0xAFEAFFFA;
744 /* Configure PDx pins speed to 50 MHz */
745 GPIOD->OSPEEDR = 0xA02A000A;
746 /* Configure PDx pins Output type to push-pull */
747 GPIOD->OTYPER = 0x00000000;
748 /* No pull-up, pull-down for PDx pins */
749 GPIOD->PUPDR = 0x55555505;
750 /* Connect PEx pins to FMC Alternate function */
751 GPIOE->AFR[0] = 0xC00000CC;
752 GPIOE->AFR[1] = 0xCCCCCCCC;
753 /* Configure PEx pins in Alternate function mode */
754 GPIOE->MODER = 0xAAAABFFA;
755 /* Configure PEx pins speed to 50 MHz */
756 GPIOE->OSPEEDR = 0xAAAA800A;
757 /* Configure PEx pins Output type to push-pull */
758 GPIOE->OTYPER = 0x00000000;
759 /* No pull-up, pull-down for PEx pins */
760 GPIOE->PUPDR = 0x55554005;
761 /* Connect PFx pins to FMC Alternate function */
762 GPIOF->AFR[0] = 0x00CCCCCC;
763 GPIOF->AFR[1] = 0xCCCCC000;
764 /* Configure PFx pins in Alternate function mode */
765 GPIOF->MODER = 0xAABFFAAA;
766 /* Configure PFx pins speed to 50 MHz */
767 GPIOF->OSPEEDR = 0xAA800AAA;
768 /* Configure PFx pins Output type to push-pull */
769 GPIOF->OTYPER = 0x00000000;
770 /* No pull-up, pull-down for PFx pins */
771 GPIOF->PUPDR = 0x55400555;
772 /* Connect PGx pins to FMC Alternate function */
773 GPIOG->AFR[0] = 0x00CCCCCC;
774 GPIOG->AFR[1] = 0xC000000C;
775 /* Configure PGx pins in Alternate function mode */
776 GPIOG->MODER = 0xBFFEFAAA;
777 /* Configure PGx pins speed to 50 MHz */
778 GPIOG->OSPEEDR = 0x80020AAA;
779 /* Configure PGx pins Output type to push-pull */
780 GPIOG->OTYPER = 0x00000000;
781 /* No pull-up, pull-down for PGx pins */
782 GPIOG->PUPDR = 0x40010515;
783 /* Connect PHx pins to FMC Alternate function */
784 GPIOH->AFR[0] = 0xCCC00000;
785 GPIOH->AFR[1] = 0xCCCCCCCC;
786 /* Configure PHx pins in Alternate function mode */
787 GPIOH->MODER = 0xAAAAABFF;
788 /* Configure PHx pins speed to 50 MHz */
789 GPIOH->OSPEEDR = 0xAAAAA800;
790 /* Configure PHx pins Output type to push-pull */
791 GPIOH->OTYPER = 0x00000000;
792 /* No pull-up, pull-down for PHx pins */
793 GPIOH->PUPDR = 0x55555400;
794 /* Connect PIx pins to FMC Alternate function */
795 GPIOI->AFR[0] = 0xCCCCCCCC;
796 GPIOI->AFR[1] = 0x00000CC0;
797 /* Configure PIx pins in Alternate function mode */
798 GPIOI->MODER = 0xFFEBAAAA;
799 /* Configure PIx pins speed to 50 MHz */
800 GPIOI->OSPEEDR = 0x0028AAAA;
801 /* Configure PIx pins Output type to push-pull */
802 GPIOI->OTYPER = 0x00000000;
803 /* No pull-up, pull-down for PIx pins */
804 GPIOI->PUPDR = 0x00145555;
805 /*-- FMC Configuration ------------------------------------------------------*/
806 /* Enable the FMC interface clock */
807 (RCC->AHB3ENR |= (RCC_AHB3ENR_FMCEN));
808 /*SDRAM Timing and access interface configuration*/
809 /*LoadToActiveDelay = 2
810 ExitSelfRefreshDelay = 6
811 SelfRefreshTime = 4
812 RowCycleDelay = 6
813 WriteRecoveryTime = 2
814 RPDelay = 2
815 RCDDelay = 2
816 SDBank = FMC_SDRAM_BANK2
817 ColumnBitsNumber = FMC_SDRAM_COLUMN_BITS_NUM_9
818 RowBitsNumber = FMC_SDRAM_ROW_BITS_NUM_12
819 MemoryDataWidth = FMC_SDRAM_MEM_BUS_WIDTH_32
820 InternalBankNumber = FMC_SDRAM_INTERN_BANKS_NUM_4
821 CASLatency = FMC_SDRAM_CAS_LATENCY_2
822 WriteProtection = FMC_SDRAM_WRITE_PROTECTION_DISABLE
823 SDClockPeriod = FMC_SDRAM_CLOCK_PERIOD_2
824 ReadBurst = FMC_SDRAM_RBURST_ENABLE
825 ReadPipeDelay = FMC_SDRAM_RPIPE_DELAY_0*/
827 FMC_Bank5_6->SDCR[0] = 0x00001800;
828 FMC_Bank5_6->SDCR[1] = 0x00000165;
829 FMC_Bank5_6->SDTR[0] = 0x00105000;
830 FMC_Bank5_6->SDTR[1] = 0x01010351;
832 /* SDRAM initialization sequence */
833 /* Clock enable command */
834 FMC_Bank5_6->SDCMR = 0x00000009;
835 tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
836 while((tmpreg != 0) && (timeout-- > 0))
838 tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
841 /* Delay */
842 for (index = 0; index<1000; index++);
844 /* PALL command */
845 FMC_Bank5_6->SDCMR = 0x0000000A;
846 timeout = 0xFFFF;
847 while((tmpreg != 0) && (timeout-- > 0))
849 tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
852 FMC_Bank5_6->SDCMR = 0x000000EB;
853 timeout = 0xFFFF;
854 while((tmpreg != 0) && (timeout-- > 0))
856 tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
859 FMC_Bank5_6->SDCMR = 0x0004400C;
860 timeout = 0xFFFF;
861 while((tmpreg != 0) && (timeout-- > 0))
863 tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
865 /* Set refresh count */
866 tmpreg = FMC_Bank5_6->SDRTR;
867 FMC_Bank5_6->SDRTR = (tmpreg | (0x00000603<<1));
869 /* Disable write protection */
870 tmpreg = FMC_Bank5_6->SDCR[1];
871 FMC_Bank5_6->SDCR[1] = (tmpreg & 0xFFFFFDFF);
873 /*FMC controller Enable*/
874 FMC_Bank1->BTCR[0] |= 0x80000000;
877 #endif /* DATA_IN_ExtSDRAM */
879 #if defined(DATA_IN_ExtSRAM)
880 /*-- GPIOs Configuration -----------------------------------------------------*/
881 /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */
882 RCC->AHB4ENR |= 0x00000078;
884 /* Connect PDx pins to FMC Alternate function */
885 GPIOD->AFR[0] = 0x00CCC0CC;
886 GPIOD->AFR[1] = 0xCCCCCCCC;
887 /* Configure PDx pins in Alternate function mode */
888 GPIOD->MODER = 0xAAAA0A8A;
889 /* Configure PDx pins speed to 100 MHz */
890 GPIOD->OSPEEDR = 0xFFFF0FCF;
891 /* Configure PDx pins Output type to push-pull */
892 GPIOD->OTYPER = 0x00000000;
893 /* No pull-up, pull-down for PDx pins */
894 GPIOD->PUPDR = 0x55550545;
896 /* Connect PEx pins to FMC Alternate function */
897 GPIOE->AFR[0] = 0xC00CC0CC;
898 GPIOE->AFR[1] = 0xCCCCCCCC;
899 /* Configure PEx pins in Alternate function mode */
900 GPIOE->MODER = 0xAAAA828A;
901 /* Configure PEx pins speed to 100 MHz */
902 GPIOE->OSPEEDR = 0xFFFFC3CF;
903 /* Configure PEx pins Output type to push-pull */
904 GPIOE->OTYPER = 0x00000000;
905 /* No pull-up, pull-down for PEx pins */
906 GPIOE->PUPDR = 0x55554145;
908 /* Connect PFx pins to FMC Alternate function */
909 GPIOF->AFR[0] = 0x00CCCCCC;
910 GPIOF->AFR[1] = 0xCCCC0000;
911 /* Configure PFx pins in Alternate function mode */
912 GPIOF->MODER = 0xAA000AAA;
913 /* Configure PFx pins speed to 100 MHz */
914 GPIOF->OSPEEDR = 0xFF000FFF;
915 /* Configure PFx pins Output type to push-pull */
916 GPIOF->OTYPER = 0x00000000;
917 /* No pull-up, pull-down for PFx pins */
918 GPIOF->PUPDR = 0x55000555;
920 /* Connect PGx pins to FMC Alternate function */
921 GPIOG->AFR[0] = 0x00CCCCCC;
922 GPIOG->AFR[1] = 0x000000C0;
923 /* Configure PGx pins in Alternate function mode */
924 GPIOG->MODER = 0x00200AAA;
925 /* Configure PGx pins speed to 100 MHz */
926 GPIOG->OSPEEDR = 0x00300FFF;
927 /* Configure PGx pins Output type to push-pull */
928 GPIOG->OTYPER = 0x00000000;
929 /* No pull-up, pull-down for PGx pins */
930 GPIOG->PUPDR = 0x00100555;
932 /*-- FMC/FSMC Configuration --------------------------------------------------*/
933 /* Enable the FMC/FSMC interface clock */
934 (RCC->AHB3ENR |= (RCC_AHB3ENR_FMCEN));
936 /* Configure and enable Bank1_SRAM2 */
937 FMC_Bank1->BTCR[4] = 0x00001091;
938 FMC_Bank1->BTCR[5] = 0x00110212;
939 FMC_Bank1E->BWTR[4] = 0x0FFFFFFF;
941 /*FMC controller Enable*/
942 FMC_Bank1->BTCR[0] |= 0x80000000;
944 #endif /* DATA_IN_ExtSRAM */
946 #endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
950 * @}
954 * @}
958 * @}
960 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/