Merge pull request #11189 from klutvott123/move-telemetry-displayport-init
[betaflight.git] / lib / main / STM32F3 / Drivers / STM32F3xx_HAL_Driver / Src / stm32f3xx_hal_rcc.c
blobdcfb2d1a003251ad01dccb0bc8857fd866aa7c2d
1 /**
2 ******************************************************************************
3 * @file stm32f3xx_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 Internal High Speed oscillator
17 (HSI 8MHz) with Flash 0 wait state, Flash prefetch buffer is enabled,
18 and all peripherals are off except internal SRAM, Flash and JTAG.
19 (+) There is no prescaler on High speed (AHB) and Low speed (APB) buses;
20 all peripherals mapped on these buses are running at HSI speed.
21 (+) The clock for all peripherals is switched off, except the SRAM and FLASH.
22 (+) All GPIOs are in input floating state, except the JTAG pins which
23 are assigned to be used for debug purpose.
24 [..] Once the device started from reset, the user application has to:
25 (+) Configure the clock source to be used to drive the System clock
26 (if the application needs higher frequency/performance)
27 (+) Configure the System clock frequency and Flash settings
28 (+) Configure the AHB and APB buses prescalers
29 (+) Enable the clock for the peripheral(s) to be used
30 (+) Configure the clock source(s) for peripherals whose clocks are not
31 derived from the System clock (RTC, ADC, I2C, I2S, TIM, USB FS)
33 ##### RCC Limitations #####
34 ==============================================================================
35 [..]
36 A delay between an RCC peripheral clock enable and the effective peripheral
37 enabling should be taken into account in order to manage the peripheral read/write
38 from/to registers.
39 (+) This delay depends on the peripheral mapping.
40 (++) AHB & APB peripherals, 1 dummy read is necessary
42 [..]
43 Workarounds:
44 (#) For AHB & APB peripherals, a dummy read to the peripheral register has been
45 inserted in each __HAL_RCC_PPP_CLK_ENABLE() macro.
47 @endverbatim
48 ******************************************************************************
49 * @attention
51 * <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
53 * Redistribution and use in source and binary forms, with or without modification,
54 * are permitted provided that the following conditions are met:
55 * 1. Redistributions of source code must retain the above copyright notice,
56 * this list of conditions and the following disclaimer.
57 * 2. Redistributions in binary form must reproduce the above copyright notice,
58 * this list of conditions and the following disclaimer in the documentation
59 * and/or other materials provided with the distribution.
60 * 3. Neither the name of STMicroelectronics nor the names of its contributors
61 * may be used to endorse or promote products derived from this software
62 * without specific prior written permission.
64 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
65 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
66 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
67 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
68 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
69 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
70 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
71 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
72 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
73 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
75 ******************************************************************************
78 /* Includes ------------------------------------------------------------------*/
79 #include "stm32f3xx_hal.h"
81 /** @addtogroup STM32F3xx_HAL_Driver
82 * @{
85 /** @defgroup RCC RCC
86 * @brief RCC HAL module driver
87 * @{
90 #ifdef HAL_RCC_MODULE_ENABLED
92 /* Private typedef -----------------------------------------------------------*/
93 /* Private define ------------------------------------------------------------*/
94 /** @defgroup RCC_Private_Constants RCC Private Constants
95 * @{
97 /* Bits position in in the CFGR register */
98 #define RCC_CFGR_HPRE_BITNUMBER POSITION_VAL(RCC_CFGR_HPRE)
99 #define RCC_CFGR_PPRE1_BITNUMBER POSITION_VAL(RCC_CFGR_PPRE1)
100 #define RCC_CFGR_PPRE2_BITNUMBER POSITION_VAL(RCC_CFGR_PPRE2)
102 * @}
104 /* Private macro -------------------------------------------------------------*/
105 /** @defgroup RCC_Private_Macros RCC Private Macros
106 * @{
109 #define MCO1_CLK_ENABLE() __HAL_RCC_GPIOA_CLK_ENABLE()
110 #define MCO1_GPIO_PORT GPIOA
111 #define MCO1_PIN GPIO_PIN_8
114 * @}
117 /* Private variables ---------------------------------------------------------*/
118 /** @defgroup RCC_Private_Variables RCC Private Variables
119 * @{
121 const uint8_t aPLLMULFactorTable[16] = { 2U, 3U, 4U, 5U, 6U, 7U, 8U, 9U,
122 10U, 11U, 12U, 13U, 14U, 15U, 16U, 16U};
123 const uint8_t aPredivFactorTable[16] = { 1U, 2U, 3U, 4U, 5U, 6U, 7U, 8U,
124 9U,10U, 11U, 12U, 13U, 14U, 15U, 16U};
126 * @}
129 /* Private function prototypes -----------------------------------------------*/
130 /* Exported functions ---------------------------------------------------------*/
132 /** @defgroup RCC_Exported_Functions RCC Exported Functions
133 * @{
136 /** @defgroup RCC_Exported_Functions_Group1 Initialization and de-initialization functions
137 * @brief Initialization and Configuration functions
139 @verbatim
140 ===============================================================================
141 ##### Initialization and de-initialization functions #####
142 ===============================================================================
143 [..]
144 This section provides functions allowing to configure the internal/external oscillators
145 (HSE, HSI, LSE, LSI, PLL, CSS and MCO) and the System buses clocks (SYSCLK, AHB, APB1
146 and APB2).
148 [..] Internal/external clock and PLL configuration
149 (#) HSI (high-speed internal), 8 MHz factory-trimmed RC used directly or through
150 the PLL as System clock source.
151 The HSI clock can be used also to clock the USART and I2C peripherals.
153 (#) LSI (low-speed internal), ~40 KHz low consumption RC used as IWDG and/or RTC
154 clock source.
156 (#) HSE (high-speed external), 4 to 32 MHz crystal oscillator used directly or
157 through the PLL as System clock source. Can be used also as RTC clock source.
159 (#) LSE (low-speed external), 32 KHz oscillator used as RTC clock source.
161 (#) PLL (clocked by HSI or HSE), featuring different output clocks:
162 (++) The first output is used to generate the high speed system clock (up to 72 MHz)
163 (++) The second output is used to generate the clock for the USB FS (48 MHz)
164 (++) The third output may be used to generate the clock for the ADC peripherals (up to 72 MHz)
165 (++) The fourth output may be used to generate the clock for the TIM peripherals (144 MHz)
167 (#) CSS (Clock security system), once enable using the macro __HAL_RCC_CSS_ENABLE()
168 and if a HSE clock failure occurs(HSE used directly or through PLL as System
169 clock source), the System clocks automatically switched to HSI and an interrupt
170 is generated if enabled. The interrupt is linked to the Cortex-M4 NMI
171 (Non-Maskable Interrupt) exception vector.
173 (#) MCO (microcontroller clock output), used to output SYSCLK, HSI, HSE, LSI, LSE or PLL
174 clock (divided by 2) output on pin (such as PA8 pin).
176 [..] System, AHB and APB buses clocks configuration
177 (#) Several clock sources can be used to drive the System clock (SYSCLK): HSI,
178 HSE and PLL.
179 The AHB clock (HCLK) is derived from System clock through configurable
180 prescaler and used to clock the CPU, memory and peripherals mapped
181 on AHB bus (DMA, GPIO...). APB1 (PCLK1) and APB2 (PCLK2) clocks are derived
182 from AHB clock through configurable prescalers and used to clock
183 the peripherals mapped on these buses. You can use
184 "@ref HAL_RCC_GetSysClockFreq()" function to retrieve the frequencies of these clocks.
186 (#) All the peripheral clocks are derived from the System clock (SYSCLK) except:
187 (++) The FLASH program/erase clock which is always HSI 8MHz clock.
188 (++) The USB 48 MHz clock which is derived from the PLL VCO clock.
189 (++) The USART clock which can be derived as well from HSI 8MHz, LSI or LSE.
190 (++) The I2C clock which can be derived as well from HSI 8MHz clock.
191 (++) The ADC clock which is derived from PLL output.
192 (++) The RTC clock which is derived from the LSE, LSI or 1 MHz HSE_RTC
193 (HSE divided by a programmable prescaler). The System clock (SYSCLK)
194 frequency must be higher or equal to the RTC clock frequency.
195 (++) IWDG clock which is always the LSI clock.
197 (#) For the STM32F3xx devices, the maximum frequency of the SYSCLK, HCLK, PCLK1 and PCLK2 is 72 MHz,
198 Depending on the SYSCLK frequency, the flash latency should be adapted accordingly.
200 (#) After reset, the System clock source is the HSI (8 MHz) with 0 WS and
201 prefetch is disabled.
202 @endverbatim
203 * @{
207 Additional consideration on the SYSCLK based on Latency settings:
208 +-----------------------------------------------+
209 | Latency | SYSCLK clock frequency (MHz) |
210 |---------------|-------------------------------|
211 |0WS(1CPU cycle)| 0 < SYSCLK <= 24 |
212 |---------------|-------------------------------|
213 |1WS(2CPU cycle)| 24 < SYSCLK <= 48 |
214 |---------------|-------------------------------|
215 |2WS(3CPU cycle)| 48 < SYSCLK <= 72 |
216 +-----------------------------------------------+
220 * @brief Resets the RCC clock configuration to the default reset state.
221 * @note The default reset state of the clock configuration is given below:
222 * - HSI ON and used as system clock source
223 * - HSE and PLL OFF
224 * - AHB, APB1 and APB2 prescaler set to 1.
225 * - CSS and MCO1 OFF
226 * - All interrupts disabled
227 * @note This function does not modify the configuration of the
228 * - Peripheral clocks
229 * - LSI, LSE and RTC clocks
230 * @retval None
232 void HAL_RCC_DeInit(void)
234 /* Set HSION bit, HSITRIM[4:0] bits to the reset value*/
235 SET_BIT(RCC->CR, RCC_CR_HSION | RCC_CR_HSITRIM_4);
237 /* Reset SW[1:0], HPRE[3:0], PPRE1[2:0], PPRE2[2:0] and MCOSEL[2:0] bits */
238 CLEAR_BIT(RCC->CFGR, RCC_CFGR_SW | RCC_CFGR_HPRE | RCC_CFGR_PPRE1 | RCC_CFGR_PPRE2 | RCC_CFGR_MCO);
240 /* Reset HSEON, CSSON, PLLON bits */
241 CLEAR_BIT(RCC->CR, RCC_CR_PLLON | RCC_CR_CSSON | RCC_CR_HSEON);
243 /* Reset HSEBYP bit */
244 CLEAR_BIT(RCC->CR, RCC_CR_HSEBYP);
246 /* Reset CFGR register */
247 CLEAR_REG(RCC->CFGR);
249 /* Reset CFGR2 register */
250 CLEAR_REG(RCC->CFGR2);
252 /* Reset CFGR3 register */
253 CLEAR_REG(RCC->CFGR3);
255 /* Disable all interrupts */
256 CLEAR_REG(RCC->CIR);
258 /* Update the SystemCoreClock global variable */
259 SystemCoreClock = HSI_VALUE;
263 * @brief Initializes the RCC Oscillators according to the specified parameters in the
264 * RCC_OscInitTypeDef.
265 * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that
266 * contains the configuration information for the RCC Oscillators.
267 * @note The PLL is not disabled when used as system clock.
268 * @note Transitions LSE Bypass to LSE On and LSE On to LSE Bypass are not
269 * supported by this macro. User should request a transition to LSE Off
270 * first and then LSE On or LSE Bypass.
271 * @note Transition HSE Bypass to HSE On and HSE On to HSE Bypass are not
272 * supported by this macro. User should request a transition to HSE Off
273 * first and then HSE On or HSE Bypass.
274 * @retval HAL status
276 HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct)
278 uint32_t tickstart = 0U;
280 /* Check the parameters */
281 assert_param(RCC_OscInitStruct != NULL);
282 assert_param(IS_RCC_OSCILLATORTYPE(RCC_OscInitStruct->OscillatorType));
284 /*------------------------------- HSE Configuration ------------------------*/
285 if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSE) == RCC_OSCILLATORTYPE_HSE)
287 /* Check the parameters */
288 assert_param(IS_RCC_HSE(RCC_OscInitStruct->HSEState));
290 /* When the HSE is used as system clock or clock source for PLL in these cases it is not allowed to be disabled */
291 if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_HSE)
292 || ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_PLLCLK) && (__HAL_RCC_GET_PLL_OSCSOURCE() == RCC_PLLSOURCE_HSE)))
294 if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) && (RCC_OscInitStruct->HSEState == RCC_HSE_OFF))
296 return HAL_ERROR;
299 else
301 /* Set the new HSE configuration ---------------------------------------*/
302 __HAL_RCC_HSE_CONFIG(RCC_OscInitStruct->HSEState);
304 #if defined(RCC_CFGR_PLLSRC_HSI_DIV2)
305 /* Configure the HSE predivision factor --------------------------------*/
306 __HAL_RCC_HSE_PREDIV_CONFIG(RCC_OscInitStruct->HSEPredivValue);
307 #endif /* RCC_CFGR_PLLSRC_HSI_DIV2 */
309 /* Check the HSE State */
310 if(RCC_OscInitStruct->HSEState != RCC_HSE_OFF)
312 /* Get Start Tick */
313 tickstart = HAL_GetTick();
315 /* Wait till HSE is ready */
316 while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET)
318 if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE)
320 return HAL_TIMEOUT;
324 else
326 /* Get Start Tick */
327 tickstart = HAL_GetTick();
329 /* Wait till HSE is disabled */
330 while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET)
332 if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE)
334 return HAL_TIMEOUT;
340 /*----------------------------- HSI Configuration --------------------------*/
341 if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI) == RCC_OSCILLATORTYPE_HSI)
343 /* Check the parameters */
344 assert_param(IS_RCC_HSI(RCC_OscInitStruct->HSIState));
345 assert_param(IS_RCC_CALIBRATION_VALUE(RCC_OscInitStruct->HSICalibrationValue));
347 /* Check if HSI is used as system clock or as PLL source when PLL is selected as system clock */
348 if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_HSI)
349 || ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_PLLCLK) && (__HAL_RCC_GET_PLL_OSCSOURCE() == RCC_PLLSOURCE_HSI)))
351 /* When HSI is used as system clock it will not disabled */
352 if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) && (RCC_OscInitStruct->HSIState != RCC_HSI_ON))
354 return HAL_ERROR;
356 /* Otherwise, just the calibration is allowed */
357 else
359 /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/
360 __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue);
363 else
365 /* Check the HSI State */
366 if(RCC_OscInitStruct->HSIState != RCC_HSI_OFF)
368 /* Enable the Internal High Speed oscillator (HSI). */
369 __HAL_RCC_HSI_ENABLE();
371 /* Get Start Tick */
372 tickstart = HAL_GetTick();
374 /* Wait till HSI is ready */
375 while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET)
377 if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE)
379 return HAL_TIMEOUT;
383 /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/
384 __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue);
386 else
388 /* Disable the Internal High Speed oscillator (HSI). */
389 __HAL_RCC_HSI_DISABLE();
391 /* Get Start Tick */
392 tickstart = HAL_GetTick();
394 /* Wait till HSI is disabled */
395 while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET)
397 if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE)
399 return HAL_TIMEOUT;
405 /*------------------------------ LSI Configuration -------------------------*/
406 if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSI) == RCC_OSCILLATORTYPE_LSI)
408 /* Check the parameters */
409 assert_param(IS_RCC_LSI(RCC_OscInitStruct->LSIState));
411 /* Check the LSI State */
412 if(RCC_OscInitStruct->LSIState != RCC_LSI_OFF)
414 /* Enable the Internal Low Speed oscillator (LSI). */
415 __HAL_RCC_LSI_ENABLE();
417 /* Get Start Tick */
418 tickstart = HAL_GetTick();
420 /* Wait till LSI is ready */
421 while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) == RESET)
423 if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE)
425 return HAL_TIMEOUT;
429 else
431 /* Disable the Internal Low Speed oscillator (LSI). */
432 __HAL_RCC_LSI_DISABLE();
434 /* Get Start Tick */
435 tickstart = HAL_GetTick();
437 /* Wait till LSI is disabled */
438 while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) != RESET)
440 if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE)
442 return HAL_TIMEOUT;
447 /*------------------------------ LSE Configuration -------------------------*/
448 if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSE) == RCC_OSCILLATORTYPE_LSE)
450 FlagStatus pwrclkchanged = RESET;
452 /* Check the parameters */
453 assert_param(IS_RCC_LSE(RCC_OscInitStruct->LSEState));
455 /* Update LSE configuration in Backup Domain control register */
456 /* Requires to enable write access to Backup Domain of necessary */
457 if(__HAL_RCC_PWR_IS_CLK_DISABLED())
459 __HAL_RCC_PWR_CLK_ENABLE();
460 pwrclkchanged = SET;
463 if(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP))
465 /* Enable write access to Backup domain */
466 SET_BIT(PWR->CR, PWR_CR_DBP);
468 /* Wait for Backup domain Write protection disable */
469 tickstart = HAL_GetTick();
471 while(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP))
473 if((HAL_GetTick() - tickstart) > RCC_DBP_TIMEOUT_VALUE)
475 return HAL_TIMEOUT;
480 /* Set the new LSE configuration -----------------------------------------*/
481 __HAL_RCC_LSE_CONFIG(RCC_OscInitStruct->LSEState);
482 /* Check the LSE State */
483 if(RCC_OscInitStruct->LSEState != RCC_LSE_OFF)
485 /* Get Start Tick */
486 tickstart = HAL_GetTick();
488 /* Wait till LSE is ready */
489 while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET)
491 if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE)
493 return HAL_TIMEOUT;
497 else
499 /* Get Start Tick */
500 tickstart = HAL_GetTick();
502 /* Wait till LSE is disabled */
503 while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) != RESET)
505 if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE)
507 return HAL_TIMEOUT;
512 /* Require to disable power clock if necessary */
513 if(pwrclkchanged == SET)
515 __HAL_RCC_PWR_CLK_DISABLE();
519 /*-------------------------------- PLL Configuration -----------------------*/
520 /* Check the parameters */
521 assert_param(IS_RCC_PLL(RCC_OscInitStruct->PLL.PLLState));
522 if ((RCC_OscInitStruct->PLL.PLLState) != RCC_PLL_NONE)
524 /* Check if the PLL is used as system clock or not */
525 if(__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_SYSCLKSOURCE_STATUS_PLLCLK)
527 if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_ON)
529 /* Check the parameters */
530 assert_param(IS_RCC_PLLSOURCE(RCC_OscInitStruct->PLL.PLLSource));
531 assert_param(IS_RCC_PLL_MUL(RCC_OscInitStruct->PLL.PLLMUL));
532 #if defined(RCC_CFGR_PLLSRC_HSI_PREDIV)
533 assert_param(IS_RCC_PREDIV(RCC_OscInitStruct->PLL.PREDIV));
534 #endif
536 /* Disable the main PLL. */
537 __HAL_RCC_PLL_DISABLE();
539 /* Get Start Tick */
540 tickstart = HAL_GetTick();
542 /* Wait till PLL is disabled */
543 while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET)
545 if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE)
547 return HAL_TIMEOUT;
551 #if defined(RCC_CFGR_PLLSRC_HSI_PREDIV)
552 /* Configure the main PLL clock source, predivider and multiplication factor. */
553 __HAL_RCC_PLL_CONFIG(RCC_OscInitStruct->PLL.PLLSource,
554 RCC_OscInitStruct->PLL.PREDIV,
555 RCC_OscInitStruct->PLL.PLLMUL);
556 #else
557 /* Configure the main PLL clock source and multiplication factor. */
558 __HAL_RCC_PLL_CONFIG(RCC_OscInitStruct->PLL.PLLSource,
559 RCC_OscInitStruct->PLL.PLLMUL);
560 #endif /* RCC_CFGR_PLLSRC_HSI_PREDIV */
561 /* Enable the main PLL. */
562 __HAL_RCC_PLL_ENABLE();
564 /* Get Start Tick */
565 tickstart = HAL_GetTick();
567 /* Wait till PLL is ready */
568 while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET)
570 if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE)
572 return HAL_TIMEOUT;
576 else
578 /* Disable the main PLL. */
579 __HAL_RCC_PLL_DISABLE();
581 /* Get Start Tick */
582 tickstart = HAL_GetTick();
584 /* Wait till PLL is disabled */
585 while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET)
587 if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE)
589 return HAL_TIMEOUT;
594 else
596 return HAL_ERROR;
600 return HAL_OK;
604 * @brief Initializes the CPU, AHB and APB buses clocks according to the specified
605 * parameters in the RCC_ClkInitStruct.
606 * @param RCC_ClkInitStruct pointer to an RCC_OscInitTypeDef structure that
607 * contains the configuration information for the RCC peripheral.
608 * @param FLatency FLASH Latency
609 * The value of this parameter depend on device used within the same series
610 * @note The SystemCoreClock CMSIS variable is used to store System Clock Frequency
611 * and updated by @ref HAL_RCC_GetHCLKFreq() function called within this function
613 * @note The HSI is used (enabled by hardware) as system clock source after
614 * start-up from Reset, wake-up from STOP and STANDBY mode, or in case
615 * of failure of the HSE used directly or indirectly as system clock
616 * (if the Clock Security System CSS is enabled).
618 * @note A switch from one clock source to another occurs only if the target
619 * clock source is ready (clock stable after start-up delay or PLL locked).
620 * If a clock source which is not yet ready is selected, the switch will
621 * occur when the clock source will be ready.
622 * You can use @ref HAL_RCC_GetClockConfig() function to know which clock is
623 * currently used as system clock source.
624 * @retval HAL status
626 HAL_StatusTypeDef HAL_RCC_ClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t FLatency)
628 uint32_t tickstart = 0U;
630 /* Check the parameters */
631 assert_param(RCC_ClkInitStruct != NULL);
632 assert_param(IS_RCC_CLOCKTYPE(RCC_ClkInitStruct->ClockType));
633 assert_param(IS_FLASH_LATENCY(FLatency));
635 /* To correctly read data from FLASH memory, the number of wait states (LATENCY)
636 must be correctly programmed according to the frequency of the CPU clock
637 (HCLK) of the device. */
639 /* Increasing the number of wait states because of higher CPU frequency */
640 if(FLatency > (FLASH->ACR & FLASH_ACR_LATENCY))
642 /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */
643 __HAL_FLASH_SET_LATENCY(FLatency);
645 /* Check that the new number of wait states is taken into account to access the Flash
646 memory by reading the FLASH_ACR register */
647 if((FLASH->ACR & FLASH_ACR_LATENCY) != FLatency)
649 return HAL_ERROR;
653 /*-------------------------- HCLK Configuration --------------------------*/
654 if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_HCLK) == RCC_CLOCKTYPE_HCLK)
656 assert_param(IS_RCC_HCLK(RCC_ClkInitStruct->AHBCLKDivider));
657 MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, RCC_ClkInitStruct->AHBCLKDivider);
660 /*------------------------- SYSCLK Configuration ---------------------------*/
661 if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_SYSCLK) == RCC_CLOCKTYPE_SYSCLK)
663 assert_param(IS_RCC_SYSCLKSOURCE(RCC_ClkInitStruct->SYSCLKSource));
665 /* HSE is selected as System Clock Source */
666 if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_HSE)
668 /* Check the HSE ready flag */
669 if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET)
671 return HAL_ERROR;
674 /* PLL is selected as System Clock Source */
675 else if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_PLLCLK)
677 /* Check the PLL ready flag */
678 if(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET)
680 return HAL_ERROR;
683 /* HSI is selected as System Clock Source */
684 else
686 /* Check the HSI ready flag */
687 if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET)
689 return HAL_ERROR;
692 __HAL_RCC_SYSCLK_CONFIG(RCC_ClkInitStruct->SYSCLKSource);
694 /* Get Start Tick */
695 tickstart = HAL_GetTick();
697 if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_HSE)
699 while (__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_SYSCLKSOURCE_STATUS_HSE)
701 if((HAL_GetTick() - tickstart ) > CLOCKSWITCH_TIMEOUT_VALUE)
703 return HAL_TIMEOUT;
707 else if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_PLLCLK)
709 while (__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_SYSCLKSOURCE_STATUS_PLLCLK)
711 if((HAL_GetTick() - tickstart ) > CLOCKSWITCH_TIMEOUT_VALUE)
713 return HAL_TIMEOUT;
717 else
719 while (__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_SYSCLKSOURCE_STATUS_HSI)
721 if((HAL_GetTick() - tickstart ) > CLOCKSWITCH_TIMEOUT_VALUE)
723 return HAL_TIMEOUT;
728 /* Decreasing the number of wait states because of lower CPU frequency */
729 if(FLatency < (FLASH->ACR & FLASH_ACR_LATENCY))
731 /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */
732 __HAL_FLASH_SET_LATENCY(FLatency);
734 /* Check that the new number of wait states is taken into account to access the Flash
735 memory by reading the FLASH_ACR register */
736 if((FLASH->ACR & FLASH_ACR_LATENCY) != FLatency)
738 return HAL_ERROR;
742 /*-------------------------- PCLK1 Configuration ---------------------------*/
743 if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1)
745 assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB1CLKDivider));
746 MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, RCC_ClkInitStruct->APB1CLKDivider);
749 /*-------------------------- PCLK2 Configuration ---------------------------*/
750 if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2)
752 assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB2CLKDivider));
753 MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, ((RCC_ClkInitStruct->APB2CLKDivider) << 3U));
756 /* Update the SystemCoreClock global variable */
757 SystemCoreClock = HAL_RCC_GetSysClockFreq() >> AHBPrescTable[(RCC->CFGR & RCC_CFGR_HPRE)>> RCC_CFGR_HPRE_BITNUMBER];
759 /* Configure the source of time base considering new system clocks settings*/
760 HAL_InitTick (TICK_INT_PRIORITY);
762 return HAL_OK;
766 * @}
769 /** @defgroup RCC_Exported_Functions_Group2 Peripheral Control functions
770 * @brief RCC clocks control functions
772 @verbatim
773 ===============================================================================
774 ##### Peripheral Control functions #####
775 ===============================================================================
776 [..]
777 This subsection provides a set of functions allowing to control the RCC Clocks
778 frequencies.
780 @endverbatim
781 * @{
784 #if defined(RCC_CFGR_MCOPRE)
786 * @brief Selects the clock source to output on MCO pin.
787 * @note MCO pin should be configured in alternate function mode.
788 * @param RCC_MCOx specifies the output direction for the clock source.
789 * This parameter can be one of the following values:
790 * @arg @ref RCC_MCO1 Clock source to output on MCO1 pin(PA8).
791 * @param RCC_MCOSource specifies the clock source to output.
792 * This parameter can be one of the following values:
793 * @arg @ref RCC_MCO1SOURCE_NOCLOCK No clock selected
794 * @arg @ref RCC_MCO1SOURCE_SYSCLK System Clock selected as MCO clock
795 * @arg @ref RCC_MCO1SOURCE_HSI HSI selected as MCO clock
796 * @arg @ref RCC_MCO1SOURCE_HSE HSE selected as MCO clock
797 * @arg @ref RCC_MCO1SOURCE_LSI LSI selected as MCO clock
798 * @arg @ref RCC_MCO1SOURCE_LSE LSE selected as MCO clock
799 * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
800 * @arg @ref RCC_MCO1SOURCE_PLLCLK_DIV2 PLLCLK Divided by 2 selected as MCO clock
801 * @param RCC_MCODiv specifies the MCO DIV.
802 * This parameter can be one of the following values:
803 * @arg @ref RCC_MCODIV_1 no division applied to MCO clock
804 * @arg @ref RCC_MCODIV_2 division by 2 applied to MCO clock
805 * @arg @ref RCC_MCODIV_4 division by 4 applied to MCO clock
806 * @arg @ref RCC_MCODIV_8 division by 8 applied to MCO clock
807 * @arg @ref RCC_MCODIV_16 division by 16 applied to MCO clock
808 * @arg @ref RCC_MCODIV_32 division by 32 applied to MCO clock
809 * @arg @ref RCC_MCODIV_64 division by 64 applied to MCO clock
810 * @arg @ref RCC_MCODIV_128 division by 128 applied to MCO clock
811 * @retval None
813 #else
815 * @brief Selects the clock source to output on MCO pin.
816 * @note MCO pin should be configured in alternate function mode.
817 * @param RCC_MCOx specifies the output direction for the clock source.
818 * This parameter can be one of the following values:
819 * @arg @ref RCC_MCO1 Clock source to output on MCO1 pin(PA8).
820 * @param RCC_MCOSource specifies the clock source to output.
821 * This parameter can be one of the following values:
822 * @arg @ref RCC_MCO1SOURCE_NOCLOCK No clock selected as MCO clock
823 * @arg @ref RCC_MCO1SOURCE_SYSCLK System clock selected as MCO clock
824 * @arg @ref RCC_MCO1SOURCE_HSI HSI selected as MCO clock
825 * @arg @ref RCC_MCO1SOURCE_HSE HSE selected as MCO clock
826 * @arg @ref RCC_MCO1SOURCE_LSI LSI selected as MCO clock
827 * @arg @ref RCC_MCO1SOURCE_LSE LSE selected as MCO clock
828 * @arg @ref RCC_MCO1SOURCE_PLLCLK_DIV2 PLLCLK Divided by 2 selected as MCO clock
829 * @param RCC_MCODiv specifies the MCO DIV.
830 * This parameter can be one of the following values:
831 * @arg @ref RCC_MCODIV_1 no division applied to MCO clock
832 * @retval None
834 #endif
835 void HAL_RCC_MCOConfig(uint32_t RCC_MCOx, uint32_t RCC_MCOSource, uint32_t RCC_MCODiv)
837 GPIO_InitTypeDef gpio;
839 /* Check the parameters */
840 assert_param(IS_RCC_MCO(RCC_MCOx));
841 assert_param(IS_RCC_MCODIV(RCC_MCODiv));
842 assert_param(IS_RCC_MCO1SOURCE(RCC_MCOSource));
844 /* Configure the MCO1 pin in alternate function mode */
845 gpio.Mode = GPIO_MODE_AF_PP;
846 gpio.Speed = GPIO_SPEED_FREQ_HIGH;
847 gpio.Pull = GPIO_NOPULL;
848 gpio.Pin = MCO1_PIN;
849 gpio.Alternate = GPIO_AF0_MCO;
851 /* MCO1 Clock Enable */
852 MCO1_CLK_ENABLE();
854 HAL_GPIO_Init(MCO1_GPIO_PORT, &gpio);
856 /* Configure the MCO clock source */
857 __HAL_RCC_MCO1_CONFIG(RCC_MCOSource, RCC_MCODiv);
861 * @brief Enables the Clock Security System.
862 * @note If a failure is detected on the HSE oscillator clock, this oscillator
863 * is automatically disabled and an interrupt is generated to inform the
864 * software about the failure (Clock Security System Interrupt, CSSI),
865 * allowing the MCU to perform rescue operations. The CSSI is linked to
866 * the Cortex-M4 NMI (Non-Maskable Interrupt) exception vector.
867 * @retval None
869 void HAL_RCC_EnableCSS(void)
871 *(__IO uint32_t *) RCC_CR_CSSON_BB = (uint32_t)ENABLE;
875 * @brief Disables the Clock Security System.
876 * @retval None
878 void HAL_RCC_DisableCSS(void)
880 *(__IO uint32_t *) RCC_CR_CSSON_BB = (uint32_t)DISABLE;
884 * @brief Returns the SYSCLK frequency
885 * @note The system frequency computed by this function is not the real
886 * frequency in the chip. It is calculated based on the predefined
887 * constant and the selected clock source:
888 * @note If SYSCLK source is HSI, function returns values based on HSI_VALUE(*)
889 * @note If SYSCLK source is HSE, function returns a value based on HSE_VALUE
890 * divided by PREDIV factor(**)
891 * @note If SYSCLK source is PLL, function returns a value based on HSE_VALUE
892 * divided by PREDIV factor(**) or HSI_VALUE(*) multiplied by the PLL factor.
893 * @note (*) HSI_VALUE is a constant defined in stm32f3xx_hal_conf.h file (default value
894 * 8 MHz) but the real value may vary depending on the variations
895 * in voltage and temperature.
896 * @note (**) HSE_VALUE is a constant defined in stm32f3xx_hal_conf.h file (default value
897 * 8 MHz), user has to ensure that HSE_VALUE is same as the real
898 * frequency of the crystal used. Otherwise, this function may
899 * have wrong result.
901 * @note The result of this function could be not correct when using fractional
902 * value for HSE crystal.
904 * @note This function can be used by the user application to compute the
905 * baud-rate for the communication peripherals or configure other parameters.
907 * @note Each time SYSCLK changes, this function must be called to update the
908 * right SYSCLK value. Otherwise, any configuration based on this function will be incorrect.
910 * @retval SYSCLK frequency
912 uint32_t HAL_RCC_GetSysClockFreq(void)
914 uint32_t tmpreg = 0U, prediv = 0U, pllclk = 0U, pllmul = 0U;
915 uint32_t sysclockfreq = 0U;
917 tmpreg = RCC->CFGR;
919 /* Get SYSCLK source -------------------------------------------------------*/
920 switch (tmpreg & RCC_CFGR_SWS)
922 case RCC_SYSCLKSOURCE_STATUS_HSE: /* HSE used as system clock */
924 sysclockfreq = HSE_VALUE;
925 break;
927 case RCC_SYSCLKSOURCE_STATUS_PLLCLK: /* PLL used as system clock */
929 pllmul = aPLLMULFactorTable[(uint32_t)(tmpreg & RCC_CFGR_PLLMUL) >> POSITION_VAL(RCC_CFGR_PLLMUL)];
930 prediv = aPredivFactorTable[(uint32_t)(RCC->CFGR2 & RCC_CFGR2_PREDIV) >> POSITION_VAL(RCC_CFGR2_PREDIV)];
931 #if defined(RCC_CFGR_PLLSRC_HSI_DIV2)
932 if ((tmpreg & RCC_CFGR_PLLSRC) != RCC_PLLSOURCE_HSI)
934 /* HSE used as PLL clock source : PLLCLK = HSE/PREDIV * PLLMUL */
935 pllclk = (HSE_VALUE / prediv) * pllmul;
937 else
939 /* HSI used as PLL clock source : PLLCLK = HSI/2 * PLLMUL */
940 pllclk = (HSI_VALUE >> 1U) * pllmul;
942 #else
943 if ((tmpreg & RCC_CFGR_PLLSRC_HSE_PREDIV) == RCC_CFGR_PLLSRC_HSE_PREDIV)
945 /* HSE used as PLL clock source : PLLCLK = HSE/PREDIV * PLLMUL */
946 pllclk = (HSE_VALUE / prediv) * pllmul;
948 else
950 /* HSI used as PLL clock source : PLLCLK = HSI/PREDIV * PLLMUL */
951 pllclk = (HSI_VALUE / prediv) * pllmul;
953 #endif /* RCC_CFGR_PLLSRC_HSI_DIV2 */
954 sysclockfreq = pllclk;
955 break;
957 case RCC_SYSCLKSOURCE_STATUS_HSI: /* HSI used as system clock source */
958 default: /* HSI used as system clock */
960 sysclockfreq = HSI_VALUE;
961 break;
964 return sysclockfreq;
968 * @brief Returns the HCLK frequency
969 * @note Each time HCLK changes, this function must be called to update the
970 * right HCLK value. Otherwise, any configuration based on this function will be incorrect.
972 * @note The SystemCoreClock CMSIS variable is used to store System Clock Frequency
973 * and updated within this function
974 * @retval HCLK frequency
976 uint32_t HAL_RCC_GetHCLKFreq(void)
978 return SystemCoreClock;
982 * @brief Returns the PCLK1 frequency
983 * @note Each time PCLK1 changes, this function must be called to update the
984 * right PCLK1 value. Otherwise, any configuration based on this function will be incorrect.
985 * @retval PCLK1 frequency
987 uint32_t HAL_RCC_GetPCLK1Freq(void)
989 /* Get HCLK source and Compute PCLK1 frequency ---------------------------*/
990 return (HAL_RCC_GetHCLKFreq() >> APBPrescTable[(RCC->CFGR & RCC_CFGR_PPRE1) >> RCC_CFGR_PPRE1_BITNUMBER]);
994 * @brief Returns the PCLK2 frequency
995 * @note Each time PCLK2 changes, this function must be called to update the
996 * right PCLK2 value. Otherwise, any configuration based on this function will be incorrect.
997 * @retval PCLK2 frequency
999 uint32_t HAL_RCC_GetPCLK2Freq(void)
1001 /* Get HCLK source and Compute PCLK2 frequency ---------------------------*/
1002 return (HAL_RCC_GetHCLKFreq()>> APBPrescTable[(RCC->CFGR & RCC_CFGR_PPRE2) >> RCC_CFGR_PPRE2_BITNUMBER]);
1006 * @brief Configures the RCC_OscInitStruct according to the internal
1007 * RCC configuration registers.
1008 * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that
1009 * will be configured.
1010 * @retval None
1012 void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct)
1014 /* Check the parameters */
1015 assert_param(RCC_OscInitStruct != NULL);
1017 /* Set all possible values for the Oscillator type parameter ---------------*/
1018 RCC_OscInitStruct->OscillatorType = RCC_OSCILLATORTYPE_HSE | RCC_OSCILLATORTYPE_HSI \
1019 | RCC_OSCILLATORTYPE_LSE | RCC_OSCILLATORTYPE_LSI;
1022 /* Get the HSE configuration -----------------------------------------------*/
1023 if((RCC->CR &RCC_CR_HSEBYP) == RCC_CR_HSEBYP)
1025 RCC_OscInitStruct->HSEState = RCC_HSE_BYPASS;
1027 else if((RCC->CR &RCC_CR_HSEON) == RCC_CR_HSEON)
1029 RCC_OscInitStruct->HSEState = RCC_HSE_ON;
1031 else
1033 RCC_OscInitStruct->HSEState = RCC_HSE_OFF;
1035 #if defined(RCC_CFGR_PLLSRC_HSI_DIV2)
1036 RCC_OscInitStruct->HSEPredivValue = __HAL_RCC_HSE_GET_PREDIV();
1037 #endif
1039 /* Get the HSI configuration -----------------------------------------------*/
1040 if((RCC->CR &RCC_CR_HSION) == RCC_CR_HSION)
1042 RCC_OscInitStruct->HSIState = RCC_HSI_ON;
1044 else
1046 RCC_OscInitStruct->HSIState = RCC_HSI_OFF;
1049 RCC_OscInitStruct->HSICalibrationValue = (uint32_t)((RCC->CR & RCC_CR_HSITRIM) >> POSITION_VAL(RCC_CR_HSITRIM));
1051 /* Get the LSE configuration -----------------------------------------------*/
1052 if((RCC->BDCR &RCC_BDCR_LSEBYP) == RCC_BDCR_LSEBYP)
1054 RCC_OscInitStruct->LSEState = RCC_LSE_BYPASS;
1056 else if((RCC->BDCR &RCC_BDCR_LSEON) == RCC_BDCR_LSEON)
1058 RCC_OscInitStruct->LSEState = RCC_LSE_ON;
1060 else
1062 RCC_OscInitStruct->LSEState = RCC_LSE_OFF;
1065 /* Get the LSI configuration -----------------------------------------------*/
1066 if((RCC->CSR &RCC_CSR_LSION) == RCC_CSR_LSION)
1068 RCC_OscInitStruct->LSIState = RCC_LSI_ON;
1070 else
1072 RCC_OscInitStruct->LSIState = RCC_LSI_OFF;
1076 /* Get the PLL configuration -----------------------------------------------*/
1077 if((RCC->CR &RCC_CR_PLLON) == RCC_CR_PLLON)
1079 RCC_OscInitStruct->PLL.PLLState = RCC_PLL_ON;
1081 else
1083 RCC_OscInitStruct->PLL.PLLState = RCC_PLL_OFF;
1085 RCC_OscInitStruct->PLL.PLLSource = (uint32_t)(RCC->CFGR & RCC_CFGR_PLLSRC);
1086 RCC_OscInitStruct->PLL.PLLMUL = (uint32_t)(RCC->CFGR & RCC_CFGR_PLLMUL);
1087 #if defined(RCC_CFGR_PLLSRC_HSI_PREDIV)
1088 RCC_OscInitStruct->PLL.PREDIV = (uint32_t)(RCC->CFGR2 & RCC_CFGR2_PREDIV);
1089 #endif /* RCC_CFGR_PLLSRC_HSI_PREDIV */
1093 * @brief Get the RCC_ClkInitStruct according to the internal
1094 * RCC configuration registers.
1095 * @param RCC_ClkInitStruct pointer to an RCC_ClkInitTypeDef structure that
1096 * contains the current clock configuration.
1097 * @param pFLatency Pointer on the Flash Latency.
1098 * @retval None
1100 void HAL_RCC_GetClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t *pFLatency)
1102 /* Check the parameters */
1103 assert_param(RCC_ClkInitStruct != NULL);
1104 assert_param(pFLatency != NULL);
1106 /* Set all possible values for the Clock type parameter --------------------*/
1107 RCC_ClkInitStruct->ClockType = RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
1109 /* Get the SYSCLK configuration --------------------------------------------*/
1110 RCC_ClkInitStruct->SYSCLKSource = (uint32_t)(RCC->CFGR & RCC_CFGR_SW);
1112 /* Get the HCLK configuration ----------------------------------------------*/
1113 RCC_ClkInitStruct->AHBCLKDivider = (uint32_t)(RCC->CFGR & RCC_CFGR_HPRE);
1115 /* Get the APB1 configuration ----------------------------------------------*/
1116 RCC_ClkInitStruct->APB1CLKDivider = (uint32_t)(RCC->CFGR & RCC_CFGR_PPRE1);
1118 /* Get the APB2 configuration ----------------------------------------------*/
1119 RCC_ClkInitStruct->APB2CLKDivider = (uint32_t)((RCC->CFGR & RCC_CFGR_PPRE2) >> 3U);
1121 /* Get the Flash Wait State (Latency) configuration ------------------------*/
1122 *pFLatency = (uint32_t)(FLASH->ACR & FLASH_ACR_LATENCY);
1126 * @brief This function handles the RCC CSS interrupt request.
1127 * @note This API should be called under the NMI_Handler().
1128 * @retval None
1130 void HAL_RCC_NMI_IRQHandler(void)
1132 /* Check RCC CSSF flag */
1133 if(__HAL_RCC_GET_IT(RCC_IT_CSS))
1135 /* RCC Clock Security System interrupt user callback */
1136 HAL_RCC_CSSCallback();
1138 /* Clear RCC CSS pending bit */
1139 __HAL_RCC_CLEAR_IT(RCC_IT_CSS);
1144 * @brief RCC Clock Security System interrupt callback
1145 * @retval none
1147 __weak void HAL_RCC_CSSCallback(void)
1149 /* NOTE : This function Should not be modified, when the callback is needed,
1150 the HAL_RCC_CSSCallback could be implemented in the user file
1155 * @}
1159 * @}
1162 #endif /* HAL_RCC_MODULE_ENABLED */
1164 * @}
1168 * @}
1171 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/