2 ******************************************************************************
3 * @file system_stm32f7xx.c
4 * @author MCD Application Team
7 * @brief CMSIS Cortex-M7 Device Peripheral Access Layer System Source File.
9 * This file provides two functions and one global variable to be called from
11 * - SystemInit(): This function is called at startup just after reset and
12 * before branch to main program. This call is made inside
13 * the "startup_stm32f7xx.s" file.
15 * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
16 * by the user application to setup the SysTick
17 * timer or configure other parameters.
19 * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
20 * be called whenever the core clock is changed
21 * during program execution.
24 ******************************************************************************
27 * <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
29 * Redistribution and use in source and binary forms, with or without modification,
30 * are permitted provided that the following conditions are met:
31 * 1. Redistributions of source code must retain the above copyright notice,
32 * this list of conditions and the following disclaimer.
33 * 2. Redistributions in binary form must reproduce the above copyright notice,
34 * this list of conditions and the following disclaimer in the documentation
35 * and/or other materials provided with the distribution.
36 * 3. Neither the name of STMicroelectronics nor the names of its contributors
37 * may be used to endorse or promote products derived from this software
38 * without specific prior written permission.
40 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
41 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
42 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
43 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
44 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
45 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
46 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
47 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
48 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
49 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
51 ******************************************************************************
58 /** @addtogroup stm32f7xx_system
62 /** @addtogroup STM32F7xx_System_Private_Includes
66 #include "stm32f7xx.h"
67 #include "drivers/system.h"
68 #include "system_stm32f7xx.h"
70 #include "drivers/persistent.h"
72 #if !defined (HSE_VALUE)
73 #define HSE_VALUE ((uint32_t)8000000) /*!< Default value of the External oscillator in Hz */
74 #endif /* HSE_VALUE */
76 #if !defined (HSI_VALUE)
77 #define HSI_VALUE ((uint32_t)16000000) /*!< Value of the Internal oscillator in Hz*/
78 #endif /* HSI_VALUE */
82 #define PLL_P RCC_PLLP_DIV2 /* 2 */
87 #define PLL_SAIP RCC_PLLSAIP_DIV8
93 /** @addtogroup STM32F7xx_System_Private_TypesDefinitions
101 /** @addtogroup STM32F7xx_System_Private_Defines
109 /** @addtogroup STM32F7xx_System_Private_Macros
117 /** @addtogroup STM32F7xx_System_Private_Variables
121 /* This variable is updated in three ways:
122 1) by calling CMSIS function SystemCoreClockUpdate()
123 2) by calling HAL API function HAL_RCC_GetHCLKFreq()
124 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
125 Note: If you use this function to configure the system clock; then there
126 is no need to call the 2 first functions listed above, since SystemCoreClock
127 variable is updated automatically.
129 uint32_t SystemCoreClock
;
130 uint32_t pll_p
= PLL_P
, pll_n
= PLL_N
, pll_q
= PLL_Q
;
132 const uint8_t AHBPrescTable
[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
133 const uint8_t APBPrescTable
[8] = {0, 0, 0, 0, 1, 2, 3, 4};
139 /** @addtogroup STM32F7xx_System_Private_FunctionPrototypes
143 /// TODO: F7 check if this is the best configuration for the clocks.
144 // current settings are just a copy from one of the example projects
145 void SystemClock_Config(void)
147 RCC_ClkInitTypeDef RCC_ClkInitStruct
;
148 RCC_OscInitTypeDef RCC_OscInitStruct
;
149 RCC_PeriphCLKInitTypeDef PeriphClkInitStruct
;
150 HAL_StatusTypeDef ret
;
152 __HAL_RCC_PWR_CLK_ENABLE();
154 __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1
);
156 #ifdef CLOCK_SOURCE_USE_HSI
157 /* Enable HSI Oscillator and activate PLL with HSI as source */
158 RCC_OscInitStruct
.OscillatorType
= RCC_OSCILLATORTYPE_HSI
;
159 RCC_OscInitStruct
.HSIState
= RCC_HSI_ON
;
160 RCC_OscInitStruct
.HSICalibrationValue
= RCC_HSICALIBRATION_DEFAULT
;
161 RCC_OscInitStruct
.PLL
.PLLState
= RCC_PLL_ON
;
162 RCC_OscInitStruct
.PLL
.PLLSource
= RCC_PLLSOURCE_HSI
;
163 RCC_OscInitStruct
.PLL
.PLLM
= 16;
164 RCC_OscInitStruct
.PLL
.PLLN
= 432;
165 RCC_OscInitStruct
.PLL
.PLLP
= RCC_PLLP_DIV2
;
166 RCC_OscInitStruct
.PLL
.PLLQ
= 9;
168 /* Enable HSE Oscillator and activate PLL with HSE as source */
169 RCC_OscInitStruct
.OscillatorType
= RCC_OSCILLATORTYPE_HSE
;
170 RCC_OscInitStruct
.HSEState
= RCC_HSE_ON
;
171 RCC_OscInitStruct
.PLL
.PLLState
= RCC_PLL_ON
;
172 RCC_OscInitStruct
.PLL
.PLLSource
= RCC_PLLSOURCE_HSE
;
173 RCC_OscInitStruct
.PLL
.PLLM
= PLL_M
;
174 RCC_OscInitStruct
.PLL
.PLLN
= pll_n
;
175 RCC_OscInitStruct
.PLL
.PLLP
= pll_p
;
176 RCC_OscInitStruct
.PLL
.PLLQ
= pll_q
;
179 ret
= HAL_RCC_OscConfig(&RCC_OscInitStruct
);
184 /* Activate the OverDrive to reach the 216 MHz Frequency */
185 ret
= HAL_PWREx_EnableOverDrive();
189 /* Select PLLSAI output as USB clock source */
190 PeriphClkInitStruct
.PeriphClockSelection
= RCC_PERIPHCLK_CLK48
;
191 PeriphClkInitStruct
.Clk48ClockSelection
= RCC_CLK48SOURCE_PLLSAIP
;
192 PeriphClkInitStruct
.PLLSAI
.PLLSAIN
= PLL_SAIN
;
193 PeriphClkInitStruct
.PLLSAI
.PLLSAIQ
= PLL_SAIQ
;
194 PeriphClkInitStruct
.PLLSAI
.PLLSAIP
= PLL_SAIP
;
195 if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct
) != HAL_OK
) {
199 /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */
200 RCC_ClkInitStruct
.ClockType
= (RCC_CLOCKTYPE_SYSCLK
| RCC_CLOCKTYPE_HCLK
| RCC_CLOCKTYPE_PCLK1
| RCC_CLOCKTYPE_PCLK2
);
201 RCC_ClkInitStruct
.SYSCLKSource
= RCC_SYSCLKSOURCE_PLLCLK
;
202 RCC_ClkInitStruct
.AHBCLKDivider
= RCC_SYSCLK_DIV1
;
203 RCC_ClkInitStruct
.APB1CLKDivider
= RCC_HCLK_DIV4
;
204 RCC_ClkInitStruct
.APB2CLKDivider
= RCC_HCLK_DIV2
;
206 ret
= HAL_RCC_ClockConfig(&RCC_ClkInitStruct
, FLASH_LATENCY_7
);
211 PeriphClkInitStruct
.PeriphClockSelection
= RCC_PERIPHCLK_USART1
|RCC_PERIPHCLK_USART2
212 |RCC_PERIPHCLK_USART3
|RCC_PERIPHCLK_USART6
213 |RCC_PERIPHCLK_UART4
|RCC_PERIPHCLK_UART5
214 |RCC_PERIPHCLK_UART7
|RCC_PERIPHCLK_UART8
215 |RCC_PERIPHCLK_I2C1
|RCC_PERIPHCLK_I2C3
216 |RCC_PERIPHCLK_I2C2
|RCC_PERIPHCLK_I2C4
;
217 PeriphClkInitStruct
.Usart1ClockSelection
= RCC_USART1CLKSOURCE_PCLK2
;
218 PeriphClkInitStruct
.Usart2ClockSelection
= RCC_USART2CLKSOURCE_PCLK1
;
219 PeriphClkInitStruct
.Usart3ClockSelection
= RCC_USART3CLKSOURCE_PCLK1
;
220 PeriphClkInitStruct
.Uart4ClockSelection
= RCC_UART4CLKSOURCE_PCLK1
;
221 PeriphClkInitStruct
.Uart5ClockSelection
= RCC_UART5CLKSOURCE_PCLK1
;
222 PeriphClkInitStruct
.Usart6ClockSelection
= RCC_USART6CLKSOURCE_PCLK2
;
223 PeriphClkInitStruct
.Uart7ClockSelection
= RCC_UART7CLKSOURCE_PCLK1
;
224 PeriphClkInitStruct
.Uart8ClockSelection
= RCC_UART8CLKSOURCE_PCLK1
;
226 // I2C clock sources: Note that peripheral clock determination in bus_i2c_hal_init.c must be modified when the sources are modified.
228 PeriphClkInitStruct
.I2c1ClockSelection
= RCC_I2C1CLKSOURCE_PCLK1
;
229 PeriphClkInitStruct
.I2c2ClockSelection
= RCC_I2C2CLKSOURCE_PCLK1
;
230 PeriphClkInitStruct
.I2c3ClockSelection
= RCC_I2C3CLKSOURCE_PCLK1
;
231 PeriphClkInitStruct
.I2c4ClockSelection
= RCC_I2C4CLKSOURCE_PCLK1
;
233 ret
= HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct
);
238 // Configure PLLI2S for 27MHz operation
239 // Actual output will be done by mcoInit in drivers/mco.c
241 PeriphClkInitStruct
.PeriphClockSelection
= RCC_PERIPHCLK_PLLI2S
;
242 PeriphClkInitStruct
.PLLI2S
.PLLI2SN
= 216;
243 PeriphClkInitStruct
.PLLI2S
.PLLI2SR
= 2;
244 PeriphClkInitStruct
.PLLI2S
.PLLI2SQ
= 2;
245 PeriphClkInitStruct
.PLLI2SDivQ
= 1;
246 if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct
) != HAL_OK
)
251 // Activating the timerprescalers while the APBx prescalers are 1/2/4 will connect the TIMxCLK to HCLK which has been configured to 216MHz
252 __HAL_RCC_TIMCLKPRESCALER(RCC_TIMPRES_ACTIVATED
);
254 SystemCoreClockUpdate();
257 typedef struct pllConfig_s
{
263 static const pllConfig_t overclockLevels
[] = {
264 { PLL_N
, PLL_P
, PLL_Q
}, // default
265 { 480, RCC_PLLP_DIV2
, 10 }, // 240 MHz
268 void SystemInitOC(void)
270 uint32_t currentOverclockLevel
= persistentObjectRead(PERSISTENT_OBJECT_OVERCLOCK_LEVEL
);
272 if (currentOverclockLevel
>= ARRAYLEN(overclockLevels
)) {
276 /* PLL setting for overclocking */
277 const pllConfig_t
* const pll
= overclockLevels
+ currentOverclockLevel
;
284 void OverclockRebootIfNecessary(uint32_t overclockLevel
)
286 if (overclockLevel
>= ARRAYLEN(overclockLevels
)) {
290 const pllConfig_t
* const pll
= overclockLevels
+ overclockLevel
;
292 // Reboot to adjust overclock frequency
293 if (SystemCoreClock
!= (pll
->n
/ pll
->p
) * 1000000U) {
294 persistentObjectWrite(PERSISTENT_OBJECT_OVERCLOCK_LEVEL
, overclockLevel
);
304 /** @addtogroup STM32F7xx_System_Private_Functions
309 * @brief Setup the microcontroller system
310 * Initialize the Embedded Flash Interface, the PLL and update the
311 * SystemFrequency variable.
315 void SystemInit(void)
317 uint32_t bootloaderRequest
= persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON
);
319 if (bootloaderRequest
== RESET_BOOTLOADER_POST
) {
320 persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON
, RESET_NONE
);
324 initialiseMemorySections();
328 SystemCoreClock
= (pll_n
/ pll_p
) * 1000000;
330 /* FPU settings ------------------------------------------------------------*/
331 #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
332 SCB
->CPACR
|= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
334 /* Reset the RCC clock configuration to the default reset state ------------*/
336 RCC
->CR
|= (uint32_t)0x00000001;
338 /* Reset CFGR register */
339 RCC
->CFGR
= 0x00000000;
341 /* Reset HSEON, CSSON and PLLON bits */
342 RCC
->CR
&= (uint32_t)0xFEF6FFFF;
344 /* Reset PLLCFGR register */
345 RCC
->PLLCFGR
= 0x24003010;
347 /* Reset HSEBYP bit */
348 RCC
->CR
&= (uint32_t)0xFFFBFFFF;
350 /* Disable all interrupts */
351 RCC
->CIR
= 0x00000000;
353 /* Configure the Vector Table location add offset address ------------------*/
354 extern uint8_t isr_vector_table_base
;
355 const uint32_t vtorOffset
= (uint32_t) &isr_vector_table_base
;
356 #define VTOR_OFFSET_ALIGNMENT 0x200
357 if (vtorOffset
% VTOR_OFFSET_ALIGNMENT
!= 0) {
358 // ISR vector table base is not 512 byte aligned
361 SCB
->VTOR
= vtorOffset
;
363 #ifdef USE_HAL_DRIVER
368 if (INSTRUCTION_CACHE_ENABLE
) {
373 if (DATA_CACHE_ENABLE
) {
377 if (PREFETCH_ENABLE
) {
378 LL_FLASH_EnablePrefetch();
381 /* Configure the system clock to specified frequency */
382 SystemClock_Config();
384 if (SystemCoreClock
!= (pll_n
/ pll_p
) * 1000000) {
385 // There is a mismatch between the configured clock and the expected clock in portable.h
391 * @brief Update SystemCoreClock variable according to Clock Register Values.
392 * The SystemCoreClock variable contains the core clock (HCLK), it can
393 * be used by the user application to setup the SysTick timer or configure
396 * @note Each time the core clock (HCLK) changes, this function must be called
397 * to update SystemCoreClock variable value. Otherwise, any configuration
398 * based on this variable will be incorrect.
400 * @note - The system frequency computed by this function is not the real
401 * frequency in the chip. It is calculated based on the predefined
402 * constant and the selected clock source:
404 * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
406 * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
408 * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
409 * or HSI_VALUE(*) multiplied/divided by the PLL factors.
411 * (*) HSI_VALUE is a constant defined in stm32f7xx_hal_conf.h file (default value
412 * 16 MHz) but the real value may vary depending on the variations
413 * in voltage and temperature.
415 * (**) HSE_VALUE is a constant defined in stm32f7xx_hal_conf.h file (default value
416 * 25 MHz), user has to ensure that HSE_VALUE is same as the real
417 * frequency of the crystal used. Otherwise, this function may
420 * - The result of this function could be not correct when using fractional
421 * value for HSE crystal.
426 void SystemCoreClockUpdate(void)
428 uint32_t tmp
= 0, pllvco
= 0, pllp
= 2, pllsource
= 0, pllm
= 2;
430 /* Get SYSCLK source -------------------------------------------------------*/
431 tmp
= RCC
->CFGR
& RCC_CFGR_SWS
;
434 case 0x00: /* HSI used as system clock source */
435 SystemCoreClock
= HSI_VALUE
;
437 case 0x04: /* HSE used as system clock source */
438 SystemCoreClock
= HSE_VALUE
;
440 case 0x08: /* PLL used as system clock source */
442 /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
443 SYSCLK = PLL_VCO / PLL_P
445 pllsource
= (RCC
->PLLCFGR
& RCC_PLLCFGR_PLLSRC
) >> 22;
446 pllm
= RCC
->PLLCFGR
& RCC_PLLCFGR_PLLM
;
448 if (pllsource
!= 0) {
449 /* HSE used as PLL clock source */
450 pllvco
= (HSE_VALUE
/ pllm
) * ((RCC
->PLLCFGR
& RCC_PLLCFGR_PLLN
) >> 6);
452 /* HSI used as PLL clock source */
453 pllvco
= (HSI_VALUE
/ pllm
) * ((RCC
->PLLCFGR
& RCC_PLLCFGR_PLLN
) >> 6);
456 pllp
= (((RCC
->PLLCFGR
& RCC_PLLCFGR_PLLP
) >> 16) + 1) * 2;
457 SystemCoreClock
= pllvco
/pllp
;
460 SystemCoreClock
= HSI_VALUE
;
463 /* Compute HCLK frequency --------------------------------------------------*/
464 /* Get HCLK prescaler */
465 tmp
= AHBPrescTable
[((RCC
->CFGR
& RCC_CFGR_HPRE
) >> 4)];
467 SystemCoreClock
>>= tmp
;
470 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/