Merge pull request #11189 from klutvott123/move-telemetry-displayport-init
[betaflight.git] / lib / main / STM32G4 / Drivers / STM32G4xx_HAL_Driver / Src / stm32g4xx_hal_rcc.c
blob22171e8002722eb968d6a8e2417b91c1f90b5568
1 /**
2 ******************************************************************************
3 * @file stm32g4xx_hal_rcc.c
4 * @author MCD Application Team
5 * @brief RCC HAL module driver.
6 * This file provides firmware functions to manage the following
7 * functionalities of the Reset and Clock Control (RCC) peripheral:
8 * + Initialization and de-initialization functions
9 * + Peripheral Control functions
11 @verbatim
12 ==============================================================================
13 ##### RCC specific features #####
14 ==============================================================================
15 [..]
16 After reset the device is running from High Speed Internal oscillator
17 (16 MHz) with Flash 0 wait state. Flash prefetch buffer, D-Cache
18 and I-Cache are disabled, and all peripherals are off except internal
19 SRAM, Flash and JTAG.
21 (+) There is no prescaler on High speed (AHBs) and Low speed (APBs) busses:
22 all peripherals mapped on these busses are running at HSI speed.
23 (+) The clock for all peripherals is switched off, except the SRAM and FLASH.
24 (+) All GPIOs are in analog mode, except the JTAG pins which
25 are assigned to be used for debug purpose.
27 [..]
28 Once the device started from reset, the user application has to:
29 (+) Configure the clock source to be used to drive the System clock
30 (if the application needs higher frequency/performance)
31 (+) Configure the System clock frequency and Flash settings
32 (+) Configure the AHB and APB busses prescalers
33 (+) Enable the clock for the peripheral(s) to be used
34 (+) Configure the clock source(s) for peripherals which clocks are not
35 derived from the System clock (USB, RNG, USART, LPUART, FDCAN, some TIMERs,
36 UCPD, I2S, I2C, LPTIM, ADC, QSPI)
38 @endverbatim
39 ******************************************************************************
40 * @attention
42 * <h2><center>&copy; Copyright (c) 2018 STMicroelectronics.
43 * All rights reserved.</center></h2>
45 * This software component is licensed by ST under BSD 3-Clause license,
46 * the "License"; You may not use this file except in compliance with the
47 * License. You may obtain a copy of the License at:
48 * opensource.org/licenses/BSD-3-Clause
50 ******************************************************************************
53 /* Includes ------------------------------------------------------------------*/
54 #include "stm32g4xx_hal.h"
56 /** @addtogroup STM32G4xx_HAL_Driver
57 * @{
60 /** @defgroup RCC RCC
61 * @brief RCC HAL module driver
62 * @{
65 #ifdef HAL_RCC_MODULE_ENABLED
67 /* Private typedef -----------------------------------------------------------*/
68 /* Private define ------------------------------------------------------------*/
69 /** @defgroup RCC_Private_Constants RCC Private Constants
70 * @{
72 #define HSE_TIMEOUT_VALUE HSE_STARTUP_TIMEOUT
73 #define HSI_TIMEOUT_VALUE 2U /* 2 ms (minimum Tick + 1) */
74 #define LSI_TIMEOUT_VALUE 2U /* 2 ms (minimum Tick + 1) */
75 #define HSI48_TIMEOUT_VALUE 2U /* 2 ms (minimum Tick + 1) */
76 #define PLL_TIMEOUT_VALUE 2U /* 2 ms (minimum Tick + 1) */
77 #define CLOCKSWITCH_TIMEOUT_VALUE 5000U /* 5 s */
78 /**
79 * @}
82 /* Private macro -------------------------------------------------------------*/
83 /** @defgroup RCC_Private_Macros RCC Private Macros
84 * @{
86 #define MCO1_CLK_ENABLE() __HAL_RCC_GPIOA_CLK_ENABLE()
87 #define MCO1_GPIO_PORT GPIOA
88 #define MCO1_PIN GPIO_PIN_8
90 #define RCC_PLL_OSCSOURCE_CONFIG(__HAL_RCC_PLLSOURCE__) \
91 (MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, (__HAL_RCC_PLLSOURCE__)))
92 /**
93 * @}
96 /* Private variables ---------------------------------------------------------*/
98 /* Private function prototypes -----------------------------------------------*/
99 /** @defgroup RCC_Private_Functions RCC Private Functions
100 * @{
102 static uint32_t RCC_GetSysClockFreqFromPLLSource(void);
104 * @}
107 /* Exported functions --------------------------------------------------------*/
109 /** @defgroup RCC_Exported_Functions RCC Exported Functions
110 * @{
113 /** @defgroup RCC_Exported_Functions_Group1 Initialization and de-initialization functions
114 * @brief Initialization and Configuration functions
116 @verbatim
117 ===============================================================================
118 ##### Initialization and de-initialization functions #####
119 ===============================================================================
120 [..]
121 This section provides functions allowing to configure the internal and external oscillators
122 (HSE, HSI, LSE, LSI, PLL, CSS and MCO) and the System busses clocks (SYSCLK, AHB, APB1
123 and APB2).
125 [..] Internal/external clock and PLL configuration
126 (+) HSI (high-speed internal): 16 MHz factory-trimmed RC used directly or through
127 the PLL as System clock source.
129 (+) LSI (low-speed internal): 32 KHz low consumption RC used as IWDG and/or RTC
130 clock source.
132 (+) HSE (high-speed external): 4 to 48 MHz crystal oscillator used directly or
133 through the PLL as System clock source. Can be used also optionally as RTC clock source.
135 (+) LSE (low-speed external): 32.768 KHz oscillator used optionally as RTC clock source.
137 (+) PLL (clocked by HSI, HSE) providing up to three independent output clocks:
138 (++) The first output is used to generate the high speed system clock (up to 170 MHz).
139 (++) The second output is used to generate the clock for the USB (48 MHz),
140 the QSPI (<= 48 MHz), the FDCAN, the SAI and the I2S.
141 (++) The third output is used to generate a clock for ADC
143 (+) CSS (Clock security system): once enabled, if a HSE clock failure occurs
144 (HSE used directly or through PLL as System clock source), the System clock
145 is automatically switched to HSI and an interrupt is generated if enabled.
146 The interrupt is linked to the Cortex-M4 NMI (Non-Maskable Interrupt)
147 exception vector.
149 (+) MCO (microcontroller clock output): used to output LSI, HSI, LSE, HSE,
150 main PLL clock, system clock or RC48 clock (through a configurable prescaler) on PA8 pin.
152 [..] System, AHB and APB busses clocks configuration
153 (+) Several clock sources can be used to drive the System clock (SYSCLK): HSI,
154 HSE and main PLL.
155 The AHB clock (HCLK) is derived from System clock through configurable
156 prescaler and used to clock the CPU, memory and peripherals mapped
157 on AHB bus (DMA, GPIO...). APB1 (PCLK1) and APB2 (PCLK2) clocks are derived
158 from AHB clock through configurable prescalers and used to clock
159 the peripherals mapped on these busses. You can use
160 "HAL_RCC_GetSysClockFreq()" function to retrieve the frequencies of these clocks.
162 -@- All the peripheral clocks are derived from the System clock (SYSCLK) except:
164 (+@) RTC: the RTC clock can be derived either from the LSI, LSE or HSE clock
165 divided by 2 to 31.
166 You have to use __HAL_RCC_RTC_ENABLE() and HAL_RCCEx_PeriphCLKConfig() function
167 to configure this clock.
168 (+@) USB FS and RNG: USB FS requires a frequency equal to 48 MHz
169 to work correctly, while the RNG peripheral requires a frequency
170 equal or lower than to 48 MHz. This clock is derived of the main PLL
171 through PLLQ divider. You have to enable the peripheral clock and use
172 HAL_RCCEx_PeriphCLKConfig() function to configure this clock.
173 (+@) IWDG clock which is always the LSI clock.
176 (+) The maximum frequency of the SYSCLK, HCLK, PCLK1 and PCLK2 is 170 MHz.
177 The clock source frequency should be adapted depending on the device voltage range
178 as listed in the Reference Manual "Clock source frequency versus voltage scaling" chapter.
180 @endverbatim
182 Table 1. HCLK clock frequency for STM32G4xx devices
183 +--------------------------------------------------------+
184 | Latency | HCLK clock frequency (MHz) |
185 | |--------------------------------------|
186 | | voltage range 1 | voltage range 2 |
187 | | 1.2 V | 1.0 V |
188 |-----------------|-------------------|------------------|
189 |0WS(1 CPU cycles)| 0 < HCLK <= 20 | 0 < HCLK <= 8 |
190 |-----------------|-------------------|------------------|
191 |1WS(2 CPU cycles)| 20 < HCLK <= 40 | 8 < HCLK <= 16 |
192 |-----------------|-------------------|------------------|
193 |2WS(3 CPU cycles)| 40 < HCLK <= 60 | 16 < HCLK <= 26 |
194 |-----------------|-------------------|------------------|
195 |3WS(4 CPU cycles)| 60 < HCLK <= 80 | 16 < HCLK <= 26 |
196 |-----------------|-------------------|------------------|
197 |4WS(5 CPU cycles)| 80 < HCLK <= 100 | 16 < HCLK <= 26 |
198 |-----------------|-------------------|------------------|
199 |5WS(6 CPU cycles)| 100 < HCLK <= 120 | 16 < HCLK <= 26 |
200 |-----------------|-------------------|------------------|
201 |6WS(7 CPU cycles)| 120 < HCLK <= 140 | 16 < HCLK <= 26 |
202 |-----------------|-------------------|------------------|
203 |7WS(8 CPU cycles)| 140 < HCLK <= 160 | 16 < HCLK <= 26 |
204 |-----------------|-------------------|------------------|
205 |8WS(9 CPU cycles)| 160 < HCLK <= 170 | 16 < HCLK <= 26 |
206 +--------------------------------------------------------+
208 * @{
212 * @brief Reset the RCC clock configuration to the default reset state.
213 * @note The default reset state of the clock configuration is given below:
214 * - HSI ON and used as system clock source
215 * - HSE, PLL OFF
216 * - AHB, APB1 and APB2 prescaler set to 1.
217 * - CSS, MCO1 OFF
218 * - All interrupts disabled
219 * - All interrupt and reset flags cleared
220 * @note This function doesn't modify the configuration of the
221 * - Peripheral clocks
222 * - LSI, LSE and RTC clocks
223 * @retval HAL status
225 HAL_StatusTypeDef HAL_RCC_DeInit(void)
227 uint32_t tickstart;
229 /* Get Start Tick*/
230 tickstart = HAL_GetTick();
232 /* Set HSION bit to the reset value */
233 SET_BIT(RCC->CR, RCC_CR_HSION);
235 /* Wait till HSI is ready */
236 while (READ_BIT(RCC->CR, RCC_CR_HSIRDY) == 0U)
238 if ((HAL_GetTick() - tickstart) > HSI_TIMEOUT_VALUE)
240 return HAL_TIMEOUT;
244 /* Set HSITRIM[6:0] bits to the reset value */
245 SET_BIT(RCC->ICSCR, RCC_HSICALIBRATION_DEFAULT << RCC_ICSCR_HSITRIM_Pos);
247 /* Get Start Tick*/
248 tickstart = HAL_GetTick();
250 /* Reset CFGR register (HSI is selected as system clock source) */
251 RCC->CFGR = 0x00000001u;
253 /* Wait till HSI is ready */
254 while (READ_BIT(RCC->CFGR, RCC_CFGR_SWS) != RCC_CFGR_SWS_HSI)
256 if ((HAL_GetTick() - tickstart) > CLOCKSWITCH_TIMEOUT_VALUE)
258 return HAL_TIMEOUT;
262 /* Update the SystemCoreClock global variable */
263 SystemCoreClock = HSI_VALUE;
265 /* Adapt Systick interrupt period */
266 if (HAL_InitTick(TICK_INT_PRIORITY) != HAL_OK)
268 return HAL_ERROR;
271 /* Clear CR register in 2 steps: first to clear HSEON in case bypass was enabled */
272 RCC->CR = RCC_CR_HSION;
274 /* Then again to HSEBYP in case bypass was enabled */
275 RCC->CR = RCC_CR_HSION;
277 /* Get Start Tick*/
278 tickstart = HAL_GetTick();
280 /* Wait till PLL is OFF */
281 while (READ_BIT(RCC->CR, RCC_CR_PLLRDY) != 0U)
283 if ((HAL_GetTick() - tickstart) > PLL_TIMEOUT_VALUE)
285 return HAL_TIMEOUT;
289 /* once PLL is OFF, reset PLLCFGR register to default value */
290 RCC->PLLCFGR = RCC_PLLCFGR_PLLN_4;
292 /* Disable all interrupts */
293 CLEAR_REG(RCC->CIER);
295 /* Clear all interrupt flags */
296 WRITE_REG(RCC->CICR, 0xFFFFFFFFU);
298 /* Clear all reset flags */
299 SET_BIT(RCC->CSR, RCC_CSR_RMVF);
301 return HAL_OK;
305 * @brief Initialize the RCC Oscillators according to the specified parameters in the
306 * RCC_OscInitTypeDef.
307 * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that
308 * contains the configuration information for the RCC Oscillators.
309 * @note The PLL is not disabled when used as system clock.
310 * @note Transitions LSE Bypass to LSE On and LSE On to LSE Bypass are not
311 * supported by this macro. User should request a transition to LSE Off
312 * first and then LSE On or LSE Bypass.
313 * @note Transition HSE Bypass to HSE On and HSE On to HSE Bypass are not
314 * supported by this macro. User should request a transition to HSE Off
315 * first and then HSE On or HSE Bypass.
316 * @retval HAL status
318 HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct)
320 uint32_t tickstart;
321 uint32_t temp_sysclksrc;
322 uint32_t temp_pllckcfg;
324 /* Check Null pointer */
325 if (RCC_OscInitStruct == NULL)
327 return HAL_ERROR;
330 /* Check the parameters */
331 assert_param(IS_RCC_OSCILLATORTYPE(RCC_OscInitStruct->OscillatorType));
333 /*------------------------------- HSE Configuration ------------------------*/
334 if (((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSE) == RCC_OSCILLATORTYPE_HSE)
336 /* Check the parameters */
337 assert_param(IS_RCC_HSE(RCC_OscInitStruct->HSEState));
339 temp_sysclksrc = __HAL_RCC_GET_SYSCLK_SOURCE();
340 temp_pllckcfg = __HAL_RCC_GET_PLL_OSCSOURCE();
342 /* When the HSE is used as system clock or clock source for PLL in these cases it is not allowed to be disabled */
343 if (((temp_sysclksrc == RCC_CFGR_SWS_PLL) && (temp_pllckcfg == RCC_PLLSOURCE_HSE)) || (temp_sysclksrc == RCC_CFGR_SWS_HSE))
345 if ((READ_BIT(RCC->CR, RCC_CR_HSERDY) != 0U) && (RCC_OscInitStruct->HSEState == RCC_HSE_OFF))
347 return HAL_ERROR;
350 else
352 /* Set the new HSE configuration ---------------------------------------*/
353 __HAL_RCC_HSE_CONFIG(RCC_OscInitStruct->HSEState);
355 /* Check the HSE State */
356 if (RCC_OscInitStruct->HSEState != RCC_HSE_OFF)
358 /* Get Start Tick*/
359 tickstart = HAL_GetTick();
361 /* Wait till HSE is ready */
362 while (READ_BIT(RCC->CR, RCC_CR_HSERDY) == 0U)
364 if ((HAL_GetTick() - tickstart) > HSE_TIMEOUT_VALUE)
366 return HAL_TIMEOUT;
370 else
372 /* Get Start Tick*/
373 tickstart = HAL_GetTick();
375 /* Wait till HSE is disabled */
376 while (READ_BIT(RCC->CR, RCC_CR_HSERDY) != 0U)
378 if ((HAL_GetTick() - tickstart) > HSE_TIMEOUT_VALUE)
380 return HAL_TIMEOUT;
386 /*----------------------------- HSI Configuration --------------------------*/
387 if (((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI) == RCC_OSCILLATORTYPE_HSI)
389 /* Check the parameters */
390 assert_param(IS_RCC_HSI(RCC_OscInitStruct->HSIState));
391 assert_param(IS_RCC_HSI_CALIBRATION_VALUE(RCC_OscInitStruct->HSICalibrationValue));
393 /* Check if HSI is used as system clock or as PLL source when PLL is selected as system clock */
394 temp_sysclksrc = __HAL_RCC_GET_SYSCLK_SOURCE();
395 temp_pllckcfg = __HAL_RCC_GET_PLL_OSCSOURCE();
396 if (((temp_sysclksrc == RCC_CFGR_SWS_PLL) && (temp_pllckcfg == RCC_PLLSOURCE_HSI)) || (temp_sysclksrc == RCC_CFGR_SWS_HSI))
398 /* When HSI is used as system clock it will not be disabled */
399 if ((READ_BIT(RCC->CR, RCC_CR_HSIRDY) != 0U) && (RCC_OscInitStruct->HSIState == RCC_HSI_OFF))
401 return HAL_ERROR;
403 /* Otherwise, just the calibration is allowed */
404 else
406 /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/
407 __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue);
409 /* Adapt Systick interrupt period */
410 if (HAL_InitTick(TICK_INT_PRIORITY) != HAL_OK)
412 return HAL_ERROR;
416 else
418 /* Check the HSI State */
419 if (RCC_OscInitStruct->HSIState != RCC_HSI_OFF)
421 /* Enable the Internal High Speed oscillator (HSI). */
422 __HAL_RCC_HSI_ENABLE();
424 /* Get Start Tick*/
425 tickstart = HAL_GetTick();
427 /* Wait till HSI is ready */
428 while (READ_BIT(RCC->CR, RCC_CR_HSIRDY) == 0U)
430 if ((HAL_GetTick() - tickstart) > HSI_TIMEOUT_VALUE)
432 return HAL_TIMEOUT;
436 /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/
437 __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue);
439 else
441 /* Disable the Internal High Speed oscillator (HSI). */
442 __HAL_RCC_HSI_DISABLE();
444 /* Get Start Tick*/
445 tickstart = HAL_GetTick();
447 /* Wait till HSI is disabled */
448 while (READ_BIT(RCC->CR, RCC_CR_HSIRDY) != 0U)
450 if ((HAL_GetTick() - tickstart) > HSI_TIMEOUT_VALUE)
452 return HAL_TIMEOUT;
458 /*------------------------------ LSI Configuration -------------------------*/
459 if (((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSI) == RCC_OSCILLATORTYPE_LSI)
461 /* Check the parameters */
462 assert_param(IS_RCC_LSI(RCC_OscInitStruct->LSIState));
464 /* Check the LSI State */
465 if(RCC_OscInitStruct->LSIState != RCC_LSI_OFF)
467 /* Enable the Internal Low Speed oscillator (LSI). */
468 __HAL_RCC_LSI_ENABLE();
470 /* Get Start Tick*/
471 tickstart = HAL_GetTick();
473 /* Wait till LSI is ready */
474 while (READ_BIT(RCC->CSR, RCC_CSR_LSIRDY) == 0U)
476 if ((HAL_GetTick() - tickstart) > LSI_TIMEOUT_VALUE)
478 return HAL_TIMEOUT;
482 else
484 /* Disable the Internal Low Speed oscillator (LSI). */
485 __HAL_RCC_LSI_DISABLE();
487 /* Get Start Tick*/
488 tickstart = HAL_GetTick();
490 /* Wait till LSI is disabled */
491 while(READ_BIT(RCC->CSR, RCC_CSR_LSIRDY) != 0U)
493 if((HAL_GetTick() - tickstart) > LSI_TIMEOUT_VALUE)
495 return HAL_TIMEOUT;
500 /*------------------------------ LSE Configuration -------------------------*/
501 if (((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSE) == RCC_OSCILLATORTYPE_LSE)
503 FlagStatus pwrclkchanged = RESET;
505 /* Check the parameters */
506 assert_param(IS_RCC_LSE(RCC_OscInitStruct->LSEState));
508 /* Update LSE configuration in Backup Domain control register */
509 /* Requires to enable write access to Backup Domain if necessary */
510 if (__HAL_RCC_PWR_IS_CLK_DISABLED() != 0U)
512 __HAL_RCC_PWR_CLK_ENABLE();
513 pwrclkchanged = SET;
516 if (HAL_IS_BIT_CLR(PWR->CR1, PWR_CR1_DBP))
518 /* Enable write access to Backup domain */
519 SET_BIT(PWR->CR1, PWR_CR1_DBP);
521 /* Wait for Backup domain Write protection disable */
522 tickstart = HAL_GetTick();
524 while (HAL_IS_BIT_CLR(PWR->CR1, PWR_CR1_DBP))
526 if ((HAL_GetTick() - tickstart) > RCC_DBP_TIMEOUT_VALUE)
528 return HAL_TIMEOUT;
533 /* Set the new LSE configuration -----------------------------------------*/
534 __HAL_RCC_LSE_CONFIG(RCC_OscInitStruct->LSEState);
536 /* Check the LSE State */
537 if (RCC_OscInitStruct->LSEState != RCC_LSE_OFF)
539 /* Get Start Tick*/
540 tickstart = HAL_GetTick();
542 /* Wait till LSE is ready */
543 while (READ_BIT(RCC->BDCR, RCC_BDCR_LSERDY) == 0U)
545 if((HAL_GetTick() - tickstart) > RCC_LSE_TIMEOUT_VALUE)
547 return HAL_TIMEOUT;
551 else
553 /* Get Start Tick*/
554 tickstart = HAL_GetTick();
556 /* Wait till LSE is disabled */
557 while (READ_BIT(RCC->BDCR, RCC_BDCR_LSERDY) != 0U)
559 if((HAL_GetTick() - tickstart) > RCC_LSE_TIMEOUT_VALUE)
561 return HAL_TIMEOUT;
566 /* Restore clock configuration if changed */
567 if (pwrclkchanged == SET)
569 __HAL_RCC_PWR_CLK_DISABLE();
573 /*------------------------------ HSI48 Configuration -----------------------*/
574 if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI48) == RCC_OSCILLATORTYPE_HSI48)
576 /* Check the parameters */
577 assert_param(IS_RCC_HSI48(RCC_OscInitStruct->HSI48State));
579 /* Check the HSI48 State */
580 if(RCC_OscInitStruct->HSI48State != RCC_HSI48_OFF)
582 /* Enable the Internal Low Speed oscillator (HSI48). */
583 __HAL_RCC_HSI48_ENABLE();
585 /* Get Start Tick*/
586 tickstart = HAL_GetTick();
588 /* Wait till HSI48 is ready */
589 while(READ_BIT(RCC->CRRCR, RCC_CRRCR_HSI48RDY) == 0U)
591 if((HAL_GetTick() - tickstart) > HSI48_TIMEOUT_VALUE)
593 return HAL_TIMEOUT;
597 else
599 /* Disable the Internal Low Speed oscillator (HSI48). */
600 __HAL_RCC_HSI48_DISABLE();
602 /* Get Start Tick*/
603 tickstart = HAL_GetTick();
605 /* Wait till HSI48 is disabled */
606 while(READ_BIT(RCC->CRRCR, RCC_CRRCR_HSI48RDY) != 0U)
608 if((HAL_GetTick() - tickstart) > HSI48_TIMEOUT_VALUE)
610 return HAL_TIMEOUT;
616 /*-------------------------------- PLL Configuration -----------------------*/
617 /* Check the parameters */
618 assert_param(IS_RCC_PLL(RCC_OscInitStruct->PLL.PLLState));
620 if (RCC_OscInitStruct->PLL.PLLState != RCC_PLL_NONE)
622 /* Check if the PLL is used as system clock or not */
623 if (__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_CFGR_SWS_PLL)
625 if (RCC_OscInitStruct->PLL.PLLState == RCC_PLL_ON)
627 /* Check the parameters */
628 assert_param(IS_RCC_PLLSOURCE(RCC_OscInitStruct->PLL.PLLSource));
629 assert_param(IS_RCC_PLLM_VALUE(RCC_OscInitStruct->PLL.PLLM));
630 assert_param(IS_RCC_PLLN_VALUE(RCC_OscInitStruct->PLL.PLLN));
631 assert_param(IS_RCC_PLLP_VALUE(RCC_OscInitStruct->PLL.PLLP));
632 assert_param(IS_RCC_PLLQ_VALUE(RCC_OscInitStruct->PLL.PLLQ));
633 assert_param(IS_RCC_PLLR_VALUE(RCC_OscInitStruct->PLL.PLLR));
635 /* Disable the main PLL. */
636 __HAL_RCC_PLL_DISABLE();
638 /* Get Start Tick*/
639 tickstart = HAL_GetTick();
641 /* Wait till PLL is ready */
642 while (READ_BIT(RCC->CR, RCC_CR_PLLRDY) != 0U)
644 if ((HAL_GetTick() - tickstart) > PLL_TIMEOUT_VALUE)
646 return HAL_TIMEOUT;
650 /* Configure the main PLL clock source, multiplication and division factors. */
651 __HAL_RCC_PLL_CONFIG(RCC_OscInitStruct->PLL.PLLSource,
652 RCC_OscInitStruct->PLL.PLLM,
653 RCC_OscInitStruct->PLL.PLLN,
654 RCC_OscInitStruct->PLL.PLLP,
655 RCC_OscInitStruct->PLL.PLLQ,
656 RCC_OscInitStruct->PLL.PLLR);
658 /* Enable the main PLL. */
659 __HAL_RCC_PLL_ENABLE();
661 /* Enable PLL System Clock output. */
662 __HAL_RCC_PLLCLKOUT_ENABLE(RCC_PLL_SYSCLK);
664 /* Get Start Tick*/
665 tickstart = HAL_GetTick();
667 /* Wait till PLL is ready */
668 while (READ_BIT(RCC->CR, RCC_CR_PLLRDY) == 0U)
670 if ((HAL_GetTick() - tickstart) > PLL_TIMEOUT_VALUE)
672 return HAL_TIMEOUT;
676 else
678 /* Disable the main PLL. */
679 __HAL_RCC_PLL_DISABLE();
681 /* Disable all PLL outputs to save power if no PLLs on */
682 MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, RCC_PLLSOURCE_NONE);
683 __HAL_RCC_PLLCLKOUT_DISABLE(RCC_PLL_SYSCLK | RCC_PLL_48M1CLK | RCC_PLL_ADCCLK);
685 /* Get Start Tick*/
686 tickstart = HAL_GetTick();
688 /* Wait till PLL is disabled */
689 while (READ_BIT(RCC->CR, RCC_CR_PLLRDY) != 0U)
691 if ((HAL_GetTick() - tickstart) > PLL_TIMEOUT_VALUE)
693 return HAL_TIMEOUT;
698 else
700 /* Check if there is a request to disable the PLL used as System clock source */
701 if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF)
703 return HAL_ERROR;
705 else
707 /* Do not return HAL_ERROR if request repeats the current configuration */
708 temp_pllckcfg = RCC->PLLCFGR;
709 if((READ_BIT(temp_pllckcfg, RCC_PLLCFGR_PLLSRC) != RCC_OscInitStruct->PLL.PLLSource) ||
710 (READ_BIT(temp_pllckcfg, RCC_PLLCFGR_PLLM) != (((RCC_OscInitStruct->PLL.PLLM) - 1U) << RCC_PLLCFGR_PLLM_Pos)) ||
711 (READ_BIT(temp_pllckcfg, RCC_PLLCFGR_PLLN) != ((RCC_OscInitStruct->PLL.PLLN) << RCC_PLLCFGR_PLLN_Pos)) ||
712 (READ_BIT(temp_pllckcfg, RCC_PLLCFGR_PLLPDIV) != ((RCC_OscInitStruct->PLL.PLLP) << RCC_PLLCFGR_PLLPDIV_Pos)) ||
713 (READ_BIT(temp_pllckcfg, RCC_PLLCFGR_PLLQ) != ((((RCC_OscInitStruct->PLL.PLLQ) >> 1U) - 1U) << RCC_PLLCFGR_PLLQ_Pos)) ||
714 (READ_BIT(temp_pllckcfg, RCC_PLLCFGR_PLLR) != ((((RCC_OscInitStruct->PLL.PLLR) >> 1U) - 1U) << RCC_PLLCFGR_PLLR_Pos)))
716 return HAL_ERROR;
722 return HAL_OK;
726 * @brief Initialize the CPU, AHB and APB busses clocks according to the specified
727 * parameters in the RCC_ClkInitStruct.
728 * @param RCC_ClkInitStruct pointer to an RCC_OscInitTypeDef structure that
729 * contains the configuration information for the RCC peripheral.
730 * @param FLatency FLASH Latency
731 * This parameter can be one of the following values:
732 * @arg FLASH_LATENCY_0 FLASH 0 Latency cycle
733 * @arg FLASH_LATENCY_1 FLASH 1 Latency cycle
734 * @arg FLASH_LATENCY_2 FLASH 2 Latency cycles
735 * @arg FLASH_LATENCY_3 FLASH 3 Latency cycles
736 * @arg FLASH_LATENCY_4 FLASH 4 Latency cycles
737 * @arg FLASH_LATENCY_5 FLASH 5 Latency cycles
738 * @arg FLASH_LATENCY_6 FLASH 6 Latency cycles
739 * @arg FLASH_LATENCY_7 FLASH 7 Latency cycles
740 * @arg FLASH_LATENCY_8 FLASH 8 Latency cycles
741 * @arg FLASH_LATENCY_9 FLASH 9 Latency cycles
742 * @arg FLASH_LATENCY_10 FLASH 10 Latency cycles
743 * @arg FLASH_LATENCY_11 FLASH 11 Latency cycles
744 * @arg FLASH_LATENCY_12 FLASH 12 Latency cycles
745 * @arg FLASH_LATENCY_13 FLASH 13 Latency cycles
746 * @arg FLASH_LATENCY_14 FLASH 14 Latency cycles
747 * @arg FLASH_LATENCY_15 FLASH 15 Latency cycles
749 * @note The SystemCoreClock CMSIS variable is used to store System Clock Frequency
750 * and updated by HAL_RCC_GetHCLKFreq() function called within this function
752 * @note The HSI is used by default as system clock source after
753 * startup from Reset, wake-up from STANDBY mode. After restart from Reset,
754 * the HSI frequency is set to its default value 16 MHz.
756 * @note The HSI can be selected as system clock source after
757 * from STOP modes or in case of failure of the HSE used directly or indirectly
758 * as system clock (if the Clock Security System CSS is enabled).
760 * @note A switch from one clock source to another occurs only if the target
761 * clock source is ready (clock stable after startup delay or PLL locked).
762 * If a clock source which is not yet ready is selected, the switch will
763 * occur when the clock source is ready.
765 * @note You can use HAL_RCC_GetClockConfig() function to know which clock is
766 * currently used as system clock source.
768 * @note Depending on the device voltage range, the software has to set correctly
769 * HPRE[3:0] bits to ensure that HCLK not exceed the maximum allowed frequency
770 * (for more details refer to section above "Initialization/de-initialization functions")
771 * @retval None
773 HAL_StatusTypeDef HAL_RCC_ClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t FLatency)
775 uint32_t tickstart;
776 uint32_t pllfreq;
777 uint32_t hpre = RCC_SYSCLK_DIV1;
779 /* Check Null pointer */
780 if (RCC_ClkInitStruct == NULL)
782 return HAL_ERROR;
785 /* Check the parameters */
786 assert_param(IS_RCC_CLOCKTYPE(RCC_ClkInitStruct->ClockType));
787 assert_param(IS_FLASH_LATENCY(FLatency));
789 /* To correctly read data from FLASH memory, the number of wait states (LATENCY)
790 must be correctly programmed according to the frequency of the CPU clock
791 (HCLK) and the supply voltage of the device. */
793 /* Increasing the number of wait states because of higher CPU frequency */
794 if (FLatency > __HAL_FLASH_GET_LATENCY())
796 /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */
797 __HAL_FLASH_SET_LATENCY(FLatency);
799 /* Check that the new number of wait states is taken into account to access the Flash
800 memory by reading the FLASH_ACR register */
801 if (__HAL_FLASH_GET_LATENCY() != FLatency)
803 return HAL_ERROR;
807 /*------------------------- SYSCLK Configuration ---------------------------*/
808 if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_SYSCLK) == RCC_CLOCKTYPE_SYSCLK)
810 assert_param(IS_RCC_SYSCLKSOURCE(RCC_ClkInitStruct->SYSCLKSource));
812 /* PLL is selected as System Clock Source */
813 if (RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_PLLCLK)
815 /* Check the PLL ready flag */
816 if (READ_BIT(RCC->CR, RCC_CR_PLLRDY) == 0U)
818 return HAL_ERROR;
820 /* Undershoot management when selection PLL as SYSCLK source and frequency above 80Mhz */
821 /* Compute target PLL output frequency */
822 pllfreq = RCC_GetSysClockFreqFromPLLSource();
824 /* Intermediate step with HCLK prescaler 2 necessary before to go over 80Mhz */
825 if(pllfreq > 80000000U)
827 if (((READ_BIT(RCC->CFGR, RCC_CFGR_HPRE) == RCC_SYSCLK_DIV1)) ||
828 (((((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_HCLK) == RCC_CLOCKTYPE_HCLK) &&
829 (RCC_ClkInitStruct->AHBCLKDivider == RCC_SYSCLK_DIV1))))
831 MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, RCC_SYSCLK_DIV2);
832 hpre = RCC_SYSCLK_DIV2;
836 else
838 /* HSE is selected as System Clock Source */
839 if (RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_HSE)
841 /* Check the HSE ready flag */
842 if(READ_BIT(RCC->CR, RCC_CR_HSERDY) == 0U)
844 return HAL_ERROR;
847 /* HSI is selected as System Clock Source */
848 else
850 /* Check the HSI ready flag */
851 if(READ_BIT(RCC->CR, RCC_CR_HSIRDY) == 0U)
853 return HAL_ERROR;
856 /* Overshoot management when going down from PLL as SYSCLK source and frequency above 80Mhz */
857 pllfreq = HAL_RCC_GetSysClockFreq();
859 /* Intermediate step with HCLK prescaler 2 necessary before to go under 80Mhz */
860 if(pllfreq > 80000000U)
862 MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, RCC_SYSCLK_DIV2);
863 hpre = RCC_SYSCLK_DIV2;
868 MODIFY_REG(RCC->CFGR, RCC_CFGR_SW, RCC_ClkInitStruct->SYSCLKSource);
870 /* Get Start Tick*/
871 tickstart = HAL_GetTick();
873 while (__HAL_RCC_GET_SYSCLK_SOURCE() != (RCC_ClkInitStruct->SYSCLKSource << RCC_CFGR_SWS_Pos))
875 if ((HAL_GetTick() - tickstart) > CLOCKSWITCH_TIMEOUT_VALUE)
877 return HAL_TIMEOUT;
882 /*-------------------------- HCLK Configuration --------------------------*/
883 if (((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_HCLK) == RCC_CLOCKTYPE_HCLK)
885 /* Set the highest APB divider in order to ensure that we do not go through
886 a non-spec phase whatever we decrease or increase HCLK. */
887 if (((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1)
889 MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, RCC_HCLK_DIV16);
891 if (((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2)
893 MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, RCC_HCLK_DIV16);
896 /* Set the new HCLK clock divider */
897 assert_param(IS_RCC_HCLK(RCC_ClkInitStruct->AHBCLKDivider));
898 MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, RCC_ClkInitStruct->AHBCLKDivider);
900 else
902 /* Is intermediate HCLK prescaler 2 applied internally, complete with HCLK prescaler 1 */
903 if(hpre == RCC_SYSCLK_DIV2)
905 MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, RCC_SYSCLK_DIV1);
909 /* Decreasing the number of wait states because of lower CPU frequency */
910 if (FLatency < __HAL_FLASH_GET_LATENCY())
912 /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */
913 __HAL_FLASH_SET_LATENCY(FLatency);
915 /* Check that the new number of wait states is taken into account to access the Flash
916 memory by polling the FLASH_ACR register */
917 tickstart = HAL_GetTick();
919 while (__HAL_FLASH_GET_LATENCY() != FLatency)
921 if ((HAL_GetTick() - tickstart) > CLOCKSWITCH_TIMEOUT_VALUE)
923 return HAL_TIMEOUT;
928 /*-------------------------- PCLK1 Configuration ---------------------------*/
929 if (((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1)
931 assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB1CLKDivider));
932 MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, RCC_ClkInitStruct->APB1CLKDivider);
935 /*-------------------------- PCLK2 Configuration ---------------------------*/
936 if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2)
938 assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB2CLKDivider));
939 MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, ((RCC_ClkInitStruct->APB2CLKDivider) << 3U));
942 /* Update the SystemCoreClock global variable */
943 SystemCoreClock = HAL_RCC_GetSysClockFreq() >> (AHBPrescTable[READ_BIT(RCC->CFGR, RCC_CFGR_HPRE) >> RCC_CFGR_HPRE_Pos] & 0x1FU);
945 /* Configure the source of time base considering new system clocks settings*/
946 return HAL_InitTick(TICK_INT_PRIORITY);
950 * @}
953 /** @defgroup RCC_Exported_Functions_Group2 Peripheral Control functions
954 * @brief RCC clocks control functions
956 @verbatim
957 ===============================================================================
958 ##### Peripheral Control functions #####
959 ===============================================================================
960 [..]
961 This subsection provides a set of functions allowing to:
963 (+) Ouput clock to MCO pin.
964 (+) Retrieve current clock frequencies.
965 (+) Enable the Clock Security System.
967 @endverbatim
968 * @{
972 * @brief Select the clock source to output on MCO pin(PA8).
973 * @note PA8 should be configured in alternate function mode.
974 * @param RCC_MCOx specifies the output direction for the clock source.
975 * For STM32G4xx family this parameter can have only one value:
976 * @arg @ref RCC_MCO1 Clock source to output on MCO1 pin(PA8).
977 * @param RCC_MCOSource specifies the clock source to output.
978 * This parameter can be one of the following values:
979 * @arg @ref RCC_MCO1SOURCE_NOCLOCK MCO output disabled, no clock on MCO
980 * @arg @ref RCC_MCO1SOURCE_SYSCLK system clock selected as MCO source
981 * @arg @ref RCC_MCO1SOURCE_HSI HSI clock selected as MCO source
982 * @arg @ref RCC_MCO1SOURCE_HSE HSE clock selected as MCO sourcee
983 * @arg @ref RCC_MCO1SOURCE_PLLCLK main PLL clock selected as MCO source
984 * @arg @ref RCC_MCO1SOURCE_LSI LSI clock selected as MCO source
985 * @arg @ref RCC_MCO1SOURCE_LSE LSE clock selected as MCO source
986 * @arg @ref RCC_MCO1SOURCE_HSI48 HSI48 clock selected as MCO source for devices with HSI48
987 * @param RCC_MCODiv specifies the MCO prescaler.
988 * This parameter can be one of the following values:
989 * @arg @ref RCC_MCODIV_1 no division applied to MCO clock
990 * @arg @ref RCC_MCODIV_2 division by 2 applied to MCO clock
991 * @arg @ref RCC_MCODIV_4 division by 4 applied to MCO clock
992 * @arg @ref RCC_MCODIV_8 division by 8 applied to MCO clock
993 * @arg @ref RCC_MCODIV_16 division by 16 applied to MCO clock
994 * @retval None
996 void HAL_RCC_MCOConfig(uint32_t RCC_MCOx, uint32_t RCC_MCOSource, uint32_t RCC_MCODiv)
998 GPIO_InitTypeDef GPIO_InitStruct;
1000 /* Check the parameters */
1001 assert_param(IS_RCC_MCO(RCC_MCOx));
1002 assert_param(IS_RCC_MCODIV(RCC_MCODiv));
1003 assert_param(IS_RCC_MCO1SOURCE(RCC_MCOSource));
1005 /* Prevent unused argument(s) compilation warning if no assert_param check */
1006 UNUSED(RCC_MCOx);
1008 /* MCO Clock Enable */
1009 MCO1_CLK_ENABLE();
1011 /* Configue the MCO1 pin in alternate function mode */
1012 GPIO_InitStruct.Pin = MCO1_PIN;
1013 GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
1014 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
1015 GPIO_InitStruct.Pull = GPIO_NOPULL;
1016 GPIO_InitStruct.Alternate = GPIO_AF0_MCO;
1017 HAL_GPIO_Init(MCO1_GPIO_PORT, &GPIO_InitStruct);
1019 /* Mask MCOSEL[] and MCOPRE[] bits then set MCO1 clock source and prescaler */
1020 MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCOSEL | RCC_CFGR_MCOPRE), (RCC_MCOSource | RCC_MCODiv));
1024 * @brief Return the SYSCLK frequency.
1026 * @note The system frequency computed by this function is not the real
1027 * frequency in the chip. It is calculated based on the predefined
1028 * constant and the selected clock source:
1029 * @note If SYSCLK source is HSI, function returns values based on HSI_VALUE(*)
1030 * @note If SYSCLK source is HSE, function returns values based on HSE_VALUE(**)
1031 * @note If SYSCLK source is PLL, function returns values based on HSE_VALUE(**),
1032 * HSI_VALUE(*) Value multiplied/divided by the PLL factors.
1033 * @note (*) HSI_VALUE is a constant defined in stm32g4xx_hal_conf.h file (default value
1034 * 16 MHz) but the real value may vary depending on the variations
1035 * in voltage and temperature.
1036 * @note (**) HSE_VALUE is a constant defined in stm32g4xx_hal_conf.h file (default value
1037 * 8 MHz), user has to ensure that HSE_VALUE is same as the real
1038 * frequency of the crystal used. Otherwise, this function may
1039 * have wrong result.
1041 * @note The result of this function could be not correct when using fractional
1042 * value for HSE crystal.
1044 * @note This function can be used by the user application to compute the
1045 * baudrate for the communication peripherals or configure other parameters.
1047 * @note Each time SYSCLK changes, this function must be called to update the
1048 * right SYSCLK value. Otherwise, any configuration based on this function will be incorrect.
1051 * @retval SYSCLK frequency
1053 uint32_t HAL_RCC_GetSysClockFreq(void)
1055 uint32_t pllvco, pllsource, pllr, pllm;
1056 uint32_t sysclockfreq;
1058 if (__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSI)
1060 /* HSI used as system clock source */
1061 sysclockfreq = HSI_VALUE;
1063 else if (__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSE)
1065 /* HSE used as system clock source */
1066 sysclockfreq = HSE_VALUE;
1068 else if (__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL)
1070 /* PLL used as system clock source */
1072 /* PLL_VCO = ((HSE_VALUE or HSI_VALUE)/ PLLM) * PLLN
1073 SYSCLK = PLL_VCO / PLLR
1075 pllsource = READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC);
1076 pllm = (READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLM) >> RCC_PLLCFGR_PLLM_Pos) + 1U ;
1078 switch (pllsource)
1080 case RCC_PLLSOURCE_HSE: /* HSE used as PLL clock source */
1081 pllvco = (HSE_VALUE / pllm) * (READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos);
1082 break;
1084 case RCC_PLLSOURCE_HSI: /* HSI used as PLL clock source */
1085 default:
1086 pllvco = (HSI_VALUE / pllm) * (READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos);
1087 break;
1089 pllr = ((READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLR) >> RCC_PLLCFGR_PLLR_Pos) + 1U ) * 2U;
1090 sysclockfreq = pllvco/pllr;
1092 else
1094 sysclockfreq = 0U;
1097 return sysclockfreq;
1101 * @brief Return the HCLK frequency.
1102 * @note Each time HCLK changes, this function must be called to update the
1103 * right HCLK value. Otherwise, any configuration based on this function will be incorrect.
1105 * @note The SystemCoreClock CMSIS variable is used to store System Clock Frequency.
1106 * @retval HCLK frequency in Hz
1108 uint32_t HAL_RCC_GetHCLKFreq(void)
1110 return SystemCoreClock;
1114 * @brief Return the PCLK1 frequency.
1115 * @note Each time PCLK1 changes, this function must be called to update the
1116 * right PCLK1 value. Otherwise, any configuration based on this function will be incorrect.
1117 * @retval PCLK1 frequency in Hz
1119 uint32_t HAL_RCC_GetPCLK1Freq(void)
1121 /* Get HCLK source and Compute PCLK1 frequency ---------------------------*/
1122 return (HAL_RCC_GetHCLKFreq() >> (APBPrescTable[READ_BIT(RCC->CFGR, RCC_CFGR_PPRE1) >> RCC_CFGR_PPRE1_Pos] & 0x1FU));
1126 * @brief Return the PCLK2 frequency.
1127 * @note Each time PCLK2 changes, this function must be called to update the
1128 * right PCLK2 value. Otherwise, any configuration based on this function will be incorrect.
1129 * @retval PCLK2 frequency in Hz
1131 uint32_t HAL_RCC_GetPCLK2Freq(void)
1133 /* Get HCLK source and Compute PCLK2 frequency ---------------------------*/
1134 return (HAL_RCC_GetHCLKFreq()>> (APBPrescTable[READ_BIT(RCC->CFGR, RCC_CFGR_PPRE2) >> RCC_CFGR_PPRE2_Pos] & 0x1FU));
1138 * @brief Configure the RCC_OscInitStruct according to the internal
1139 * RCC configuration registers.
1140 * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that
1141 * will be configured.
1142 * @retval None
1144 void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct)
1146 /* Check the parameters */
1147 assert_param(RCC_OscInitStruct != (void *)NULL);
1149 /* Set all possible values for the Oscillator type parameter ---------------*/
1150 RCC_OscInitStruct->OscillatorType = RCC_OSCILLATORTYPE_HSE | RCC_OSCILLATORTYPE_HSI | \
1151 RCC_OSCILLATORTYPE_LSE | RCC_OSCILLATORTYPE_LSI | RCC_OSCILLATORTYPE_HSI48;
1153 /* Get the HSE configuration -----------------------------------------------*/
1154 if(READ_BIT(RCC->CR, RCC_CR_HSEBYP) == RCC_CR_HSEBYP)
1156 RCC_OscInitStruct->HSEState = RCC_HSE_BYPASS;
1158 else if(READ_BIT(RCC->CR, RCC_CR_HSEON) == RCC_CR_HSEON)
1160 RCC_OscInitStruct->HSEState = RCC_HSE_ON;
1162 else
1164 RCC_OscInitStruct->HSEState = RCC_HSE_OFF;
1167 /* Get the HSI configuration -----------------------------------------------*/
1168 if(READ_BIT(RCC->CR, RCC_CR_HSION) == RCC_CR_HSION)
1170 RCC_OscInitStruct->HSIState = RCC_HSI_ON;
1172 else
1174 RCC_OscInitStruct->HSIState = RCC_HSI_OFF;
1177 RCC_OscInitStruct->HSICalibrationValue = READ_BIT(RCC->ICSCR, RCC_ICSCR_HSITRIM) >> RCC_ICSCR_HSITRIM_Pos;
1179 /* Get the LSE configuration -----------------------------------------------*/
1180 if(READ_BIT(RCC->BDCR, RCC_BDCR_LSEBYP) == RCC_BDCR_LSEBYP)
1182 RCC_OscInitStruct->LSEState = RCC_LSE_BYPASS;
1184 else if(READ_BIT(RCC->BDCR, RCC_BDCR_LSEON) == RCC_BDCR_LSEON)
1186 RCC_OscInitStruct->LSEState = RCC_LSE_ON;
1188 else
1190 RCC_OscInitStruct->LSEState = RCC_LSE_OFF;
1193 /* Get the LSI configuration -----------------------------------------------*/
1194 if(READ_BIT(RCC->CSR, RCC_CSR_LSION) == RCC_CSR_LSION)
1196 RCC_OscInitStruct->LSIState = RCC_LSI_ON;
1198 else
1200 RCC_OscInitStruct->LSIState = RCC_LSI_OFF;
1203 /* Get the HSI48 configuration ---------------------------------------------*/
1204 if(READ_BIT(RCC->CRRCR, RCC_CRRCR_HSI48ON) == RCC_CRRCR_HSI48ON)
1206 RCC_OscInitStruct->HSI48State = RCC_HSI48_ON;
1208 else
1210 RCC_OscInitStruct->HSI48State = RCC_HSI48_OFF;
1213 /* Get the PLL configuration -----------------------------------------------*/
1214 if(READ_BIT(RCC->CR, RCC_CR_PLLON) == RCC_CR_PLLON)
1216 RCC_OscInitStruct->PLL.PLLState = RCC_PLL_ON;
1218 else
1220 RCC_OscInitStruct->PLL.PLLState = RCC_PLL_OFF;
1222 RCC_OscInitStruct->PLL.PLLSource = READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC);
1223 RCC_OscInitStruct->PLL.PLLM = (READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLM) >> RCC_PLLCFGR_PLLM_Pos) + 1U;
1224 RCC_OscInitStruct->PLL.PLLN = READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos;
1225 RCC_OscInitStruct->PLL.PLLQ = (((READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLQ) >> RCC_PLLCFGR_PLLQ_Pos) + 1U) << 1U);
1226 RCC_OscInitStruct->PLL.PLLR = (((READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLR) >> RCC_PLLCFGR_PLLR_Pos) + 1U) << 1U);
1227 RCC_OscInitStruct->PLL.PLLP = READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLPDIV) >> RCC_PLLCFGR_PLLPDIV_Pos;
1231 * @brief Configure the RCC_ClkInitStruct according to the internal
1232 * RCC configuration registers.
1233 * @param RCC_ClkInitStruct pointer to an RCC_ClkInitTypeDef structure that
1234 * will be configured.
1235 * @param pFLatency Pointer on the Flash Latency.
1236 * @retval None
1238 void HAL_RCC_GetClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t *pFLatency)
1240 /* Check the parameters */
1241 assert_param(RCC_ClkInitStruct != (void *)NULL);
1242 assert_param(pFLatency != (void *)NULL);
1244 /* Set all possible values for the Clock type parameter --------------------*/
1245 RCC_ClkInitStruct->ClockType = RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
1247 /* Get the SYSCLK configuration --------------------------------------------*/
1248 RCC_ClkInitStruct->SYSCLKSource = READ_BIT(RCC->CFGR, RCC_CFGR_SW);
1250 /* Get the HCLK configuration ----------------------------------------------*/
1251 RCC_ClkInitStruct->AHBCLKDivider = READ_BIT(RCC->CFGR, RCC_CFGR_HPRE);
1253 /* Get the APB1 configuration ----------------------------------------------*/
1254 RCC_ClkInitStruct->APB1CLKDivider = READ_BIT(RCC->CFGR, RCC_CFGR_PPRE1);
1256 /* Get the APB2 configuration ----------------------------------------------*/
1257 RCC_ClkInitStruct->APB2CLKDivider = (READ_BIT(RCC->CFGR, RCC_CFGR_PPRE2) >> 3U);
1259 /* Get the Flash Wait State (Latency) configuration ------------------------*/
1260 *pFLatency = __HAL_FLASH_GET_LATENCY();
1264 * @brief Enable the Clock Security System.
1265 * @note If a failure is detected on the HSE oscillator clock, this oscillator
1266 * is automatically disabled and an interrupt is generated to inform the
1267 * software about the failure (Clock Security System Interrupt, CSSI),
1268 * allowing the MCU to perform rescue operations. The CSSI is linked to
1269 * the Cortex-M4 NMI (Non-Maskable Interrupt) exception vector.
1270 * @note The Clock Security System can only be cleared by reset.
1271 * @retval None
1273 void HAL_RCC_EnableCSS(void)
1275 SET_BIT(RCC->CR, RCC_CR_CSSON) ;
1279 * @brief Enable the LSE Clock Security System.
1280 * @note If a failure is detected on the external 32 kHz oscillator,
1281 * the LSE clock is no longer supplied to the RTC but no hardware action
1282 * is made to the registers. If enabled, an interrupt will be generated
1283 * and handle through @ref RCCEx_EXTI_LINE_LSECSS
1284 * @note The Clock Security System can only be cleared by reset or after a LSE failure detection.
1285 * @retval None
1287 void HAL_RCC_EnableLSECSS(void)
1289 SET_BIT(RCC->BDCR, RCC_BDCR_LSECSSON) ;
1293 * @brief Disable the LSE Clock Security System.
1294 * @note After LSE failure detection, the software must disable LSECSSON
1295 * @note The Clock Security System can only be cleared by reset otherwise.
1296 * @retval None
1298 void HAL_RCC_DisableLSECSS(void)
1300 CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSECSSON) ;
1304 * @brief Handle the RCC Clock Security System interrupt request.
1305 * @note This API should be called under the NMI_Handler().
1306 * @retval None
1308 void HAL_RCC_NMI_IRQHandler(void)
1310 /* Check RCC CSSF interrupt flag */
1311 if(__HAL_RCC_GET_IT(RCC_IT_CSS))
1313 /* RCC Clock Security System interrupt user callback */
1314 HAL_RCC_CSSCallback();
1316 /* Clear RCC CSS pending bit */
1317 __HAL_RCC_CLEAR_IT(RCC_IT_CSS);
1322 * @brief RCC Clock Security System interrupt callback.
1323 * @retval none
1325 __weak void HAL_RCC_CSSCallback(void)
1327 /* NOTE : This function should not be modified, when the callback is needed,
1328 the HAL_RCC_CSSCallback should be implemented in the user file
1333 * @}
1337 * @}
1340 /* Private function prototypes -----------------------------------------------*/
1341 /** @addtogroup RCC_Private_Functions
1342 * @{
1346 * @brief Compute SYSCLK frequency based on PLL SYSCLK source.
1347 * @retval SYSCLK frequency
1349 static uint32_t RCC_GetSysClockFreqFromPLLSource(void)
1351 uint32_t pllvco, pllsource, pllr, pllm;
1352 uint32_t sysclockfreq;
1354 /* PLL_VCO = (HSE_VALUE or HSI_VALUE/ PLLM) * PLLN
1355 SYSCLK = PLL_VCO / PLLR
1357 pllsource = READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC);
1358 pllm = (READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLM) >> RCC_PLLCFGR_PLLM_Pos) + 1U ;
1360 switch (pllsource)
1362 case RCC_PLLSOURCE_HSE: /* HSE used as PLL clock source */
1363 pllvco = (HSE_VALUE / pllm) * (READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos);
1364 break;
1366 case RCC_PLLSOURCE_HSI: /* HSI used as PLL clock source */
1367 default:
1368 pllvco = (HSI_VALUE / pllm) * (READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos);
1369 break;
1372 pllr = ((READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLR) >> RCC_PLLCFGR_PLLR_Pos) + 1U ) * 2U;
1373 sysclockfreq = pllvco/pllr;
1375 return sysclockfreq;
1379 * @}
1382 #endif /* HAL_RCC_MODULE_ENABLED */
1384 * @}
1388 * @}
1391 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/