STM32H730 - Initial ST32H730 support.
[betaflight.git] / src / main / startup / system_stm32h7xx.c
blob890ed7ee578d015eea69ec4b16d690ca73ba41a9
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 <string.h>
66 #include "platform.h"
68 #include "common/utils.h"
70 #include "build/debug.h"
72 #include "drivers/memprot.h"
73 #include "drivers/system.h"
76 #if !defined (HSE_VALUE)
77 #define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */
78 #endif /* HSE_VALUE */
80 #if !defined (CSI_VALUE)
81 #define CSI_VALUE ((uint32_t)4000000) /*!< Value of the Internal oscillator in Hz*/
82 #endif /* CSI_VALUE */
84 #if !defined (HSI_VALUE)
85 #define HSI_VALUE ((uint32_t)64000000) /*!< Value of the Internal oscillator in Hz*/
86 #endif /* HSI_VALUE */
89 /**
90 * @}
93 /** @addtogroup STM32H7xx_System_Private_TypesDefinitions
94 * @{
97 /**
98 * @}
101 /** @addtogroup STM32H7xx_System_Private_Defines
102 * @{
105 /************************* Miscellaneous Configuration ************************/
106 /*!< Uncomment the following line if you need to use external SRAM or SDRAM mounted
107 on EVAL board as data memory */
108 /*#define DATA_IN_ExtSRAM */
109 /*#define DATA_IN_ExtSDRAM*/
111 #if defined(DATA_IN_ExtSRAM) && defined(DATA_IN_ExtSDRAM)
112 #error "Please select DATA_IN_ExtSRAM or DATA_IN_ExtSDRAM "
113 #endif /* DATA_IN_ExtSRAM && DATA_IN_ExtSDRAM */
115 /*!< Uncomment the following line if you need to relocate your vector Table in
116 Internal SRAM. */
117 /* #define VECT_TAB_SRAM */
118 #define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field.
119 This value must be a multiple of 0x200. */
120 /******************************************************************************/
123 * @}
126 /** @addtogroup STM32H7xx_System_Private_Macros
127 * @{
131 * @}
134 /** @addtogroup STM32H7xx_System_Private_Variables
135 * @{
137 /* This variable is updated in three ways:
138 1) by calling CMSIS function SystemCoreClockUpdate()
139 2) by calling HAL API function HAL_RCC_GetHCLKFreq()
140 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
141 Note: If you use this function to configure the system clock; then there
142 is no need to call the 2 first functions listed above, since SystemCoreClock
143 variable is updated automatically.
145 uint32_t SystemCoreClock = 64000000;
146 uint32_t SystemD2Clock = 64000000;
147 const uint8_t D1CorePrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};
150 * @}
153 /** @addtogroup STM32H7xx_System_Private_FunctionPrototypes
154 * @{
156 #if defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
157 static void SystemInit_ExtMemCtl(void);
158 #endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
161 * @}
164 /** @addtogroup STM32H7xx_System_Private_Functions
165 * @{
168 static void ErrorHandler(void)
170 while (1);
173 void HandleStuckSysTick(void)
175 uint32_t tickStart = HAL_GetTick();
176 uint32_t tickEnd = 0;
178 // H7 at 480Mhz requires a loop count of 160000. Double this for the timeout to be safe.
179 int attemptsRemaining = 320000;
180 while (((tickEnd = HAL_GetTick()) == tickStart) && --attemptsRemaining) {
183 if (tickStart == tickEnd) {
184 systemResetWithoutDisablingCaches();
188 typedef struct pllConfig_s {
189 uint16_t clockMhz;
190 uint8_t m;
191 uint16_t n;
192 uint8_t p;
193 uint8_t q;
194 uint8_t r;
195 uint32_t vos;
196 uint32_t vciRange;
197 } pllConfig_t;
199 #if defined(STM32H743xx) || defined(STM32H750xx)
201 PLL1 configuration for different silicon revisions of H743 and H750.
203 Note for future overclocking support.
205 - Rev.Y (and Rev.X), nominal max at 400MHz, runs stably overclocked to 480MHz.
206 - Rev.V, nominal max at 480MHz, runs stably at 540MHz, but not to 600MHz (VCO probably out of operating range)
208 - A possible frequency table would look something like this, and a revision
209 check logic would place a cap for Rev.Y and V.
211 400 420 440 460 (Rev.Y & V ends here) 480 500 520 540
214 // 400MHz for Rev.Y (and Rev.X)
215 pllConfig_t pll1ConfigRevY = {
216 .clockMhz = 400,
217 .m = 4,
218 .n = 400,
219 .p = 2,
220 .q = 8,
221 .r = 5,
222 .vos = PWR_REGULATOR_VOLTAGE_SCALE1,
223 .vciRange = RCC_PLL1VCIRANGE_2,
226 // 480MHz for Rev.V
227 pllConfig_t pll1ConfigRevV = {
228 .clockMhz = 480,
229 .m = 4,
230 .n = 480,
231 .p = 2,
232 .q = 8,
233 .r = 5,
234 .vos = PWR_REGULATOR_VOLTAGE_SCALE0,
235 .vciRange = RCC_PLL1VCIRANGE_2,
238 #define MCU_HCLK_DIVIDER RCC_HCLK_DIV2
240 // H743 and H750
241 // For HCLK=200MHz with VOS1 range, ST recommended flash latency is 2WS.
242 // RM0433 (Rev.5) Table 12. FLASH recommended number of wait states and programming delay
244 // For higher HCLK frequency, VOS0 is available on RevV silicons, with FLASH wait states 4WS
245 // AN5312 (Rev.1) Section 1.2.1 Voltage scaling Table.1
247 // XXX Check if Rev.V requires a different value
249 #define MCU_FLASH_LATENCY FLASH_LATENCY_2
251 // Source for CRS input
252 #define MCU_RCC_CRS_SYNC_SOURCE RCC_CRS_SYNC_SOURCE_USB2
254 // Workaround for weird HSE behaviors
255 // (Observed only on Rev.V H750, but may also apply to H743 and Rev.V.)
256 #define USE_H7_HSERDY_SLOW_WORKAROUND
257 #define USE_H7_HSE_TIMEOUT_WORKAROUND
259 #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
261 // Nominal max 280MHz with 8MHz HSE
262 // (340 is okay, 360 doesn't work.)
265 pllConfig_t pll1Config7A3 = {
266 .clockMhz = 280,
267 .m = 4,
268 .n = 280,
269 .p = 2,
270 .q = 8,
271 .r = 5,
272 .vos = PWR_REGULATOR_VOLTAGE_SCALE0,
273 .vciRange = RCC_PLL1VCIRANGE_1,
276 // Unlike H743/H750, HCLK can be directly fed with SYSCLK.
277 #define MCU_HCLK_DIVIDER RCC_HCLK_DIV1
279 // RM0455 (Rev.6) Table 15. FLASH recommended number of wait states and programming delay
280 // 280MHz at VOS0 is 6WS
282 #define MCU_FLASH_LATENCY FLASH_LATENCY_6
284 // Source for CRS input
285 #define MCU_RCC_CRS_SYNC_SOURCE RCC_CRS_SYNC_SOURCE_USB1
287 #elif defined(STM32H723xx) || defined(STM32H725xx)
289 // Nominal max 550MHz
291 pllConfig_t pll1Config72x = {
292 .clockMhz = 550,
293 .m = 4,
294 .n = 275,
295 .p = 1,
296 .q = 2,
297 .r = 2,
298 .vos = PWR_REGULATOR_VOLTAGE_SCALE0,
299 .vciRange = RCC_PLL1VCIRANGE_1,
302 #define MCU_HCLK_DIVIDER RCC_HCLK_DIV2
304 // RM0468 (Rev.2) Table 16.
305 // 550MHz (AXI Interface clock) at VOS0 is 3WS
306 #define MCU_FLASH_LATENCY FLASH_LATENCY_3
308 #define MCU_RCC_CRS_SYNC_SOURCE RCC_CRS_SYNC_SOURCE_USB1
310 #elif defined(STM32H730xx)
312 // 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.
313 // 4.9.24 FLASH option status register 2 (FLASH_OPTSR2_CUR)
314 // "Bit 2CPUFREQ_BOOST: CPU frequency boost status bitThis 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"
315 // ...
316 // So use 520Mhz so that OCTOSPI clk can be 200Mhz with OCTOPSI prescaler 2 via PLL2R or 130Mhz with OCTOPSI prescaler 1 via PLL1Q
318 pllConfig_t pll1Config73x = {
319 .clockMhz = 520,
320 .m = 2,
321 .n = 130,
322 .p = 1,
323 .q = 4,
324 .r = 2,
325 .vos = PWR_REGULATOR_VOLTAGE_SCALE0,
326 .vciRange = RCC_PLL1VCIRANGE_1,
329 #define MCU_HCLK_DIVIDER RCC_HCLK_DIV2
331 // RM0468 (Rev.2) Table 16.
332 // 520MHz (AXI Interface clock) at VOS0 is 3WS
333 #define MCU_FLASH_LATENCY FLASH_LATENCY_3
335 #define MCU_RCC_CRS_SYNC_SOURCE RCC_CRS_SYNC_SOURCE_USB1
337 #else
338 #error Unknown MCU type
339 #endif
341 // HSE clock configuration, originally taken from
342 // STM32Cube_FW_H7_V1.3.0/Projects/STM32H743ZI-Nucleo/Examples/RCC/RCC_ClockConfig/Src/main.c
343 static void SystemClockHSE_Config(void)
345 RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
346 RCC_OscInitTypeDef RCC_OscInitStruct = {0};
348 #ifdef notdef
349 // CSI has been disabled at SystemInit().
350 // HAL_RCC_ClockConfig() will fail because CSIRDY is off.
352 /* -1- Select CSI as system clock source to allow modification of the PLL configuration */
354 RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_SYSCLK;
355 RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_CSI;
356 if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1) != HAL_OK) {
357 /* Initialization Error */
358 ErrorHandler();
360 #endif
362 pllConfig_t *pll1Config;
364 #if defined(STM32H743xx) || defined(STM32H750xx)
365 pll1Config = (HAL_GetREVID() == REV_ID_V) ? &pll1ConfigRevV : &pll1ConfigRevY;
366 #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
367 pll1Config = &pll1Config7A3;
368 #elif defined(STM32H723xx) || defined(STM32H725xx)
369 pll1Config = &pll1Config72x;
370 #elif defined(STM32H730xx)
371 pll1Config = &pll1Config73x;
372 #else
373 #error Unknown MCU type
374 #endif
376 // Configure voltage scale.
377 // It has been pre-configured at PWR_REGULATOR_VOLTAGE_SCALE1,
378 // and it may stay or overridden by PWR_REGULATOR_VOLTAGE_SCALE0 depending on the clock config.
380 __HAL_PWR_VOLTAGESCALING_CONFIG(pll1Config->vos);
382 while (!__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY)) {
383 // Empty
386 /* -2- Enable HSE Oscillator, select it as PLL source and finally activate the PLL */
388 #ifdef USE_H7_HSERDY_SLOW_WORKAROUND
389 // With reference to 2.3.22 in the ES0250 Errata for the L476.
390 // Applying the same workaround here in the vain hopes that it improves startup times.
391 // Randomly the HSERDY bit takes AGES, over 10 seconds, to be set.
393 __HAL_RCC_GPIOH_CLK_ENABLE();
395 HAL_GPIO_WritePin(GPIOH, GPIO_PIN_0 | GPIO_PIN_1, GPIO_PIN_RESET);
397 GPIO_InitTypeDef gpio_initstruct;
398 gpio_initstruct.Pin = GPIO_PIN_0 | GPIO_PIN_1;
399 gpio_initstruct.Mode = GPIO_MODE_OUTPUT_PP;
400 gpio_initstruct.Pull = GPIO_NOPULL;
401 gpio_initstruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
403 HAL_GPIO_Init(GPIOH, &gpio_initstruct);
404 #endif
406 RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
407 RCC_OscInitStruct.HSEState = RCC_HSE_ON; // Even Nucleo-H473ZI and Nucleo-H7A3ZI work without RCC_HSE_BYPASS
409 RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
410 RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
411 RCC_OscInitStruct.PLL.PLLM = pll1Config->m;
412 RCC_OscInitStruct.PLL.PLLN = pll1Config->n;
413 RCC_OscInitStruct.PLL.PLLP = pll1Config->p;
414 RCC_OscInitStruct.PLL.PLLQ = pll1Config->q;
415 RCC_OscInitStruct.PLL.PLLR = pll1Config->r;
417 RCC_OscInitStruct.PLL.PLLVCOSEL = RCC_PLL1VCOWIDE;
418 RCC_OscInitStruct.PLL.PLLRGE = pll1Config->vciRange;
419 HAL_StatusTypeDef status = HAL_RCC_OscConfig(&RCC_OscInitStruct);
421 #ifdef USE_H7_HSE_TIMEOUT_WORKAROUND
422 if (status == HAL_TIMEOUT) {
423 systemResetWithoutDisablingCaches(); // DC - sometimes HSERDY gets stuck, waiting longer doesn't help.
425 #endif
427 if (status != HAL_OK) {
428 /* Initialization Error */
429 ErrorHandler();
432 // Configure PLL2 and PLL3
433 // Use of PLL2 and PLL3 are not determined yet.
434 // A review of total system wide clock requirements is necessary.
437 // Configure SCGU (System Clock Generation Unit)
438 // Select PLL as system clock source and configure bus clock dividers.
440 // Clock type and divider member names do not have direct visual correspondence.
441 // Here is how these correspond:
442 // RCC_CLOCKTYPE_SYSCLK sys_ck
443 // RCC_CLOCKTYPE_HCLK AHBx (rcc_hclk1,rcc_hclk2,rcc_hclk3,rcc_hclk4)
444 // RCC_CLOCKTYPE_D1PCLK1 APB3 (rcc_pclk3)
445 // RCC_CLOCKTYPE_PCLK1 APB1 (rcc_pclk1)
446 // RCC_CLOCKTYPE_PCLK2 APB2 (rcc_pclk2)
447 // RCC_CLOCKTYPE_D3PCLK1 APB4 (rcc_pclk4)
449 RCC_ClkInitStruct.ClockType = ( \
450 RCC_CLOCKTYPE_SYSCLK | \
451 RCC_CLOCKTYPE_HCLK | \
452 RCC_CLOCKTYPE_D1PCLK1 | \
453 RCC_CLOCKTYPE_PCLK1 | \
454 RCC_CLOCKTYPE_PCLK2 | \
455 RCC_CLOCKTYPE_D3PCLK1);
456 RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
457 RCC_ClkInitStruct.SYSCLKDivider = RCC_SYSCLK_DIV1;
459 RCC_ClkInitStruct.AHBCLKDivider = MCU_HCLK_DIVIDER;
460 RCC_ClkInitStruct.APB3CLKDivider = RCC_APB3_DIV2;
461 RCC_ClkInitStruct.APB1CLKDivider = RCC_APB1_DIV2;
462 RCC_ClkInitStruct.APB2CLKDivider = RCC_APB2_DIV2;
463 RCC_ClkInitStruct.APB4CLKDivider = RCC_APB4_DIV2;
465 if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, MCU_FLASH_LATENCY) != HAL_OK) {
466 /* Initialization Error */
467 ErrorHandler();
470 /* -4- Optional: Disable CSI Oscillator (if the HSI is no more needed by the application)*/
471 RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_CSI;
472 RCC_OscInitStruct.CSIState = RCC_CSI_OFF;
473 RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
474 if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
475 /* Initialization Error */
476 ErrorHandler();
480 void SystemClock_Config(void)
482 // Configure power supply
484 #if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H7A3xx) || defined(STM32H730xx)
485 // Legacy H7 devices (H743, H750) and newer but SMPS-less devices(H7A3, H723, H730)
487 HAL_PWREx_ConfigSupply(PWR_LDO_SUPPLY);
489 // Pre-configure voltage scale to PWR_REGULATOR_VOLTAGE_SCALE1.
490 // SystemClockHSE_Config may configure PWR_REGULATOR_VOLTAGE_SCALE0.
492 __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
494 #elif defined(STM32H7A3xxQ) || defined(STM32H725xx)
496 // We assume all SMPS equipped devices use this mode (Direct SMPS).
497 // - All STM32H7A3xxQ devices.
498 // - All STM32H725xx devices (Note STM32H725RG is Direct SMPS only - no LDO).
500 // Note that:
501 // - Nucleo-H7A3ZI-Q is preconfigured for power supply configuration 2 (Direct SMPS).
502 // - Nucleo-H723ZI-Q transplanted with STM32H725ZG is the same as above.
504 HAL_PWREx_ConfigSupply(PWR_DIRECT_SMPS_SUPPLY);
506 __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE0);
508 #else
509 #error Unknown MCU
510 #endif
512 while (!__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY)) {
513 // Empty
516 SystemClockHSE_Config();
518 /*activate CSI clock mondatory for I/O Compensation Cell*/
520 __HAL_RCC_CSI_ENABLE() ;
522 /* Enable SYSCFG clock mondatory for I/O Compensation Cell */
524 __HAL_RCC_SYSCFG_CLK_ENABLE() ;
526 /* Enables the I/O Compensation Cell */
528 HAL_EnableCompensationCell();
530 HandleStuckSysTick();
532 HAL_Delay(10);
534 // Configure peripheral clocks
536 RCC_PeriphCLKInitTypeDef RCC_PeriphClkInit;
538 // Configure HSI48 as peripheral clock for USB
540 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USB;
541 RCC_PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_HSI48;
542 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
544 // Configure CRS for dynamic calibration of HSI48
545 // While ES0392 Rev 5 "STM32H742xI/G and STM32H743xI/G device limitations" states CRS not working for REV.Y,
546 // it is always turned on as it seems that it has no negative effect on clock accuracy.
548 RCC_CRSInitTypeDef crsInit = {
549 .Prescaler = RCC_CRS_SYNC_DIV1,
550 .Source = MCU_RCC_CRS_SYNC_SOURCE,
551 .Polarity = RCC_CRS_SYNC_POLARITY_RISING,
552 .ReloadValue = RCC_CRS_RELOADVALUE_DEFAULT,
553 .ErrorLimitValue = RCC_CRS_ERRORLIMIT_DEFAULT,
554 .HSI48CalibrationValue = RCC_CRS_HSI48CALIBRATION_DEFAULT,
557 __HAL_RCC_CRS_CLK_ENABLE();
558 HAL_RCCEx_CRSConfig(&crsInit);
560 #ifdef USE_CRS_INTERRUPTS
561 // Turn on USE_CRS_INTERRUPTS to see CRS in action
562 HAL_NVIC_SetPriority(CRS_IRQn, 6, 0);
563 HAL_NVIC_EnableIRQ(CRS_IRQn);
564 __HAL_RCC_CRS_ENABLE_IT(RCC_CRS_IT_SYNCOK|RCC_CRS_IT_SYNCWARN|RCC_CRS_IT_ESYNC|RCC_CRS_IT_ERR);
565 #endif
567 // Configure UART peripheral clock sources
569 // Possible sources:
570 // D2PCLK1 (pclk1 for APB1 = USART234578)
571 // D2PCLK2 (pclk2 for APB2 = USART16)
572 // PLL2 (pll2_q_ck)
573 // PLL3 (pll3_q_ck),
574 // HSI (hsi_ck),
575 // CSI (csi_ck),LSE(lse_ck);
577 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART16|RCC_PERIPHCLK_USART234578;
578 RCC_PeriphClkInit.Usart16ClockSelection = RCC_USART16CLKSOURCE_D2PCLK2;
579 RCC_PeriphClkInit.Usart234578ClockSelection = RCC_USART234578CLKSOURCE_D2PCLK1;
580 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
582 // Configure SPI peripheral clock sources
584 // Possible sources for SPI123:
585 // PLL (pll1_q_ck)
586 // PLL2 (pll2_p_ck)
587 // PLL3 (pll3_p_ck)
588 // PIN (I2S_CKIN)
589 // CLKP (per_ck)
590 // Possible sources for SPI45:
591 // D2PCLK1 (rcc_pclk2 = APB1) 100MHz
592 // PLL2 (pll2_q_ck)
593 // PLL3 (pll3_q_ck)
594 // HSI (hsi_ker_ck)
595 // CSI (csi_ker_ck)
596 // HSE (hse_ck)
597 // Possible sources for SPI6:
598 // D3PCLK1 (rcc_pclk4 = APB4) 100MHz
599 // PLL2 (pll2_q_ck)
600 // PLL3 (pll3_q_ck)
601 // HSI (hsi_ker_ck)
602 // CSI (csi_ker_ck)
603 // HSE (hse_ck)
605 // We use 100MHz for Rev.Y and 120MHz for Rev.V from various sources
607 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_SPI123|RCC_PERIPHCLK_SPI45|RCC_PERIPHCLK_SPI6;
608 RCC_PeriphClkInit.Spi123ClockSelection = RCC_SPI123CLKSOURCE_PLL;
609 RCC_PeriphClkInit.Spi45ClockSelection = RCC_SPI45CLKSOURCE_D2PCLK1;
610 RCC_PeriphClkInit.Spi6ClockSelection = RCC_SPI6CLKSOURCE_D3PCLK1;
611 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
613 // Configure I2C peripheral clock sources
615 // Current source for I2C123:
616 // D2PCLK1 (rcc_pclk1 = APB1 peripheral clock)
618 // Current source for I2C4:
619 // D3PCLK1 (rcc_pclk4 = APB4 peripheral clock)
621 // Note that peripheral clock determination in bus_i2c_hal_init.c must be modified when the sources are modified.
623 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_I2C123|RCC_PERIPHCLK_I2C4;
624 RCC_PeriphClkInit.I2c123ClockSelection = RCC_I2C123CLKSOURCE_D2PCLK1;
625 RCC_PeriphClkInit.I2c4ClockSelection = RCC_I2C4CLKSOURCE_D3PCLK1;
626 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
628 #ifdef USE_SDCARD_SDIO
629 __HAL_RCC_SDMMC1_CLK_ENABLE(); // FIXME enable SDMMC1 or SDMMC2 depending on target.
631 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_SDMMC;
633 # if (HSE_VALUE != 8000000)
634 # error Unsupported external oscillator speed. The calculations below are based on 8Mhz resonators
635 // if you are seeing this, then calculate the PLL2 settings for your resonator and add support as required.
636 # else
637 # if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H725xx)
638 RCC_PeriphClkInit.PLL2.PLL2M = 5;
639 RCC_PeriphClkInit.PLL2.PLL2N = 500; // 8Mhz (Oscillator Frequency) / 5 (PLL2M) = 1.6 * 500 (PLL2N) = 800Mhz.
640 RCC_PeriphClkInit.PLL2.PLL2VCOSEL = RCC_PLL2VCOWIDE; // Wide VCO range:192 to 836 MHz
641 RCC_PeriphClkInit.PLL2.PLL2RGE = RCC_PLL2VCIRANGE_0; // PLL2 input between 1 and 2Mhz (1.6)
642 RCC_PeriphClkInit.PLL2.PLL2FRACN = 0;
644 RCC_PeriphClkInit.PLL2.PLL2P = 2; // 800Mhz / 2 = 400Mhz
645 RCC_PeriphClkInit.PLL2.PLL2Q = 3; // 800Mhz / 3 = 266Mhz // 133Mhz can be derived from this for for QSPI if flash chip supports the speed.
646 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
647 # elif defined(STM32H730xx)
648 RCC_PeriphClkInit.PLL2.PLL2M = 8;
649 RCC_PeriphClkInit.PLL2.PLL2N = 400; // 8Mhz (Oscillator Frequency) / 8 (PLL2M) = 1.0 * 400 (PLL2N) = 400Mhz.
650 RCC_PeriphClkInit.PLL2.PLL2VCOSEL = RCC_PLL2VCOMEDIUM; // Medium VCO range:150 to 420 MHz
651 RCC_PeriphClkInit.PLL2.PLL2RGE = RCC_PLL2VCIRANGE_0; // PLL2 input between 1 and 2Mhz (1.0)
652 RCC_PeriphClkInit.PLL2.PLL2FRACN = 0;
654 RCC_PeriphClkInit.PLL2.PLL2P = 3; // 400Mhz / 3 = 133Mhz // ADC does't like much higher when using PLL2P
655 RCC_PeriphClkInit.PLL2.PLL2Q = 3; // 400Mhz / 3 = 133Mhz // SPI6 does't like much higher when using PLL2Q
656 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
657 # else
658 # error Unknown MCU type
659 # endif
660 RCC_PeriphClkInit.SdmmcClockSelection = RCC_SDMMCCLKSOURCE_PLL2;
661 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
662 # endif
663 #endif
665 RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC;
666 RCC_PeriphClkInit.AdcClockSelection = RCC_ADCCLKSOURCE_CLKP;
667 HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);
669 // TODO H730 OCTOSPI clock for 100Mhz flash chips should use PLL2R at 200Mhz
671 // Configure MCO clocks for clock test/verification
673 // Possible sources for MCO1:
674 // RCC_MCO1SOURCE_HSI (hsi_ck)
675 // RCC_MCO1SOURCE_LSE (?)
676 // RCC_MCO1SOURCE_HSE (hse_ck)
677 // RCC_MCO1SOURCE_PLL1QCLK (pll1_q_ck)
678 // RCC_MCO1SOURCE_HSI48 (hsi48_ck)
680 // HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSE, RCC_MCODIV_1); // HSE(8M) / 1 = 1M
681 HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSI48, RCC_MCODIV_4); // HSI48(48M) / 4 = 12M
683 // Possible sources for MCO2:
684 // RCC_MCO2SOURCE_SYSCLK (sys_ck)
685 // RCC_MCO2SOURCE_PLL2PCLK (pll2_p_ck)
686 // RCC_MCO2SOURCE_HSE (hse_ck)
687 // RCC_MCO2SOURCE_PLLCLK (pll1_p_ck)
688 // RCC_MCO2SOURCE_CSICLK (csi_ck)
689 // RCC_MCO2SOURCE_LSICLK (lsi_ck)
691 HAL_RCC_MCOConfig(RCC_MCO2, RCC_MCO2SOURCE_PLLCLK, RCC_MCODIV_15); // PLL1P(400M) / 15 = 26.67M
694 #ifdef USE_CRS_INTERRUPTS
695 static uint32_t crs_syncok = 0;
696 static uint32_t crs_syncwarn = 0;
697 static uint32_t crs_expectedsync = 0;
698 static uint32_t crs_error = 0;
700 void HAL_RCCEx_CRS_SyncOkCallback(void)
702 ++crs_syncok;
705 void HAL_RCCEx_CRS_SyncWarnCallback(void)
707 ++crs_syncwarn;
710 void HAL_RCCEx_CRS_ExpectedSyncCallback(void)
712 ++crs_expectedsync;
715 void HAL_RCCEx_CRS_ErrorCallback(uint32_t Error)
717 ++crs_error;
720 void CRS_IRQHandler(void)
722 HAL_RCCEx_CRS_IRQHandler();
724 #endif
726 void SystemInit (void)
728 memProtReset();
730 initialiseMemorySections();
732 #if !defined(USE_EXST)
733 // only stand-alone and bootloader firmware needs to do this.
734 // if it's done in the EXST firmware as well as the BOOTLOADER firmware you get a reset loop.
735 systemProcessResetReason();
736 #endif
738 // FPU settings
739 #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
740 SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); // Set CP10 and CP11 Full Access
741 #endif
743 // Reset the RCC clock configuration to the default reset state
744 // Set HSION bit
745 RCC->CR = RCC_CR_HSION;
747 // Reset CFGR register
748 RCC->CFGR = 0x00000000;
750 // Reset HSEON, CSSON , CSION,RC48ON, CSIKERON PLL1ON, PLL2ON and PLL3ON bits
752 // XXX Don't do this until we are established with clock handling
753 // RCC->CR &= (uint32_t)0xEAF6ED7F;
755 // Instead, we explicitly turn those on
756 RCC->CR |= RCC_CR_CSION;
757 RCC->CR |= RCC_CR_HSION;
758 RCC->CR |= RCC_CR_HSEON;
759 RCC->CR |= RCC_CR_HSI48ON;
761 #if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx)
762 /* Reset D1CFGR register */
763 RCC->D1CFGR = 0x00000000;
765 /* Reset D2CFGR register */
766 RCC->D2CFGR = 0x00000000;
768 /* Reset D3CFGR register */
769 RCC->D3CFGR = 0x00000000;
770 #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
771 /* Reset CDCFGR1 register */
772 RCC->CDCFGR1 = 0x00000000;
774 /* Reset CDCFGR2 register */
775 RCC->CDCFGR2 = 0x00000000;
777 /* Reset SRDCFGR register */
778 RCC->SRDCFGR = 0x00000000;
779 #endif
781 /* Reset PLLCKSELR register */
782 RCC->PLLCKSELR = 0x00000000;
784 /* Reset PLLCFGR register */
785 RCC->PLLCFGR = 0x00000000;
786 /* Reset PLL1DIVR register */
787 RCC->PLL1DIVR = 0x00000000;
788 /* Reset PLL1FRACR register */
789 RCC->PLL1FRACR = 0x00000000;
791 /* Reset PLL2DIVR register */
792 RCC->PLL2DIVR = 0x00000000;
794 /* Reset PLL2FRACR register */
796 RCC->PLL2FRACR = 0x00000000;
797 /* Reset PLL3DIVR register */
798 RCC->PLL3DIVR = 0x00000000;
800 /* Reset PLL3FRACR register */
801 RCC->PLL3FRACR = 0x00000000;
803 /* Reset HSEBYP bit */
804 RCC->CR &= (uint32_t)0xFFFBFFFF;
806 /* Disable all interrupts */
807 RCC->CIER = 0x00000000;
809 /* Change the switch matrix read issuing capability to 1 for the AXI SRAM target (Target 7) */
810 *((__IO uint32_t*)0x51008108) = 0x00000001;
812 #if defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
813 SystemInit_ExtMemCtl();
814 #endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
816 /* Configure the Vector Table location add offset address ------------------*/
817 #if defined(VECT_TAB_SRAM)
818 #if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx)
819 SCB->VTOR = D1_AXISRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal ITCMSRAM */
820 #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
821 SCB->VTOR = CD_AXISRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal ITCMSRAM */
822 #else
823 #error Unknown MCU type
824 #endif
825 #elif defined(USE_EXST)
826 extern uint8_t isr_vector_table_base;
828 SCB->VTOR = (uint32_t)&isr_vector_table_base;
829 #if defined(STM32H730xx)
830 /* Configure the Vector Table location add offset address ------------------*/
832 extern uint8_t isr_vector_table_flash_base;
833 extern uint8_t isr_vector_table_end;
835 extern uint8_t ram_isr_vector_table_base;
837 memcpy(&ram_isr_vector_table_base, &isr_vector_table_flash_base, (size_t) (&isr_vector_table_end - &isr_vector_table_base));
839 SCB->VTOR = (uint32_t)&ram_isr_vector_table_base;
840 #endif
841 #else
842 SCB->VTOR = FLASH_BANK1_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
843 #endif
845 #ifdef USE_HAL_DRIVER
846 HAL_Init();
847 #endif
849 SystemClock_Config();
850 SystemCoreClockUpdate();
852 #ifdef STM32H7
853 initialiseD2MemorySections();
854 #endif
856 // Configure MPU
858 memProtConfigure(mpuRegions, mpuRegionCount);
860 // Enable CPU L1-Cache
861 SCB_EnableICache();
862 SCB_EnableDCache();
866 * @brief Update SystemCoreClock variable according to Clock Register Values.
867 * The SystemCoreClock variable contains the core clock , it can
868 * be used by the user application to setup the SysTick timer or configure
869 * other parameters.
871 * @note Each time the core clock changes, this function must be called
872 * to update SystemCoreClock variable value. Otherwise, any configuration
873 * based on this variable will be incorrect.
875 * @note - The system frequency computed by this function is not the real
876 * frequency in the chip. It is calculated based on the predefined
877 * constant and the selected clock source:
879 * - If SYSCLK source is CSI, SystemCoreClock will contain the CSI_VALUE(*)
880 * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(**)
881 * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(***)
882 * - If SYSCLK source is PLL, SystemCoreClock will contain the CSI_VALUE(*),
883 * HSI_VALUE(**) or HSE_VALUE(***) multiplied/divided by the PLL factors.
885 * (*) CSI_VALUE is a constant defined in stm32h7xx_hal.h file (default value
886 * 4 MHz) but the real value may vary depending on the variations
887 * in voltage and temperature.
888 * (**) HSI_VALUE is a constant defined in stm32h7xx_hal.h file (default value
889 * 64 MHz) but the real value may vary depending on the variations
890 * in voltage and temperature.
892 * (***)HSE_VALUE is a constant defined in stm32h7xx_hal.h file (default value
893 * 25 MHz), user has to ensure that HSE_VALUE is same as the real
894 * frequency of the crystal used. Otherwise, this function may
895 * have wrong result.
897 * - The result of this function could be not correct when using fractional
898 * value for HSE crystal.
899 * @param None
900 * @retval None
903 void SystemCoreClockUpdate (void)
905 SystemCoreClock = HAL_RCC_GetSysClockFreq();
908 #if defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
910 * @brief Setup the external memory controller.
911 * Called in startup_stm32h7xx.s before jump to main.
912 * This function configures the external memories (SRAM/SDRAM)
913 * This SRAM/SDRAM will be used as program data memory (including heap and stack).
914 * @param None
915 * @retval None
917 void SystemInit_ExtMemCtl(void)
919 #if defined (DATA_IN_ExtSDRAM)
920 register uint32_t tmpreg = 0, timeout = 0xFFFF;
921 register __IO uint32_t index;
923 /* Enable GPIOD, GPIOE, GPIOF, GPIOG, GPIOH and GPIOI interface clock */
924 RCC->AHB4ENR |= 0x000001F8;
925 /* Connect PDx pins to FMC Alternate function */
926 GPIOD->AFR[0] = 0x000000CC;
927 GPIOD->AFR[1] = 0xCC000CCC;
928 /* Configure PDx pins in Alternate function mode */
929 GPIOD->MODER = 0xAFEAFFFA;
930 /* Configure PDx pins speed to 50 MHz */
931 GPIOD->OSPEEDR = 0xA02A000A;
932 /* Configure PDx pins Output type to push-pull */
933 GPIOD->OTYPER = 0x00000000;
934 /* No pull-up, pull-down for PDx pins */
935 GPIOD->PUPDR = 0x55555505;
936 /* Connect PEx pins to FMC Alternate function */
937 GPIOE->AFR[0] = 0xC00000CC;
938 GPIOE->AFR[1] = 0xCCCCCCCC;
939 /* Configure PEx pins in Alternate function mode */
940 GPIOE->MODER = 0xAAAABFFA;
941 /* Configure PEx pins speed to 50 MHz */
942 GPIOE->OSPEEDR = 0xAAAA800A;
943 /* Configure PEx pins Output type to push-pull */
944 GPIOE->OTYPER = 0x00000000;
945 /* No pull-up, pull-down for PEx pins */
946 GPIOE->PUPDR = 0x55554005;
947 /* Connect PFx pins to FMC Alternate function */
948 GPIOF->AFR[0] = 0x00CCCCCC;
949 GPIOF->AFR[1] = 0xCCCCC000;
950 /* Configure PFx pins in Alternate function mode */
951 GPIOF->MODER = 0xAABFFAAA;
952 /* Configure PFx pins speed to 50 MHz */
953 GPIOF->OSPEEDR = 0xAA800AAA;
954 /* Configure PFx pins Output type to push-pull */
955 GPIOF->OTYPER = 0x00000000;
956 /* No pull-up, pull-down for PFx pins */
957 GPIOF->PUPDR = 0x55400555;
958 /* Connect PGx pins to FMC Alternate function */
959 GPIOG->AFR[0] = 0x00CCCCCC;
960 GPIOG->AFR[1] = 0xC000000C;
961 /* Configure PGx pins in Alternate function mode */
962 GPIOG->MODER = 0xBFFEFAAA;
963 /* Configure PGx pins speed to 50 MHz */
964 GPIOG->OSPEEDR = 0x80020AAA;
965 /* Configure PGx pins Output type to push-pull */
966 GPIOG->OTYPER = 0x00000000;
967 /* No pull-up, pull-down for PGx pins */
968 GPIOG->PUPDR = 0x40010515;
969 /* Connect PHx pins to FMC Alternate function */
970 GPIOH->AFR[0] = 0xCCC00000;
971 GPIOH->AFR[1] = 0xCCCCCCCC;
972 /* Configure PHx pins in Alternate function mode */
973 GPIOH->MODER = 0xAAAAABFF;
974 /* Configure PHx pins speed to 50 MHz */
975 GPIOH->OSPEEDR = 0xAAAAA800;
976 /* Configure PHx pins Output type to push-pull */
977 GPIOH->OTYPER = 0x00000000;
978 /* No pull-up, pull-down for PHx pins */
979 GPIOH->PUPDR = 0x55555400;
980 /* Connect PIx pins to FMC Alternate function */
981 GPIOI->AFR[0] = 0xCCCCCCCC;
982 GPIOI->AFR[1] = 0x00000CC0;
983 /* Configure PIx pins in Alternate function mode */
984 GPIOI->MODER = 0xFFEBAAAA;
985 /* Configure PIx pins speed to 50 MHz */
986 GPIOI->OSPEEDR = 0x0028AAAA;
987 /* Configure PIx pins Output type to push-pull */
988 GPIOI->OTYPER = 0x00000000;
989 /* No pull-up, pull-down for PIx pins */
990 GPIOI->PUPDR = 0x00145555;
991 /*-- FMC Configuration ------------------------------------------------------*/
992 /* Enable the FMC interface clock */
993 (RCC->AHB3ENR |= (RCC_AHB3ENR_FMCEN));
994 /*SDRAM Timing and access interface configuration*/
995 /*LoadToActiveDelay = 2
996 ExitSelfRefreshDelay = 6
997 SelfRefreshTime = 4
998 RowCycleDelay = 6
999 WriteRecoveryTime = 2
1000 RPDelay = 2
1001 RCDDelay = 2
1002 SDBank = FMC_SDRAM_BANK2
1003 ColumnBitsNumber = FMC_SDRAM_COLUMN_BITS_NUM_9
1004 RowBitsNumber = FMC_SDRAM_ROW_BITS_NUM_12
1005 MemoryDataWidth = FMC_SDRAM_MEM_BUS_WIDTH_32
1006 InternalBankNumber = FMC_SDRAM_INTERN_BANKS_NUM_4
1007 CASLatency = FMC_SDRAM_CAS_LATENCY_2
1008 WriteProtection = FMC_SDRAM_WRITE_PROTECTION_DISABLE
1009 SDClockPeriod = FMC_SDRAM_CLOCK_PERIOD_2
1010 ReadBurst = FMC_SDRAM_RBURST_ENABLE
1011 ReadPipeDelay = FMC_SDRAM_RPIPE_DELAY_0*/
1013 FMC_Bank5_6->SDCR[0] = 0x00001800;
1014 FMC_Bank5_6->SDCR[1] = 0x00000165;
1015 FMC_Bank5_6->SDTR[0] = 0x00105000;
1016 FMC_Bank5_6->SDTR[1] = 0x01010351;
1018 /* SDRAM initialization sequence */
1019 /* Clock enable command */
1020 FMC_Bank5_6->SDCMR = 0x00000009;
1021 tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
1022 while((tmpreg != 0) && (timeout-- > 0))
1024 tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
1027 /* Delay */
1028 for (index = 0; index<1000; index++);
1030 /* PALL command */
1031 FMC_Bank5_6->SDCMR = 0x0000000A;
1032 timeout = 0xFFFF;
1033 while((tmpreg != 0) && (timeout-- > 0))
1035 tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
1038 FMC_Bank5_6->SDCMR = 0x000000EB;
1039 timeout = 0xFFFF;
1040 while((tmpreg != 0) && (timeout-- > 0))
1042 tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
1045 FMC_Bank5_6->SDCMR = 0x0004400C;
1046 timeout = 0xFFFF;
1047 while((tmpreg != 0) && (timeout-- > 0))
1049 tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
1051 /* Set refresh count */
1052 tmpreg = FMC_Bank5_6->SDRTR;
1053 FMC_Bank5_6->SDRTR = (tmpreg | (0x00000603<<1));
1055 /* Disable write protection */
1056 tmpreg = FMC_Bank5_6->SDCR[1];
1057 FMC_Bank5_6->SDCR[1] = (tmpreg & 0xFFFFFDFF);
1059 /*FMC controller Enable*/
1060 FMC_Bank1->BTCR[0] |= 0x80000000;
1063 #endif /* DATA_IN_ExtSDRAM */
1065 #if defined(DATA_IN_ExtSRAM)
1066 /*-- GPIOs Configuration -----------------------------------------------------*/
1067 /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */
1068 RCC->AHB4ENR |= 0x00000078;
1070 /* Connect PDx pins to FMC Alternate function */
1071 GPIOD->AFR[0] = 0x00CCC0CC;
1072 GPIOD->AFR[1] = 0xCCCCCCCC;
1073 /* Configure PDx pins in Alternate function mode */
1074 GPIOD->MODER = 0xAAAA0A8A;
1075 /* Configure PDx pins speed to 100 MHz */
1076 GPIOD->OSPEEDR = 0xFFFF0FCF;
1077 /* Configure PDx pins Output type to push-pull */
1078 GPIOD->OTYPER = 0x00000000;
1079 /* No pull-up, pull-down for PDx pins */
1080 GPIOD->PUPDR = 0x55550545;
1082 /* Connect PEx pins to FMC Alternate function */
1083 GPIOE->AFR[0] = 0xC00CC0CC;
1084 GPIOE->AFR[1] = 0xCCCCCCCC;
1085 /* Configure PEx pins in Alternate function mode */
1086 GPIOE->MODER = 0xAAAA828A;
1087 /* Configure PEx pins speed to 100 MHz */
1088 GPIOE->OSPEEDR = 0xFFFFC3CF;
1089 /* Configure PEx pins Output type to push-pull */
1090 GPIOE->OTYPER = 0x00000000;
1091 /* No pull-up, pull-down for PEx pins */
1092 GPIOE->PUPDR = 0x55554145;
1094 /* Connect PFx pins to FMC Alternate function */
1095 GPIOF->AFR[0] = 0x00CCCCCC;
1096 GPIOF->AFR[1] = 0xCCCC0000;
1097 /* Configure PFx pins in Alternate function mode */
1098 GPIOF->MODER = 0xAA000AAA;
1099 /* Configure PFx pins speed to 100 MHz */
1100 GPIOF->OSPEEDR = 0xFF000FFF;
1101 /* Configure PFx pins Output type to push-pull */
1102 GPIOF->OTYPER = 0x00000000;
1103 /* No pull-up, pull-down for PFx pins */
1104 GPIOF->PUPDR = 0x55000555;
1106 /* Connect PGx pins to FMC Alternate function */
1107 GPIOG->AFR[0] = 0x00CCCCCC;
1108 GPIOG->AFR[1] = 0x000000C0;
1109 /* Configure PGx pins in Alternate function mode */
1110 GPIOG->MODER = 0x00200AAA;
1111 /* Configure PGx pins speed to 100 MHz */
1112 GPIOG->OSPEEDR = 0x00300FFF;
1113 /* Configure PGx pins Output type to push-pull */
1114 GPIOG->OTYPER = 0x00000000;
1115 /* No pull-up, pull-down for PGx pins */
1116 GPIOG->PUPDR = 0x00100555;
1118 /*-- FMC/FSMC Configuration --------------------------------------------------*/
1119 /* Enable the FMC/FSMC interface clock */
1120 (RCC->AHB3ENR |= (RCC_AHB3ENR_FMCEN));
1122 /* Configure and enable Bank1_SRAM2 */
1123 FMC_Bank1->BTCR[4] = 0x00001091;
1124 FMC_Bank1->BTCR[5] = 0x00110212;
1125 FMC_Bank1E->BWTR[4] = 0x0FFFFFFF;
1127 /*FMC controller Enable*/
1128 FMC_Bank1->BTCR[0] |= 0x80000000;
1130 #endif /* DATA_IN_ExtSRAM */
1132 #endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
1136 * @}
1140 * @}
1144 * @}
1146 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/