Merge pull request #11297 from SteveCEvans/baro_state
[betaflight.git] / src / main / startup / system_stm32g4xx.c
blob1c050274de323530d2a41194ded12e00dd9872b1
1 /**
2 ******************************************************************************
3 * @file system_stm32g4xx.c
4 * @author MCD Application Team
5 * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File
7 ******************************************************************************
8 * @attention
10 * <h2><center>&copy; Copyright (c) 2017 STMicroelectronics.
11 * All rights reserved.</center></h2>
13 * This software component is licensed by ST under BSD 3-Clause license,
14 * the "License"; You may not use this file except in compliance with the
15 * License. You may obtain a copy of the License at:
16 * opensource.org/licenses/BSD-3-Clause
18 ******************************************************************************
21 #include <string.h>
23 #include "stm32g4xx.h"
24 #include "drivers/system.h"
25 #include "platform.h"
26 #include "drivers/persistent.h"
28 #if !defined (HSE_VALUE)
29 #define HSE_VALUE 8000000U /*!< Value of the External oscillator in Hz */
30 #endif /* HSE_VALUE */
32 #if !defined (HSI_VALUE)
33 #define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz*/
34 #endif /* HSI_VALUE */
36 /* The SystemCoreClock variable is updated in three ways:
37 1) by calling CMSIS function SystemCoreClockUpdate()
38 2) by calling HAL API function HAL_RCC_GetHCLKFreq()
39 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
40 Note: If you use this function to configure the system clock; then there
41 is no need to call the 2 first functions listed above, since SystemCoreClock
42 variable is updated automatically.
44 uint32_t SystemCoreClock = HSI_VALUE;
46 const uint8_t AHBPrescTable[16] = {0U, 0U, 0U, 0U, 0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U, 6U, 7U, 8U, 9U};
47 const uint8_t APBPrescTable[8] = {0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U};
49 void SystemClock_Config(void); // Forward
51 void SystemInit(void)
53 systemProcessResetReason();
55 initialiseMemorySections();
57 /* FPU settings ------------------------------------------------------------*/
58 #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
59 SCB->CPACR |= ((3UL << (10*2))|(3UL << (11*2))); /* set CP10 and CP11 Full Access */
60 #endif
62 /* Configure the Vector Table location add offset address ------------------*/
64 extern uint8_t isr_vector_table_flash_base;
65 extern uint8_t isr_vector_table_base;
66 extern uint8_t isr_vector_table_end;
68 if (&isr_vector_table_base != &isr_vector_table_flash_base) {
69 memcpy(&isr_vector_table_base, &isr_vector_table_flash_base, (size_t) (&isr_vector_table_end - &isr_vector_table_base));
72 SCB->VTOR = (uint32_t)&isr_vector_table_base;
74 #ifdef USE_HAL_DRIVER
75 HAL_Init();
76 #endif
78 SystemClock_Config();
79 SystemCoreClockUpdate();
82 /**
83 * @brief Update SystemCoreClock variable according to Clock Register Values.
84 * The SystemCoreClock variable contains the core clock (HCLK), it can
85 * be used by the user application to setup the SysTick timer or configure
86 * other parameters.
88 * @note Each time the core clock (HCLK) changes, this function must be called
89 * to update SystemCoreClock variable value. Otherwise, any configuration
90 * based on this variable will be incorrect.
92 * @note - The system frequency computed by this function is not the real
93 * frequency in the chip. It is calculated based on the predefined
94 * constant and the selected clock source:
96 * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(**)
98 * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(***)
100 * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(***)
101 * or HSI_VALUE(*) multiplied/divided by the PLL factors.
103 * (**) HSI_VALUE is a constant defined in stm32g4xx_hal.h file (default value
104 * 16 MHz) but the real value may vary depending on the variations
105 * in voltage and temperature.
107 * (***) HSE_VALUE is a constant defined in stm32g4xx_hal.h file (default value
108 * 8 MHz), user has to ensure that HSE_VALUE is same as the real
109 * frequency of the crystal used. Otherwise, this function may
110 * have wrong result.
112 * - The result of this function could be not correct when using fractional
113 * value for HSE crystal.
115 * @param None
116 * @retval None
118 void SystemCoreClockUpdate(void)
120 uint32_t hse_value = persistentObjectRead(PERSISTENT_OBJECT_HSE_VALUE);
122 uint32_t tmp, pllvco, pllr, pllsource, pllm;
124 /* Get SYSCLK source -------------------------------------------------------*/
125 switch (RCC->CFGR & RCC_CFGR_SWS)
127 case 0x04: /* HSI used as system clock source */
128 SystemCoreClock = HSI_VALUE;
129 break;
131 case 0x08: /* HSE used as system clock source */
132 SystemCoreClock = hse_value;
133 break;
135 case 0x0C: /* PLL used as system clock source */
136 /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN
137 SYSCLK = PLL_VCO / PLLR
139 pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC);
140 pllm = ((RCC->PLLCFGR & RCC_PLLCFGR_PLLM) >> 4) + 1U ;
141 if (pllsource == 0x02UL) /* HSI used as PLL clock source */
143 pllvco = (HSI_VALUE / pllm);
145 else /* HSE used as PLL clock source */
147 pllvco = (hse_value / pllm);
149 pllvco = pllvco * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 8);
150 pllr = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 25) + 1U) * 2U;
151 SystemCoreClock = pllvco/pllr;
152 break;
154 default:
155 break;
157 /* Compute HCLK clock frequency --------------------------------------------*/
158 /* Get HCLK prescaler */
159 tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
160 /* HCLK clock frequency */
161 SystemCoreClock >>= tmp;
164 // SystemSYSCLKSource
165 // 0: HSI
166 // 1: HSE
167 // (2: PLLP)
168 // 3: PLLR
170 int SystemSYSCLKSource(void)
172 uint32_t rawSrc = RCC->CFGR & RCC_CFGR_SW;
173 int src = 0;
175 switch (rawSrc) {
176 case 0: // can't happen, fall through
177 FALLTHROUGH;
178 case 1:
179 src = 0; // HSI
180 break;
182 case 2:
183 src = 1; // HSE
184 break;
186 case 3:
187 src = 3; // PLL-R
190 return src;
193 // SystemPLLSource
194 // 0: HSI
195 // 1: HSE
197 int SystemPLLSource(void)
199 return (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) & 1; // LSB determines HSI(0) or HSE(1)
202 void Error_Handler(void)
204 while (1) {
209 * G4 is capable of fine granularity overclocking thanks to a separate 48MHz source,
210 * but we keep the overclocking capability to match that of F405 (clocks at 168, 192, 216, 240).
212 * However, due to restrictions on MCO source, designs that wishes to generate 27MHz on MCO
213 * must use a 27MHz HSE source. The 27MHz HSE source will produce slightly different series of clocks
214 * due to restriction on PLL multipler range.
216 * If mhz == 8, 16 or 24 then scale it down to 4 and start with PLLN=42 for base 168MHz,
217 * with PLLN increment of 6 (4 * 6 = 24MHz a part)
219 * If mhz == 27 then scale it down to 9 with PLL=19 for base 171MHz with PLLN increment of 3 (9 * 3 = 27MHz a part)
221 * We don't prepare a separate frequency selection for 27MHz series in CLI, so what is set with "cpu_overclock"
222 * will result in slightly higher clock when examined with "status" command.
225 // Target frequencies for cpu_overclock (Levels 0 through 3)
227 uint16_t sysclkSeries8[] = { 168, 192, 216, 240 };
228 uint16_t sysclkSeries27[] = { 171, 198, 225, 252 };
229 #define OVERCLOCK_LEVELS ARRAYLEN(sysclkSeries8)
231 // Generic fine granularity PLL parameter calculation
233 static bool systemComputePLLParameters(uint8_t src, uint16_t target, int *sysclk, int *pllm, int *plln, int *pllr)
235 int vcoTarget = target * 2;
236 int vcoBase;
237 int vcoDiff;
238 int multDiff;
239 int vcoFreq;
241 *pllr = 2;
243 if (src == 8 || src == 16 || src == 24) {
244 *pllm = src / 8;
245 vcoBase = 168 * 2;
246 vcoDiff = vcoTarget - vcoBase;
247 multDiff = vcoDiff / 16 * 2;
248 *plln = 42 + multDiff;
249 vcoFreq = 8 * *plln;
250 } else if (src == 27) {
251 *pllm = 3;
252 vcoBase = 171 * 2;
253 vcoDiff = vcoTarget - vcoBase;
254 multDiff = vcoDiff / 18 * 2;
255 *plln = 38 + multDiff;
256 vcoFreq = 9 * *plln;
257 } else {
258 return false;
261 // VCO seems to top out at 590MHz or so. Give it some margin.
263 if (vcoFreq >= 560) {
264 return false;
266 *sysclk = vcoFreq / 2;
268 return true;
271 static int pll_m;
272 static int pll_n;
273 static int pll_r;
274 static uint32_t pllSrc;
275 static int sysclkMhz;
277 static bool systemClock_PLLConfig(int overclockLevel)
279 uint32_t hse_value = persistentObjectRead(PERSISTENT_OBJECT_HSE_VALUE);
280 int pllInput;
281 int targetMhz;
283 if (hse_value == 0) {
284 pllInput = 16; // HSI
285 pllSrc = RCC_PLLSOURCE_HSI;
286 targetMhz = 168;
287 } else {
288 pllInput = hse_value / 1000000;
289 pllSrc = RCC_PLLSOURCE_HSE;
290 if (pllInput == 8 || pllInput == 16 || pllInput == 24) {
291 targetMhz = sysclkSeries8[overclockLevel];
292 } else if (pllInput == 27) {
293 targetMhz = sysclkSeries8[overclockLevel];
294 } else {
295 return false;
299 return systemComputePLLParameters(pllInput, targetMhz, &sysclkMhz, &pll_m, &pll_n, &pll_r);
302 void systemClockSetHSEValue(uint32_t frequency)
304 uint32_t freqMhz = frequency / 1000000;
306 // Only supported HSE crystal/resonator is 27MHz or integer multiples of 8MHz
308 if (freqMhz != 27 && (freqMhz / 8) * 8 != freqMhz) {
309 return;
312 uint32_t hse_value = persistentObjectRead(PERSISTENT_OBJECT_HSE_VALUE);
314 if (hse_value != frequency) {
315 persistentObjectWrite(PERSISTENT_OBJECT_HSE_VALUE, frequency);
317 if (hse_value != 0) {
318 __disable_irq();
319 NVIC_SystemReset();
324 void OverclockRebootIfNecessary(unsigned requestedOverclockLevel)
326 uint32_t currentOverclockLevel = persistentObjectRead(PERSISTENT_OBJECT_OVERCLOCK_LEVEL);
328 if (requestedOverclockLevel >= OVERCLOCK_LEVELS ) {
329 requestedOverclockLevel = 0;
332 // If we are not running at the requested speed or
333 // we are running on PLL-HSI even HSE has been set,
334 // then remember the requested clock and issue soft reset
336 uint32_t hse_value = persistentObjectRead(PERSISTENT_OBJECT_HSE_VALUE);
338 if ((currentOverclockLevel != requestedOverclockLevel) ||
339 (hse_value &&
340 SystemSYSCLKSource() == 3 /* PLL-R */ &&
341 SystemPLLSource() != 1 /* HSE */)) {
343 // Make sure we can configure the requested clock.
344 if (!systemClock_PLLConfig(requestedOverclockLevel)) {
345 return;
347 persistentObjectWrite(PERSISTENT_OBJECT_OVERCLOCK_LEVEL, requestedOverclockLevel);
348 __disable_irq();
349 NVIC_SystemReset();
354 * @brief System Clock Configuration
355 * @retval None
357 // Extracted from MX generated main.c
359 void SystemClock_Config(void)
361 RCC_OscInitTypeDef RCC_OscInitStruct = {0};
362 RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
363 RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
364 RCC_CRSInitTypeDef pInit = {0};
366 systemClock_PLLConfig(persistentObjectRead(PERSISTENT_OBJECT_OVERCLOCK_LEVEL));
368 // Configure the main internal regulator output voltage
370 HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1_BOOST);
372 // Initializes the CPU, AHB and APB busses clocks
374 RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI|RCC_OSCILLATORTYPE_HSI48
375 |RCC_OSCILLATORTYPE_LSI|RCC_OSCILLATORTYPE_HSE;
377 RCC_OscInitStruct.HSEState = RCC_HSE_ON;
378 RCC_OscInitStruct.HSIState = RCC_HSI_ON;
379 RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
380 RCC_OscInitStruct.LSIState = RCC_LSI_ON;
381 RCC_OscInitStruct.HSI48State = RCC_HSI48_ON;
383 RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
384 RCC_OscInitStruct.PLL.PLLSource = pllSrc;
385 RCC_OscInitStruct.PLL.PLLM = pll_m;
386 RCC_OscInitStruct.PLL.PLLN = pll_n;
387 RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
388 RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV2;
389 RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV2;
391 if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
393 Error_Handler();
396 // Initializes the CPU, AHB and APB busses clocks
398 RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
399 |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
400 RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
401 RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
402 RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
403 RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
405 if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_8) != HAL_OK)
407 Error_Handler();
410 // Initializes the peripherals clocks
412 PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART1|RCC_PERIPHCLK_USART2
413 |RCC_PERIPHCLK_USART3|RCC_PERIPHCLK_UART4
414 |RCC_PERIPHCLK_UART5|RCC_PERIPHCLK_I2C1
415 |RCC_PERIPHCLK_I2C2|RCC_PERIPHCLK_I2C3
416 |RCC_PERIPHCLK_I2C4|RCC_PERIPHCLK_USB
417 |RCC_PERIPHCLK_ADC12
418 |RCC_PERIPHCLK_ADC345
419 |RCC_PERIPHCLK_FDCAN
420 |RCC_PERIPHCLK_LPUART1
422 PeriphClkInit.Usart1ClockSelection = RCC_USART1CLKSOURCE_PCLK2;
423 PeriphClkInit.Usart2ClockSelection = RCC_USART2CLKSOURCE_PCLK1;
424 PeriphClkInit.Usart3ClockSelection = RCC_USART3CLKSOURCE_PCLK1;
425 PeriphClkInit.Uart4ClockSelection = RCC_UART4CLKSOURCE_PCLK1;
426 PeriphClkInit.Uart5ClockSelection = RCC_UART5CLKSOURCE_PCLK1;
427 PeriphClkInit.Lpuart1ClockSelection = RCC_LPUART1CLKSOURCE_PCLK1;
428 PeriphClkInit.I2c1ClockSelection = RCC_I2C1CLKSOURCE_PCLK1;
429 PeriphClkInit.I2c2ClockSelection = RCC_I2C2CLKSOURCE_PCLK1;
430 PeriphClkInit.I2c3ClockSelection = RCC_I2C3CLKSOURCE_PCLK1;
431 PeriphClkInit.I2c4ClockSelection = RCC_I2C4CLKSOURCE_PCLK1;
432 PeriphClkInit.Adc12ClockSelection = RCC_ADC12CLKSOURCE_SYSCLK;
433 PeriphClkInit.Adc345ClockSelection = RCC_ADC345CLKSOURCE_SYSCLK;
434 PeriphClkInit.FdcanClockSelection = RCC_FDCANCLKSOURCE_PCLK1;
435 PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_HSI48;
436 PeriphClkInit.RTCClockSelection = RCC_RTCCLKSOURCE_LSI;
438 if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
440 Error_Handler();
443 // Configures CRS
445 pInit.Prescaler = RCC_CRS_SYNC_DIV1;
446 pInit.Source = RCC_CRS_SYNC_SOURCE_USB;
447 pInit.Polarity = RCC_CRS_SYNC_POLARITY_RISING;
448 pInit.ReloadValue = __HAL_RCC_CRS_RELOADVALUE_CALCULATE(48000000,1000);
449 pInit.ErrorLimitValue = 34;
450 pInit.HSI48CalibrationValue = 32;
452 HAL_RCCEx_CRSConfig(&pInit);