add more gyros for NeutronRCF411SX1280 target
[betaflight.git] / src / main / startup / system_stm32f7xx.c
blob33afba1d4f8fc7670449ed37ea0356b478c66897
1 /**
2 ******************************************************************************
3 * @file system_stm32f7xx.c
4 * @author MCD Application Team
5 * @version V1.0.0
6 * @date 22-April-2016
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
10 * user application:
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 ******************************************************************************
25 * @attention
27 * <h2><center>&copy; 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 ******************************************************************************
54 /** @addtogroup CMSIS
55 * @{
58 /** @addtogroup stm32f7xx_system
59 * @{
62 /** @addtogroup STM32F7xx_System_Private_Includes
63 * @{
66 #include "stm32f7xx.h"
67 #include "drivers/system.h"
68 #include "system_stm32f7xx.h"
69 #include "platform.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 */
80 #define PLL_M 8
81 #define PLL_N 432
82 #define PLL_P RCC_PLLP_DIV2 /* 2 */
83 #define PLL_Q 9
85 #define PLL_SAIN 384
86 #define PLL_SAIQ 7
87 #define PLL_SAIP RCC_PLLSAIP_DIV8
89 /**
90 * @}
93 /** @addtogroup STM32F7xx_System_Private_TypesDefinitions
94 * @{
97 /**
98 * @}
101 /** @addtogroup STM32F7xx_System_Private_Defines
102 * @{
106 * @}
109 /** @addtogroup STM32F7xx_System_Private_Macros
110 * @{
114 * @}
117 /** @addtogroup STM32F7xx_System_Private_Variables
118 * @{
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};
136 * @}
139 /** @addtogroup STM32F7xx_System_Private_FunctionPrototypes
140 * @{
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;
167 #else
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;
177 #endif
179 ret = HAL_RCC_OscConfig(&RCC_OscInitStruct);
180 if (ret != HAL_OK) {
181 while (1);
184 /* Activate the OverDrive to reach the 216 MHz Frequency */
185 ret = HAL_PWREx_EnableOverDrive();
186 if (ret != HAL_OK) {
187 while (1);
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) {
196 while (1);
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);
207 if (ret != HAL_OK) {
208 while (1);
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);
234 if (ret != HAL_OK) {
235 while (1);
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)
248 while (1);
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 {
258 uint16_t n;
259 uint16_t p;
260 uint16_t q;
261 } pllConfig_t;
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) {
269 uint32_t currentOverclockLevel = persistentObjectRead(PERSISTENT_OBJECT_OVERCLOCK_LEVEL);
271 if (currentOverclockLevel >= ARRAYLEN(overclockLevels)) {
272 return;
275 /* PLL setting for overclocking */
276 const pllConfig_t * const pll = overclockLevels + currentOverclockLevel;
278 pll_n = pll->n;
279 pll_p = pll->p;
280 pll_q = pll->q;
283 void OverclockRebootIfNecessary(uint32_t overclockLevel)
285 if (overclockLevel >= ARRAYLEN(overclockLevels)) {
286 return;
289 const pllConfig_t * const pll = overclockLevels + overclockLevel;
291 // Reboot to adjust overclock frequency
292 if (SystemCoreClock != (pll->n / pll->p) * 1000000U) {
293 persistentObjectWrite(PERSISTENT_OBJECT_OVERCLOCK_LEVEL, overclockLevel);
294 __disable_irq();
295 NVIC_SystemReset();
300 * @}
303 /** @addtogroup STM32F7xx_System_Private_Functions
304 * @{
308 * @brief Setup the microcontroller system
309 * Initialize the Embedded Flash Interface, the PLL and update the
310 * SystemFrequency variable.
311 * @param None
312 * @retval None
314 void SystemInit(void)
316 uint32_t bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON);
318 if (bootloaderRequest == RESET_BOOTLOADER_POST) {
319 persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_NONE);
320 NVIC_SystemReset();
323 initialiseMemorySections();
325 SystemInitOC();
327 SystemCoreClock = (pll_n / pll_p) * 1000000;
329 /* FPU settings ------------------------------------------------------------*/
330 #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
331 SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
332 #endif
333 /* Reset the RCC clock configuration to the default reset state ------------*/
334 /* Set HSION bit */
335 RCC->CR |= (uint32_t)0x00000001;
337 /* Reset CFGR register */
338 RCC->CFGR = 0x00000000;
340 /* Reset HSEON, CSSON and PLLON bits */
341 RCC->CR &= (uint32_t)0xFEF6FFFF;
343 /* Reset PLLCFGR register */
344 RCC->PLLCFGR = 0x24003010;
346 /* Reset HSEBYP bit */
347 RCC->CR &= (uint32_t)0xFFFBFFFF;
349 /* Disable all interrupts */
350 RCC->CIR = 0x00000000;
352 /* Configure the Vector Table location add offset address ------------------*/
353 extern uint8_t isr_vector_table_base;
354 const uint32_t vtorOffset = (uint32_t) &isr_vector_table_base;
355 #define VTOR_OFFSET_ALIGNMENT 0x200
356 if (vtorOffset % VTOR_OFFSET_ALIGNMENT != 0) {
357 // ISR vector table base is not 512 byte aligned
358 while (1);
360 SCB->VTOR = vtorOffset;
362 #ifdef USE_HAL_DRIVER
363 HAL_Init();
364 #endif
366 /* Enable I-Cache */
367 if (INSTRUCTION_CACHE_ENABLE) {
368 SCB_EnableICache();
371 /* Enable D-Cache */
372 if (DATA_CACHE_ENABLE) {
373 SCB_EnableDCache();
376 if (PREFETCH_ENABLE) {
377 LL_FLASH_EnablePrefetch();
380 /* Configure the system clock to specified frequency */
381 SystemClock_Config();
383 if (SystemCoreClock != (pll_n / pll_p) * 1000000) {
384 // There is a mismatch between the configured clock and the expected clock in portable.h
385 while (1);
390 * @brief Update SystemCoreClock variable according to Clock Register Values.
391 * The SystemCoreClock variable contains the core clock (HCLK), it can
392 * be used by the user application to setup the SysTick timer or configure
393 * other parameters.
395 * @note Each time the core clock (HCLK) changes, this function must be called
396 * to update SystemCoreClock variable value. Otherwise, any configuration
397 * based on this variable will be incorrect.
399 * @note - The system frequency computed by this function is not the real
400 * frequency in the chip. It is calculated based on the predefined
401 * constant and the selected clock source:
403 * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
405 * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
407 * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
408 * or HSI_VALUE(*) multiplied/divided by the PLL factors.
410 * (*) HSI_VALUE is a constant defined in stm32f7xx_hal_conf.h file (default value
411 * 16 MHz) but the real value may vary depending on the variations
412 * in voltage and temperature.
414 * (**) HSE_VALUE is a constant defined in stm32f7xx_hal_conf.h file (default value
415 * 25 MHz), user has to ensure that HSE_VALUE is same as the real
416 * frequency of the crystal used. Otherwise, this function may
417 * have wrong result.
419 * - The result of this function could be not correct when using fractional
420 * value for HSE crystal.
422 * @param None
423 * @retval None
425 void SystemCoreClockUpdate(void)
427 uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2;
429 /* Get SYSCLK source -------------------------------------------------------*/
430 tmp = RCC->CFGR & RCC_CFGR_SWS;
432 switch (tmp) {
433 case 0x00: /* HSI used as system clock source */
434 SystemCoreClock = HSI_VALUE;
435 break;
436 case 0x04: /* HSE used as system clock source */
437 SystemCoreClock = HSE_VALUE;
438 break;
439 case 0x08: /* PLL used as system clock source */
441 /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
442 SYSCLK = PLL_VCO / PLL_P
444 pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
445 pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
447 if (pllsource != 0) {
448 /* HSE used as PLL clock source */
449 pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
450 } else {
451 /* HSI used as PLL clock source */
452 pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
455 pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >> 16) + 1) * 2;
456 SystemCoreClock = pllvco/pllp;
457 break;
458 default:
459 SystemCoreClock = HSI_VALUE;
460 break;
462 /* Compute HCLK frequency --------------------------------------------------*/
463 /* Get HCLK prescaler */
464 tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
465 /* HCLK frequency */
466 SystemCoreClock >>= tmp;
469 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/