2 ******************************************************************************
3 * @file stm32f7xx_ll_rcc.c
4 * @author MCD Application Team
5 * @brief RCC LL module driver.
6 ******************************************************************************
9 * <h2><center>© Copyright (c) 2017 STMicroelectronics.
10 * All rights reserved.</center></h2>
12 * This software component is licensed by ST under BSD 3-Clause license,
13 * the "License"; You may not use this file except in compliance with the
14 * License. You may obtain a copy of the License at:
15 * opensource.org/licenses/BSD-3-Clause
17 ******************************************************************************
19 #if defined(USE_FULL_LL_DRIVER)
21 /* Includes ------------------------------------------------------------------*/
22 #include "stm32f7xx_ll_rcc.h"
23 #ifdef USE_FULL_ASSERT
24 #include "stm32_assert.h"
26 #define assert_param(expr) ((void)0U)
29 /** @addtogroup STM32F7xx_LL_Driver
35 /** @addtogroup RCC_LL
39 /* Private types -------------------------------------------------------------*/
40 /* Private variables ---------------------------------------------------------*/
41 /* Private constants ---------------------------------------------------------*/
42 /* Private macros ------------------------------------------------------------*/
43 /** @addtogroup RCC_LL_Private_Macros
46 #define IS_LL_RCC_USART_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_USART1_CLKSOURCE) \
47 || ((__VALUE__) == LL_RCC_USART2_CLKSOURCE) \
48 || ((__VALUE__) == LL_RCC_USART3_CLKSOURCE) \
49 || ((__VALUE__) == LL_RCC_USART6_CLKSOURCE))
51 #define IS_LL_RCC_UART_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_UART4_CLKSOURCE) \
52 || ((__VALUE__) == LL_RCC_UART5_CLKSOURCE) \
53 || ((__VALUE__) == LL_RCC_UART7_CLKSOURCE) \
54 || ((__VALUE__) == LL_RCC_UART8_CLKSOURCE))
57 #define IS_LL_RCC_I2C_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_I2C1_CLKSOURCE) \
58 || ((__VALUE__) == LL_RCC_I2C2_CLKSOURCE) \
59 || ((__VALUE__) == LL_RCC_I2C3_CLKSOURCE) \
60 || ((__VALUE__) == LL_RCC_I2C4_CLKSOURCE))
62 #define IS_LL_RCC_I2C_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_I2C1_CLKSOURCE) \
63 || ((__VALUE__) == LL_RCC_I2C2_CLKSOURCE) \
64 || ((__VALUE__) == LL_RCC_I2C3_CLKSOURCE))
67 #define IS_LL_RCC_LPTIM_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_LPTIM1_CLKSOURCE))
69 #define IS_LL_RCC_SAI_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_SAI1_CLKSOURCE) \
70 || ((__VALUE__) == LL_RCC_SAI2_CLKSOURCE))
73 #define IS_LL_RCC_SDMMC_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_SDMMC1_CLKSOURCE) \
74 || ((__VALUE__) == LL_RCC_SDMMC2_CLKSOURCE))
76 #define IS_LL_RCC_SDMMC_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_SDMMC1_CLKSOURCE))
79 #define IS_LL_RCC_RNG_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_RNG_CLKSOURCE))
81 #define IS_LL_RCC_USB_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_USB_CLKSOURCE))
83 #if defined(DFSDM1_Channel0)
84 #define IS_LL_RCC_DFSDM_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_DFSDM1_CLKSOURCE))
86 #define IS_LL_RCC_DFSDM_AUDIO_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_DFSDM1_AUDIO_CLKSOURCE))
87 #endif /* DFSDM1_Channel0 */
89 #define IS_LL_RCC_I2S_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_I2S1_CLKSOURCE))
92 #define IS_LL_RCC_CEC_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_CEC_CLKSOURCE))
96 #define IS_LL_RCC_DSI_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_DSI_CLKSOURCE))
100 #define IS_LL_RCC_LTDC_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_LTDC_CLKSOURCE))
104 #define IS_LL_RCC_SPDIFRX_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_SPDIFRX1_CLKSOURCE))
111 /* Private function prototypes -----------------------------------------------*/
112 /** @defgroup RCC_LL_Private_Functions RCC Private functions
115 uint32_t RCC_GetSystemClockFreq(void);
116 uint32_t RCC_GetHCLKClockFreq(uint32_t SYSCLK_Frequency
);
117 uint32_t RCC_GetPCLK1ClockFreq(uint32_t HCLK_Frequency
);
118 uint32_t RCC_GetPCLK2ClockFreq(uint32_t HCLK_Frequency
);
119 uint32_t RCC_PLL_GetFreqDomain_SYS(void);
120 uint32_t RCC_PLL_GetFreqDomain_SAI(void);
121 uint32_t RCC_PLL_GetFreqDomain_48M(void);
123 uint32_t RCC_PLL_GetFreqDomain_DSI(void);
125 uint32_t RCC_PLLSAI_GetFreqDomain_SAI(void);
126 uint32_t RCC_PLLSAI_GetFreqDomain_48M(void);
128 uint32_t RCC_PLLSAI_GetFreqDomain_LTDC(void);
130 uint32_t RCC_PLLI2S_GetFreqDomain_I2S(void);
131 uint32_t RCC_PLLI2S_GetFreqDomain_SAI(void);
133 uint32_t RCC_PLLI2S_GetFreqDomain_SPDIFRX(void);
140 /* Exported functions --------------------------------------------------------*/
141 /** @addtogroup RCC_LL_Exported_Functions
145 /** @addtogroup RCC_LL_EF_Init
150 * @brief Reset the RCC clock configuration to the default reset state.
151 * @note The default reset state of the clock configuration is given below:
152 * - HSI ON and used as system clock source
153 * - HSE, PLL, PLLI2S, PLLSAI OFF
154 * - AHB, APB1 and APB2 prescaler set to 1.
156 * - All interrupts disabled
157 * @note This function doesn't modify the configuration of the
158 * - Peripheral clocks
159 * - LSI, LSE and RTC clocks
160 * @retval An ErrorStatus enumeration value:
161 * - SUCCESS: RCC registers are de-initialized
162 * - ERROR: not applicable
164 ErrorStatus
LL_RCC_DeInit(void)
166 uint32_t vl_mask
= 0xFFFFFFFFU
;
171 /* Wait for HSI READY bit */
172 while(LL_RCC_HSI_IsReady() != 1U)
175 /* Reset CFGR register */
176 LL_RCC_WriteReg(CFGR
, 0x00000000U
);
178 /* Reset HSEON, HSEBYP, PLLON, CSSON, PLLI2SON and PLLSAION bits */
179 CLEAR_BIT(vl_mask
, (RCC_CR_HSEON
| RCC_CR_HSEBYP
| RCC_CR_PLLON
| RCC_CR_CSSON
| RCC_CR_PLLSAION
| RCC_CR_PLLI2SON
));
181 /* Write new mask in CR register */
182 LL_RCC_WriteReg(CR
, vl_mask
);
184 /* Set HSITRIM bits to the reset value*/
185 LL_RCC_HSI_SetCalibTrimming(0x10U
);
187 /* Wait for PLL READY bit to be reset */
188 while(LL_RCC_PLL_IsReady() != 0U)
191 /* Wait for PLLI2S READY bit to be reset */
192 while(LL_RCC_PLLI2S_IsReady() != 0U)
195 /* Wait for PLLSAI READY bit to be reset */
196 while(LL_RCC_PLLSAI_IsReady() != 0U)
199 /* Reset PLLCFGR register */
200 LL_RCC_WriteReg(PLLCFGR
, 0x24003010U
);
202 /* Reset PLLI2SCFGR register */
203 LL_RCC_WriteReg(PLLI2SCFGR
, 0x24003000U
);
205 /* Reset PLLSAICFGR register */
206 LL_RCC_WriteReg(PLLSAICFGR
, 0x24003000U
);
208 /* Disable all interrupts */
209 CLEAR_BIT(RCC
->CIR
, RCC_CIR_LSIRDYIE
| RCC_CIR_LSERDYIE
| RCC_CIR_HSIRDYIE
| RCC_CIR_HSERDYIE
| RCC_CIR_PLLRDYIE
| RCC_CIR_PLLI2SRDYIE
| RCC_CIR_PLLSAIRDYIE
);
211 /* Clear all interrupt flags */
212 SET_BIT(RCC
->CIR
, RCC_CIR_LSIRDYC
| RCC_CIR_LSERDYC
| RCC_CIR_HSIRDYC
| RCC_CIR_HSERDYC
| RCC_CIR_PLLRDYC
| RCC_CIR_PLLI2SRDYC
| RCC_CIR_PLLSAIRDYC
| RCC_CIR_CSSC
);
214 /* Clear LSION bit */
215 CLEAR_BIT(RCC
->CSR
, RCC_CSR_LSION
);
217 /* Reset all CSR flags */
218 SET_BIT(RCC
->CSR
, RCC_CSR_RMVF
);
227 /** @addtogroup RCC_LL_EF_Get_Freq
228 * @brief Return the frequencies of different on chip clocks; System, AHB, APB1 and APB2 buses clocks
229 * and different peripheral clocks available on the device.
230 * @note If SYSCLK source is HSI, function returns values based on HSI_VALUE(**)
231 * @note If SYSCLK source is HSE, function returns values based on HSE_VALUE(***)
232 * @note If SYSCLK source is PLL, function returns values based on HSE_VALUE(***)
233 * or HSI_VALUE(**) multiplied/divided by the PLL factors.
234 * @note (**) HSI_VALUE is a constant defined in this file (default value
235 * 16 MHz) but the real value may vary depending on the variations
236 * in voltage and temperature.
237 * @note (***) HSE_VALUE is a constant defined in this file (default value
238 * 25 MHz), user has to ensure that HSE_VALUE is same as the real
239 * frequency of the crystal used. Otherwise, this function may
241 * @note The result of this function could be incorrect when using fractional
242 * value for HSE crystal.
243 * @note This function can be used by the user application to compute the
244 * baud-rate for the communication peripherals or configure other parameters.
249 * @brief Return the frequencies of different on chip clocks; System, AHB, APB1 and APB2 buses clocks
250 * @note Each time SYSCLK, HCLK, PCLK1 and/or PCLK2 clock changes, this function
251 * must be called to update structure fields. Otherwise, any
252 * configuration based on this function will be incorrect.
253 * @param RCC_Clocks pointer to a @ref LL_RCC_ClocksTypeDef structure which will hold the clocks frequencies
256 void LL_RCC_GetSystemClocksFreq(LL_RCC_ClocksTypeDef
*RCC_Clocks
)
258 /* Get SYSCLK frequency */
259 RCC_Clocks
->SYSCLK_Frequency
= RCC_GetSystemClockFreq();
261 /* HCLK clock frequency */
262 RCC_Clocks
->HCLK_Frequency
= RCC_GetHCLKClockFreq(RCC_Clocks
->SYSCLK_Frequency
);
264 /* PCLK1 clock frequency */
265 RCC_Clocks
->PCLK1_Frequency
= RCC_GetPCLK1ClockFreq(RCC_Clocks
->HCLK_Frequency
);
267 /* PCLK2 clock frequency */
268 RCC_Clocks
->PCLK2_Frequency
= RCC_GetPCLK2ClockFreq(RCC_Clocks
->HCLK_Frequency
);
272 * @brief Return USARTx clock frequency
273 * @param USARTxSource This parameter can be one of the following values:
274 * @arg @ref LL_RCC_USART1_CLKSOURCE
275 * @arg @ref LL_RCC_USART2_CLKSOURCE
276 * @arg @ref LL_RCC_USART3_CLKSOURCE
277 * @arg @ref LL_RCC_USART6_CLKSOURCE
278 * @retval USART clock frequency (in Hz)
279 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator (HSI or LSE) is not ready
281 uint32_t LL_RCC_GetUSARTClockFreq(uint32_t USARTxSource
)
283 uint32_t usart_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
285 /* Check parameter */
286 assert_param(IS_LL_RCC_USART_CLKSOURCE(USARTxSource
));
288 if (USARTxSource
== LL_RCC_USART1_CLKSOURCE
)
290 /* USART1CLK clock frequency */
291 switch (LL_RCC_GetUSARTClockSource(USARTxSource
))
293 case LL_RCC_USART1_CLKSOURCE_SYSCLK
: /* USART1 Clock is System Clock */
294 usart_frequency
= RCC_GetSystemClockFreq();
297 case LL_RCC_USART1_CLKSOURCE_HSI
: /* USART1 Clock is HSI Osc. */
298 if (LL_RCC_HSI_IsReady())
300 usart_frequency
= HSI_VALUE
;
304 case LL_RCC_USART1_CLKSOURCE_LSE
: /* USART1 Clock is LSE Osc. */
305 if (LL_RCC_LSE_IsReady())
307 usart_frequency
= LSE_VALUE
;
311 case LL_RCC_USART1_CLKSOURCE_PCLK2
: /* USART1 Clock is PCLK2 */
313 usart_frequency
= RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
317 else if (USARTxSource
== LL_RCC_USART2_CLKSOURCE
)
319 /* USART2CLK clock frequency */
320 switch (LL_RCC_GetUSARTClockSource(USARTxSource
))
322 case LL_RCC_USART2_CLKSOURCE_SYSCLK
: /* USART2 Clock is System Clock */
323 usart_frequency
= RCC_GetSystemClockFreq();
326 case LL_RCC_USART2_CLKSOURCE_HSI
: /* USART2 Clock is HSI Osc. */
327 if (LL_RCC_HSI_IsReady())
329 usart_frequency
= HSI_VALUE
;
333 case LL_RCC_USART2_CLKSOURCE_LSE
: /* USART2 Clock is LSE Osc. */
334 if (LL_RCC_LSE_IsReady())
336 usart_frequency
= LSE_VALUE
;
340 case LL_RCC_USART2_CLKSOURCE_PCLK1
: /* USART2 Clock is PCLK1 */
342 usart_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
346 else if (USARTxSource
== LL_RCC_USART6_CLKSOURCE
)
348 /* USART6CLK clock frequency */
349 switch (LL_RCC_GetUSARTClockSource(USARTxSource
))
351 case LL_RCC_USART6_CLKSOURCE_SYSCLK
: /* USART6 Clock is System Clock */
352 usart_frequency
= RCC_GetSystemClockFreq();
355 case LL_RCC_USART6_CLKSOURCE_HSI
: /* USART6 Clock is HSI Osc. */
356 if (LL_RCC_HSI_IsReady())
358 usart_frequency
= HSI_VALUE
;
362 case LL_RCC_USART6_CLKSOURCE_LSE
: /* USART6 Clock is LSE Osc. */
363 if (LL_RCC_LSE_IsReady())
365 usart_frequency
= LSE_VALUE
;
369 case LL_RCC_USART6_CLKSOURCE_PCLK2
: /* USART6 Clock is PCLK2 */
371 usart_frequency
= RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
377 if (USARTxSource
== LL_RCC_USART3_CLKSOURCE
)
379 /* USART3CLK clock frequency */
380 switch (LL_RCC_GetUSARTClockSource(USARTxSource
))
382 case LL_RCC_USART3_CLKSOURCE_SYSCLK
: /* USART3 Clock is System Clock */
383 usart_frequency
= RCC_GetSystemClockFreq();
386 case LL_RCC_USART3_CLKSOURCE_HSI
: /* USART3 Clock is HSI Osc. */
387 if (LL_RCC_HSI_IsReady())
389 usart_frequency
= HSI_VALUE
;
393 case LL_RCC_USART3_CLKSOURCE_LSE
: /* USART3 Clock is LSE Osc. */
394 if (LL_RCC_LSE_IsReady())
396 usart_frequency
= LSE_VALUE
;
400 case LL_RCC_USART3_CLKSOURCE_PCLK1
: /* USART3 Clock is PCLK1 */
402 usart_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
407 return usart_frequency
;
411 * @brief Return UARTx clock frequency
412 * @param UARTxSource This parameter can be one of the following values:
413 * @arg @ref LL_RCC_UART4_CLKSOURCE
414 * @arg @ref LL_RCC_UART5_CLKSOURCE
415 * @arg @ref LL_RCC_UART7_CLKSOURCE
416 * @arg @ref LL_RCC_UART8_CLKSOURCE
417 * @retval UART clock frequency (in Hz)
418 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator (HSI or LSE) is not ready
420 uint32_t LL_RCC_GetUARTClockFreq(uint32_t UARTxSource
)
422 uint32_t uart_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
424 /* Check parameter */
425 assert_param(IS_LL_RCC_UART_CLKSOURCE(UARTxSource
));
427 if (UARTxSource
== LL_RCC_UART4_CLKSOURCE
)
429 /* UART4CLK clock frequency */
430 switch (LL_RCC_GetUARTClockSource(UARTxSource
))
432 case LL_RCC_UART4_CLKSOURCE_SYSCLK
: /* UART4 Clock is System Clock */
433 uart_frequency
= RCC_GetSystemClockFreq();
436 case LL_RCC_UART4_CLKSOURCE_HSI
: /* UART4 Clock is HSI Osc. */
437 if (LL_RCC_HSI_IsReady())
439 uart_frequency
= HSI_VALUE
;
443 case LL_RCC_UART4_CLKSOURCE_LSE
: /* UART4 Clock is LSE Osc. */
444 if (LL_RCC_LSE_IsReady())
446 uart_frequency
= LSE_VALUE
;
450 case LL_RCC_UART4_CLKSOURCE_PCLK1
: /* UART4 Clock is PCLK1 */
452 uart_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
456 else if (UARTxSource
== LL_RCC_UART5_CLKSOURCE
)
458 /* UART5CLK clock frequency */
459 switch (LL_RCC_GetUARTClockSource(UARTxSource
))
461 case LL_RCC_UART5_CLKSOURCE_SYSCLK
: /* UART5 Clock is System Clock */
462 uart_frequency
= RCC_GetSystemClockFreq();
465 case LL_RCC_UART5_CLKSOURCE_HSI
: /* UART5 Clock is HSI Osc. */
466 if (LL_RCC_HSI_IsReady())
468 uart_frequency
= HSI_VALUE
;
472 case LL_RCC_UART5_CLKSOURCE_LSE
: /* UART5 Clock is LSE Osc. */
473 if (LL_RCC_LSE_IsReady())
475 uart_frequency
= LSE_VALUE
;
479 case LL_RCC_UART5_CLKSOURCE_PCLK1
: /* UART5 Clock is PCLK1 */
481 uart_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
485 else if (UARTxSource
== LL_RCC_UART7_CLKSOURCE
)
487 /* UART7CLK clock frequency */
488 switch (LL_RCC_GetUARTClockSource(UARTxSource
))
490 case LL_RCC_UART7_CLKSOURCE_SYSCLK
: /* UART7 Clock is System Clock */
491 uart_frequency
= RCC_GetSystemClockFreq();
494 case LL_RCC_UART7_CLKSOURCE_HSI
: /* UART7 Clock is HSI Osc. */
495 if (LL_RCC_HSI_IsReady())
497 uart_frequency
= HSI_VALUE
;
501 case LL_RCC_UART7_CLKSOURCE_LSE
: /* UART7 Clock is LSE Osc. */
502 if (LL_RCC_LSE_IsReady())
504 uart_frequency
= LSE_VALUE
;
508 case LL_RCC_UART7_CLKSOURCE_PCLK1
: /* UART7 Clock is PCLK1 */
510 uart_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
516 if (UARTxSource
== LL_RCC_UART8_CLKSOURCE
)
518 /* UART8CLK clock frequency */
519 switch (LL_RCC_GetUARTClockSource(UARTxSource
))
521 case LL_RCC_UART8_CLKSOURCE_SYSCLK
: /* UART8 Clock is System Clock */
522 uart_frequency
= RCC_GetSystemClockFreq();
525 case LL_RCC_UART8_CLKSOURCE_HSI
: /* UART8 Clock is HSI Osc. */
526 if (LL_RCC_HSI_IsReady())
528 uart_frequency
= HSI_VALUE
;
532 case LL_RCC_UART8_CLKSOURCE_LSE
: /* UART8 Clock is LSE Osc. */
533 if (LL_RCC_LSE_IsReady())
535 uart_frequency
= LSE_VALUE
;
539 case LL_RCC_UART8_CLKSOURCE_PCLK1
: /* UART8 Clock is PCLK1 */
541 uart_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
546 return uart_frequency
;
550 * @brief Return I2Cx clock frequency
551 * @param I2CxSource This parameter can be one of the following values:
552 * @arg @ref LL_RCC_I2C1_CLKSOURCE
553 * @arg @ref LL_RCC_I2C2_CLKSOURCE
554 * @arg @ref LL_RCC_I2C3_CLKSOURCE
555 * @arg @ref LL_RCC_I2C4_CLKSOURCE (*)
557 * (*) value not defined in all devices.
558 * @retval I2C clock frequency (in Hz)
559 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that HSI oscillator is not ready
561 uint32_t LL_RCC_GetI2CClockFreq(uint32_t I2CxSource
)
563 uint32_t i2c_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
565 /* Check parameter */
566 assert_param(IS_LL_RCC_I2C_CLKSOURCE(I2CxSource
));
568 if (I2CxSource
== LL_RCC_I2C1_CLKSOURCE
)
570 /* I2C1 CLK clock frequency */
571 switch (LL_RCC_GetI2CClockSource(I2CxSource
))
573 case LL_RCC_I2C1_CLKSOURCE_SYSCLK
: /* I2C1 Clock is System Clock */
574 i2c_frequency
= RCC_GetSystemClockFreq();
577 case LL_RCC_I2C1_CLKSOURCE_HSI
: /* I2C1 Clock is HSI Osc. */
578 if (LL_RCC_HSI_IsReady())
580 i2c_frequency
= HSI_VALUE
;
584 case LL_RCC_I2C1_CLKSOURCE_PCLK1
: /* I2C1 Clock is PCLK1 */
586 i2c_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
590 else if (I2CxSource
== LL_RCC_I2C2_CLKSOURCE
)
592 /* I2C2 CLK clock frequency */
593 switch (LL_RCC_GetI2CClockSource(I2CxSource
))
595 case LL_RCC_I2C2_CLKSOURCE_SYSCLK
: /* I2C2 Clock is System Clock */
596 i2c_frequency
= RCC_GetSystemClockFreq();
599 case LL_RCC_I2C2_CLKSOURCE_HSI
: /* I2C2 Clock is HSI Osc. */
600 if (LL_RCC_HSI_IsReady())
602 i2c_frequency
= HSI_VALUE
;
606 case LL_RCC_I2C2_CLKSOURCE_PCLK1
: /* I2C2 Clock is PCLK1 */
608 i2c_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
612 else if (I2CxSource
== LL_RCC_I2C3_CLKSOURCE
)
614 /* I2C3 CLK clock frequency */
615 switch (LL_RCC_GetI2CClockSource(I2CxSource
))
617 case LL_RCC_I2C3_CLKSOURCE_SYSCLK
: /* I2C3 Clock is System Clock */
618 i2c_frequency
= RCC_GetSystemClockFreq();
621 case LL_RCC_I2C3_CLKSOURCE_HSI
: /* I2C3 Clock is HSI Osc. */
622 if (LL_RCC_HSI_IsReady())
624 i2c_frequency
= HSI_VALUE
;
628 case LL_RCC_I2C3_CLKSOURCE_PCLK1
: /* I2C3 Clock is PCLK1 */
630 i2c_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
637 if (I2CxSource
== LL_RCC_I2C4_CLKSOURCE
)
639 /* I2C4 CLK clock frequency */
640 switch (LL_RCC_GetI2CClockSource(I2CxSource
))
642 case LL_RCC_I2C4_CLKSOURCE_SYSCLK
: /* I2C4 Clock is System Clock */
643 i2c_frequency
= RCC_GetSystemClockFreq();
646 case LL_RCC_I2C4_CLKSOURCE_HSI
: /* I2C4 Clock is HSI Osc. */
647 if (LL_RCC_HSI_IsReady())
649 i2c_frequency
= HSI_VALUE
;
653 case LL_RCC_I2C4_CLKSOURCE_PCLK1
: /* I2C4 Clock is PCLK1 */
655 i2c_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
662 return i2c_frequency
;
666 * @brief Return I2Sx clock frequency
667 * @param I2SxSource This parameter can be one of the following values:
668 * @arg @ref LL_RCC_I2S1_CLKSOURCE
669 * @retval I2S clock frequency (in Hz)
670 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that PLLI2S oscillator is not ready
672 uint32_t LL_RCC_GetI2SClockFreq(uint32_t I2SxSource
)
674 uint32_t i2s_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
676 /* Check parameter */
677 assert_param(IS_LL_RCC_I2S_CLKSOURCE(I2SxSource
));
679 if (I2SxSource
== LL_RCC_I2S1_CLKSOURCE
)
681 /* I2S1 CLK clock frequency */
682 switch (LL_RCC_GetI2SClockSource(I2SxSource
))
684 case LL_RCC_I2S1_CLKSOURCE_PLLI2S
: /* I2S1 Clock is PLLI2S */
685 if (LL_RCC_PLLI2S_IsReady())
687 i2s_frequency
= RCC_PLLI2S_GetFreqDomain_I2S();
691 case LL_RCC_I2S1_CLKSOURCE_PIN
: /* I2S1 Clock is External clock */
693 i2s_frequency
= EXTERNAL_CLOCK_VALUE
;
698 return i2s_frequency
;
702 * @brief Return LPTIMx clock frequency
703 * @param LPTIMxSource This parameter can be one of the following values:
704 * @arg @ref LL_RCC_LPTIM1_CLKSOURCE
705 * @retval LPTIM clock frequency (in Hz)
706 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator (HSI, LSI or LSE) is not ready
708 uint32_t LL_RCC_GetLPTIMClockFreq(uint32_t LPTIMxSource
)
710 uint32_t lptim_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
712 /* Check parameter */
713 assert_param(IS_LL_RCC_LPTIM_CLKSOURCE(LPTIMxSource
));
715 if (LPTIMxSource
== LL_RCC_LPTIM1_CLKSOURCE
)
717 /* LPTIM1CLK clock frequency */
718 switch (LL_RCC_GetLPTIMClockSource(LPTIMxSource
))
720 case LL_RCC_LPTIM1_CLKSOURCE_LSI
: /* LPTIM1 Clock is LSI Osc. */
721 if (LL_RCC_LSI_IsReady())
723 lptim_frequency
= LSI_VALUE
;
727 case LL_RCC_LPTIM1_CLKSOURCE_HSI
: /* LPTIM1 Clock is HSI Osc. */
728 if (LL_RCC_HSI_IsReady())
730 lptim_frequency
= HSI_VALUE
;
734 case LL_RCC_LPTIM1_CLKSOURCE_LSE
: /* LPTIM1 Clock is LSE Osc. */
735 if (LL_RCC_LSE_IsReady())
737 lptim_frequency
= LSE_VALUE
;
741 case LL_RCC_LPTIM1_CLKSOURCE_PCLK1
: /* LPTIM1 Clock is PCLK1 */
743 lptim_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
748 return lptim_frequency
;
752 * @brief Return SAIx clock frequency
753 * @param SAIxSource This parameter can be one of the following values:
754 * @arg @ref LL_RCC_SAI1_CLKSOURCE
755 * @arg @ref LL_RCC_SAI2_CLKSOURCE
756 * @retval SAI clock frequency (in Hz)
757 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that PLL is not ready
759 uint32_t LL_RCC_GetSAIClockFreq(uint32_t SAIxSource
)
761 uint32_t sai_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
763 /* Check parameter */
764 assert_param(IS_LL_RCC_SAI_CLKSOURCE(SAIxSource
));
766 if (SAIxSource
== LL_RCC_SAI1_CLKSOURCE
)
768 /* SAI1CLK clock frequency */
769 switch (LL_RCC_GetSAIClockSource(SAIxSource
))
771 case LL_RCC_SAI1_CLKSOURCE_PLLSAI
: /* PLLSAI clock used as SAI1 clock source */
772 if (LL_RCC_PLLSAI_IsReady())
774 sai_frequency
= RCC_PLLSAI_GetFreqDomain_SAI();
778 case LL_RCC_SAI1_CLKSOURCE_PLLI2S
: /* PLLI2S clock used as SAI1 clock source */
779 if (LL_RCC_PLLI2S_IsReady())
781 sai_frequency
= RCC_PLLI2S_GetFreqDomain_SAI();
785 #if defined(RCC_SAI1SEL_PLLSRC_SUPPORT)
786 case LL_RCC_SAI1_CLKSOURCE_PLLSRC
:
787 switch (LL_RCC_PLL_GetMainSource())
789 case LL_RCC_PLLSOURCE_HSE
: /* HSE clock used as SAI1 clock source */
790 if (LL_RCC_HSE_IsReady())
792 sai_frequency
= HSE_VALUE
;
796 case LL_RCC_PLLSOURCE_HSI
: /* HSI clock used as SAI1 clock source */
798 if (LL_RCC_HSI_IsReady())
800 sai_frequency
= HSI_VALUE
;
805 #endif /* RCC_SAI1SEL_PLLSRC_SUPPORT */
806 case LL_RCC_SAI1_CLKSOURCE_PIN
: /* External input clock used as SAI1 clock source */
807 sai_frequency
= EXTERNAL_SAI1_CLOCK_VALUE
;
816 if (SAIxSource
== LL_RCC_SAI2_CLKSOURCE
)
818 /* SAI2CLK clock frequency */
819 switch (LL_RCC_GetSAIClockSource(SAIxSource
))
821 case LL_RCC_SAI2_CLKSOURCE_PLLSAI
: /* PLLSAI clock used as SAI2 clock source */
822 if (LL_RCC_PLLSAI_IsReady())
824 sai_frequency
= RCC_PLLSAI_GetFreqDomain_SAI();
828 case LL_RCC_SAI2_CLKSOURCE_PLLI2S
: /* PLLI2S clock used as SAI2 clock source */
829 if (LL_RCC_PLLI2S_IsReady())
831 sai_frequency
= RCC_PLLI2S_GetFreqDomain_SAI();
835 #if defined(RCC_SAI2SEL_PLLSRC_SUPPORT)
836 case LL_RCC_SAI2_CLKSOURCE_PLLSRC
:
837 switch (LL_RCC_PLL_GetMainSource())
839 case LL_RCC_PLLSOURCE_HSE
: /* HSE clock used as SAI2 clock source */
840 if (LL_RCC_HSE_IsReady())
842 sai_frequency
= HSE_VALUE
;
846 case LL_RCC_PLLSOURCE_HSI
: /* HSI clock used as SAI2 clock source */
848 if (LL_RCC_HSI_IsReady())
850 sai_frequency
= HSI_VALUE
;
855 #endif /* RCC_SAI2SEL_PLLSRC_SUPPORT */
856 case LL_RCC_SAI2_CLKSOURCE_PIN
: /* External input clock used as SAI2 clock source */
857 sai_frequency
= EXTERNAL_SAI2_CLOCK_VALUE
;
866 return sai_frequency
;
870 * @brief Return SDMMCx clock frequency
871 * @param SDMMCxSource This parameter can be one of the following values:
872 * @arg @ref LL_RCC_SDMMC1_CLKSOURCE
873 * @arg @ref LL_RCC_SDMMC2_CLKSOURCE (*)
875 * (*) value not defined in all devices.
876 * @retval SDMMC clock frequency (in Hz)
877 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator PLL is not ready
879 uint32_t LL_RCC_GetSDMMCClockFreq(uint32_t SDMMCxSource
)
881 uint32_t sdmmc_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
883 /* Check parameter */
884 assert_param(IS_LL_RCC_SDMMC_CLKSOURCE(SDMMCxSource
));
886 if (SDMMCxSource
== LL_RCC_SDMMC1_CLKSOURCE
)
888 /* SDMMC1CLK clock frequency */
889 switch (LL_RCC_GetSDMMCClockSource(SDMMCxSource
))
891 case LL_RCC_SDMMC1_CLKSOURCE_PLL48CLK
: /* PLL48 clock used as SDMMC1 clock source */
892 switch (LL_RCC_GetCK48MClockSource(LL_RCC_CK48M_CLKSOURCE
))
894 case LL_RCC_CK48M_CLKSOURCE_PLL
: /* PLL clock used as 48Mhz domain clock */
895 if (LL_RCC_PLL_IsReady())
897 sdmmc_frequency
= RCC_PLL_GetFreqDomain_48M();
901 case LL_RCC_CK48M_CLKSOURCE_PLLSAI
: /* PLLSAI clock used as 48Mhz domain clock */
903 if (LL_RCC_PLLSAI_IsReady())
905 sdmmc_frequency
= RCC_PLLSAI_GetFreqDomain_48M();
911 case LL_RCC_SDMMC1_CLKSOURCE_SYSCLK
: /* PLL clock used as SDMMC1 clock source */
913 sdmmc_frequency
= RCC_GetSystemClockFreq();
920 /* SDMMC2CLK clock frequency */
921 switch (LL_RCC_GetSDMMCClockSource(SDMMCxSource
))
923 case LL_RCC_SDMMC2_CLKSOURCE_PLL48CLK
: /* PLL48 clock used as SDMMC2 clock source */
924 switch (LL_RCC_GetCK48MClockSource(LL_RCC_CK48M_CLKSOURCE
))
926 case LL_RCC_CK48M_CLKSOURCE_PLL
: /* PLL clock used as 48Mhz domain clock */
927 if (LL_RCC_PLL_IsReady())
929 sdmmc_frequency
= RCC_PLL_GetFreqDomain_48M();
933 case LL_RCC_CK48M_CLKSOURCE_PLLSAI
: /* PLLSAI clock used as 48Mhz domain clock */
935 if (LL_RCC_PLLSAI_IsReady())
937 sdmmc_frequency
= RCC_PLLSAI_GetFreqDomain_48M();
943 case LL_RCC_SDMMC2_CLKSOURCE_SYSCLK
: /* PLL clock used as SDMMC2 clock source */
945 sdmmc_frequency
= RCC_GetSystemClockFreq();
951 return sdmmc_frequency
;
955 * @brief Return RNGx clock frequency
956 * @param RNGxSource This parameter can be one of the following values:
957 * @arg @ref LL_RCC_RNG_CLKSOURCE
958 * @retval RNG clock frequency (in Hz)
959 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready
961 uint32_t LL_RCC_GetRNGClockFreq(uint32_t RNGxSource
)
963 uint32_t rng_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
965 /* Check parameter */
966 assert_param(IS_LL_RCC_RNG_CLKSOURCE(RNGxSource
));
968 /* RNGCLK clock frequency */
969 switch (LL_RCC_GetRNGClockSource(RNGxSource
))
971 case LL_RCC_RNG_CLKSOURCE_PLL
: /* PLL clock used as RNG clock source */
972 if (LL_RCC_PLL_IsReady())
974 rng_frequency
= RCC_PLL_GetFreqDomain_48M();
978 case LL_RCC_RNG_CLKSOURCE_PLLSAI
: /* PLLSAI clock used as RNG clock source */
980 if (LL_RCC_PLLSAI_IsReady())
982 rng_frequency
= RCC_PLLSAI_GetFreqDomain_48M();
987 return rng_frequency
;
992 * @brief Return CEC clock frequency
993 * @param CECxSource This parameter can be one of the following values:
994 * @arg @ref LL_RCC_CEC_CLKSOURCE
995 * @retval CEC clock frequency (in Hz)
996 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator (HSI or LSE) is not ready
998 uint32_t LL_RCC_GetCECClockFreq(uint32_t CECxSource
)
1000 uint32_t cec_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
1002 /* Check parameter */
1003 assert_param(IS_LL_RCC_CEC_CLKSOURCE(CECxSource
));
1005 /* CECCLK clock frequency */
1006 switch (LL_RCC_GetCECClockSource(CECxSource
))
1008 case LL_RCC_CEC_CLKSOURCE_LSE
: /* CEC Clock is LSE Osc. */
1009 if (LL_RCC_LSE_IsReady())
1011 cec_frequency
= LSE_VALUE
;
1015 case LL_RCC_CEC_CLKSOURCE_HSI_DIV488
: /* CEC Clock is HSI Osc. */
1017 if (LL_RCC_HSI_IsReady())
1019 cec_frequency
= HSI_VALUE
/488U;
1024 return cec_frequency
;
1029 * @brief Return USBx clock frequency
1030 * @param USBxSource This parameter can be one of the following values:
1031 * @arg @ref LL_RCC_USB_CLKSOURCE
1032 * @retval USB clock frequency (in Hz)
1034 uint32_t LL_RCC_GetUSBClockFreq(uint32_t USBxSource
)
1036 uint32_t usb_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
1038 /* Check parameter */
1039 assert_param(IS_LL_RCC_USB_CLKSOURCE(USBxSource
));
1041 /* USBCLK clock frequency */
1042 switch (LL_RCC_GetUSBClockSource(USBxSource
))
1044 case LL_RCC_USB_CLKSOURCE_PLL
: /* PLL clock used as USB clock source */
1045 if (LL_RCC_PLL_IsReady())
1047 usb_frequency
= RCC_PLL_GetFreqDomain_48M();
1051 case LL_RCC_USB_CLKSOURCE_PLLSAI
: /* PLLSAI clock used as USB clock source */
1053 if (LL_RCC_PLLSAI_IsReady())
1055 usb_frequency
= RCC_PLLSAI_GetFreqDomain_48M();
1060 return usb_frequency
;
1063 #if defined(DFSDM1_Channel0)
1065 * @brief Return DFSDMx clock frequency
1066 * @param DFSDMxSource This parameter can be one of the following values:
1067 * @arg @ref LL_RCC_DFSDM1_CLKSOURCE
1068 * @retval DFSDM clock frequency (in Hz)
1070 uint32_t LL_RCC_GetDFSDMClockFreq(uint32_t DFSDMxSource
)
1072 uint32_t dfsdm_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
1074 /* Check parameter */
1075 assert_param(IS_LL_RCC_DFSDM_CLKSOURCE(DFSDMxSource
));
1077 /* DFSDM1CLK clock frequency */
1078 switch (LL_RCC_GetDFSDMClockSource(DFSDMxSource
))
1080 case LL_RCC_DFSDM1_CLKSOURCE_SYSCLK
: /* DFSDM1 Clock is SYSCLK */
1081 dfsdm_frequency
= RCC_GetSystemClockFreq();
1084 case LL_RCC_DFSDM1_CLKSOURCE_PCLK2
: /* DFSDM1 Clock is PCLK2 */
1086 dfsdm_frequency
= RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
1090 return dfsdm_frequency
;
1094 * @brief Return DFSDMx Audio clock frequency
1095 * @param DFSDMxSource This parameter can be one of the following values:
1096 * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE
1097 * @retval DFSDM clock frequency (in Hz)
1098 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready
1100 uint32_t LL_RCC_GetDFSDMAudioClockFreq(uint32_t DFSDMxSource
)
1102 uint32_t dfsdm_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
1104 /* Check parameter */
1105 assert_param(IS_LL_RCC_DFSDM_AUDIO_CLKSOURCE(DFSDMxSource
));
1107 /* DFSDM1CLK clock frequency */
1108 switch (LL_RCC_GetDFSDMAudioClockSource(DFSDMxSource
))
1110 case LL_RCC_DFSDM1_AUDIO_CLKSOURCE_SAI1
: /* SAI1 clock used as DFSDM1 audio clock */
1111 dfsdm_frequency
= LL_RCC_GetSAIClockFreq(LL_RCC_SAI1_CLKSOURCE
);
1114 case LL_RCC_DFSDM1_AUDIO_CLKSOURCE_SAI2
: /* SAI2 clock used as DFSDM1 audio clock */
1116 dfsdm_frequency
= LL_RCC_GetSAIClockFreq(LL_RCC_SAI2_CLKSOURCE
);
1120 return dfsdm_frequency
;
1122 #endif /* DFSDM1_Channel0 */
1126 * @brief Return DSI clock frequency
1127 * @param DSIxSource This parameter can be one of the following values:
1128 * @arg @ref LL_RCC_DSI_CLKSOURCE
1129 * @retval DSI clock frequency (in Hz)
1130 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready
1131 * - @ref LL_RCC_PERIPH_FREQUENCY_NA indicates that external clock is used
1133 uint32_t LL_RCC_GetDSIClockFreq(uint32_t DSIxSource
)
1135 uint32_t dsi_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
1137 /* Check parameter */
1138 assert_param(IS_LL_RCC_DSI_CLKSOURCE(DSIxSource
));
1140 /* DSICLK clock frequency */
1141 switch (LL_RCC_GetDSIClockSource(DSIxSource
))
1143 case LL_RCC_DSI_CLKSOURCE_PLL
: /* DSI Clock is PLL Osc. */
1144 if (LL_RCC_PLL_IsReady())
1146 dsi_frequency
= RCC_PLL_GetFreqDomain_DSI();
1150 case LL_RCC_DSI_CLKSOURCE_PHY
: /* DSI Clock is DSI physical clock. */
1152 dsi_frequency
= LL_RCC_PERIPH_FREQUENCY_NA
;
1156 return dsi_frequency
;
1162 * @brief Return LTDC clock frequency
1163 * @param LTDCxSource This parameter can be one of the following values:
1164 * @arg @ref LL_RCC_LTDC_CLKSOURCE
1165 * @retval LTDC clock frequency (in Hz)
1166 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator PLLSAI is not ready
1168 uint32_t LL_RCC_GetLTDCClockFreq(uint32_t LTDCxSource
)
1170 UNUSED(LTDCxSource
);
1172 uint32_t ltdc_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
1174 /* Check parameter */
1175 assert_param(IS_LL_RCC_LTDC_CLKSOURCE(LTDCxSource
));
1177 if (LL_RCC_PLLSAI_IsReady())
1179 ltdc_frequency
= RCC_PLLSAI_GetFreqDomain_LTDC();
1182 return ltdc_frequency
;
1186 #if defined(SPDIFRX)
1188 * @brief Return SPDIFRX clock frequency
1189 * @param SPDIFRXxSource This parameter can be one of the following values:
1190 * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE
1191 * @retval SPDIFRX clock frequency (in Hz)
1192 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready
1194 uint32_t LL_RCC_GetSPDIFRXClockFreq(uint32_t SPDIFRXxSource
)
1196 UNUSED(SPDIFRXxSource
);
1198 uint32_t spdifrx_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
1200 /* Check parameter */
1201 assert_param(IS_LL_RCC_SPDIFRX_CLKSOURCE(SPDIFRXxSource
));
1203 if (LL_RCC_PLLI2S_IsReady())
1205 spdifrx_frequency
= RCC_PLLI2S_GetFreqDomain_SPDIFRX();
1208 return spdifrx_frequency
;
1210 #endif /* SPDIFRX */
1220 /** @addtogroup RCC_LL_Private_Functions
1225 * @brief Return SYSTEM clock frequency
1226 * @retval SYSTEM clock frequency (in Hz)
1228 uint32_t RCC_GetSystemClockFreq(void)
1230 uint32_t frequency
= 0U;
1232 /* Get SYSCLK source -------------------------------------------------------*/
1233 switch (LL_RCC_GetSysClkSource())
1235 case LL_RCC_SYS_CLKSOURCE_STATUS_HSI
: /* HSI used as system clock source */
1236 frequency
= HSI_VALUE
;
1239 case LL_RCC_SYS_CLKSOURCE_STATUS_HSE
: /* HSE used as system clock source */
1240 frequency
= HSE_VALUE
;
1243 case LL_RCC_SYS_CLKSOURCE_STATUS_PLL
: /* PLL used as system clock source */
1244 frequency
= RCC_PLL_GetFreqDomain_SYS();
1248 frequency
= HSI_VALUE
;
1256 * @brief Return HCLK clock frequency
1257 * @param SYSCLK_Frequency SYSCLK clock frequency
1258 * @retval HCLK clock frequency (in Hz)
1260 uint32_t RCC_GetHCLKClockFreq(uint32_t SYSCLK_Frequency
)
1262 /* HCLK clock frequency */
1263 return __LL_RCC_CALC_HCLK_FREQ(SYSCLK_Frequency
, LL_RCC_GetAHBPrescaler());
1267 * @brief Return PCLK1 clock frequency
1268 * @param HCLK_Frequency HCLK clock frequency
1269 * @retval PCLK1 clock frequency (in Hz)
1271 uint32_t RCC_GetPCLK1ClockFreq(uint32_t HCLK_Frequency
)
1273 /* PCLK1 clock frequency */
1274 return __LL_RCC_CALC_PCLK1_FREQ(HCLK_Frequency
, LL_RCC_GetAPB1Prescaler());
1278 * @brief Return PCLK2 clock frequency
1279 * @param HCLK_Frequency HCLK clock frequency
1280 * @retval PCLK2 clock frequency (in Hz)
1282 uint32_t RCC_GetPCLK2ClockFreq(uint32_t HCLK_Frequency
)
1284 /* PCLK2 clock frequency */
1285 return __LL_RCC_CALC_PCLK2_FREQ(HCLK_Frequency
, LL_RCC_GetAPB2Prescaler());
1289 * @brief Return PLL clock frequency used for system domain
1290 * @retval PLL clock frequency (in Hz)
1292 uint32_t RCC_PLL_GetFreqDomain_SYS(void)
1294 uint32_t pllinputfreq
= 0U, pllsource
= 0U;
1296 /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN
1297 SYSCLK = PLL_VCO / PLLP
1299 pllsource
= LL_RCC_PLL_GetMainSource();
1303 case LL_RCC_PLLSOURCE_HSI
: /* HSI used as PLL clock source */
1304 pllinputfreq
= HSI_VALUE
;
1307 case LL_RCC_PLLSOURCE_HSE
: /* HSE used as PLL clock source */
1308 pllinputfreq
= HSE_VALUE
;
1312 pllinputfreq
= HSI_VALUE
;
1315 return __LL_RCC_CALC_PLLCLK_FREQ(pllinputfreq
, LL_RCC_PLL_GetDivider(),
1316 LL_RCC_PLL_GetN(), LL_RCC_PLL_GetP());
1320 * @brief Return PLL clock frequency used for 48 MHz domain
1321 * @retval PLL clock frequency (in Hz)
1323 uint32_t RCC_PLL_GetFreqDomain_48M(void)
1325 uint32_t pllinputfreq
= 0U, pllsource
= 0U;
1327 /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM ) * PLLN
1328 48M Domain clock = PLL_VCO / PLLQ
1330 pllsource
= LL_RCC_PLL_GetMainSource();
1334 case LL_RCC_PLLSOURCE_HSI
: /* HSI used as PLL clock source */
1335 pllinputfreq
= HSI_VALUE
;
1338 case LL_RCC_PLLSOURCE_HSE
: /* HSE used as PLL clock source */
1339 pllinputfreq
= HSE_VALUE
;
1343 pllinputfreq
= HSI_VALUE
;
1346 return __LL_RCC_CALC_PLLCLK_48M_FREQ(pllinputfreq
, LL_RCC_PLL_GetDivider(),
1347 LL_RCC_PLL_GetN(), LL_RCC_PLL_GetQ());
1352 * @brief Return PLL clock frequency used for DSI clock
1353 * @retval PLL clock frequency (in Hz)
1355 uint32_t RCC_PLL_GetFreqDomain_DSI(void)
1357 uint32_t pllinputfreq
= 0U, pllsource
= 0U;
1359 /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN
1360 DSICLK = PLL_VCO / PLLR
1362 pllsource
= LL_RCC_PLL_GetMainSource();
1366 case LL_RCC_PLLSOURCE_HSE
: /* HSE used as PLL clock source */
1367 pllinputfreq
= HSE_VALUE
;
1370 case LL_RCC_PLLSOURCE_HSI
: /* HSI used as PLL clock source */
1372 pllinputfreq
= HSI_VALUE
;
1375 return __LL_RCC_CALC_PLLCLK_DSI_FREQ(pllinputfreq
, LL_RCC_PLL_GetDivider(),
1376 LL_RCC_PLL_GetN(), LL_RCC_PLL_GetR());
1381 * @brief Return PLLSAI clock frequency used for SAI1 and SAI2 domains
1382 * @retval PLLSAI clock frequency (in Hz)
1384 uint32_t RCC_PLLSAI_GetFreqDomain_SAI(void)
1386 uint32_t pllinputfreq
= 0U, pllsource
= 0U;
1388 /* PLLSAI_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLSAIN
1389 SAI1 and SAI2 domains clock = (PLLSAI_VCO / PLLSAIQ) / PLLSAIDIVQ
1391 pllsource
= LL_RCC_PLL_GetMainSource();
1395 case LL_RCC_PLLSOURCE_HSI
: /* HSI used as PLLSAI clock source */
1396 pllinputfreq
= HSI_VALUE
;
1399 case LL_RCC_PLLSOURCE_HSE
: /* HSE used as PLLSAI clock source */
1400 pllinputfreq
= HSE_VALUE
;
1404 pllinputfreq
= HSI_VALUE
;
1407 return __LL_RCC_CALC_PLLSAI_SAI_FREQ(pllinputfreq
, LL_RCC_PLL_GetDivider(),
1408 LL_RCC_PLLSAI_GetN(), LL_RCC_PLLSAI_GetQ(), LL_RCC_PLLSAI_GetDIVQ());
1412 * @brief Return PLLSAI clock frequency used for 48Mhz domain
1413 * @retval PLLSAI clock frequency (in Hz)
1415 uint32_t RCC_PLLSAI_GetFreqDomain_48M(void)
1417 uint32_t pllinputfreq
= 0U, pllsource
= 0U;
1419 /* PLLSAI_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLSAIN
1420 48M Domain clock = PLLSAI_VCO / PLLSAIP
1422 pllsource
= LL_RCC_PLL_GetMainSource();
1426 case LL_RCC_PLLSOURCE_HSI
: /* HSI used as PLLSAI clock source */
1427 pllinputfreq
= HSI_VALUE
;
1430 case LL_RCC_PLLSOURCE_HSE
: /* HSE used as PLLSAI clock source */
1431 pllinputfreq
= HSE_VALUE
;
1435 pllinputfreq
= HSI_VALUE
;
1438 return __LL_RCC_CALC_PLLSAI_48M_FREQ(pllinputfreq
, LL_RCC_PLL_GetDivider(),
1439 LL_RCC_PLLSAI_GetN(), LL_RCC_PLLSAI_GetP());
1444 * @brief Return PLLSAI clock frequency used for LTDC domain
1445 * @retval PLLSAI clock frequency (in Hz)
1447 uint32_t RCC_PLLSAI_GetFreqDomain_LTDC(void)
1449 uint32_t pllinputfreq
= 0U, pllsource
= 0U;
1451 /* PLLSAI_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLSAIN
1452 LTDC Domain clock = (PLLSAI_VCO / PLLSAIR) / PLLSAIDIVR
1454 pllsource
= LL_RCC_PLL_GetMainSource();
1458 case LL_RCC_PLLSOURCE_HSI
: /* HSI used as PLLSAI clock source */
1459 pllinputfreq
= HSI_VALUE
;
1462 case LL_RCC_PLLSOURCE_HSE
: /* HSE used as PLLSAI clock source */
1463 pllinputfreq
= HSE_VALUE
;
1467 pllinputfreq
= HSI_VALUE
;
1470 return __LL_RCC_CALC_PLLSAI_LTDC_FREQ(pllinputfreq
, LL_RCC_PLL_GetDivider(),
1471 LL_RCC_PLLSAI_GetN(), LL_RCC_PLLSAI_GetR(), LL_RCC_PLLSAI_GetDIVR());
1476 * @brief Return PLLI2S clock frequency used for SAI1 and SAI2 domains
1477 * @retval PLLI2S clock frequency (in Hz)
1479 uint32_t RCC_PLLI2S_GetFreqDomain_SAI(void)
1481 uint32_t pllinputfreq
= 0U, pllsource
= 0U;
1483 /* PLLI2S_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLI2SN
1484 SAI1 and SAI2 domains clock = (PLLI2S_VCO / PLLI2SQ) / PLLI2SDIVQ
1486 pllsource
= LL_RCC_PLL_GetMainSource();
1490 case LL_RCC_PLLSOURCE_HSI
: /* HSI used as PLLI2S clock source */
1491 pllinputfreq
= HSI_VALUE
;
1494 case LL_RCC_PLLSOURCE_HSE
: /* HSE used as PLLI2S clock source */
1495 pllinputfreq
= HSE_VALUE
;
1499 pllinputfreq
= HSI_VALUE
;
1502 return __LL_RCC_CALC_PLLI2S_SAI_FREQ(pllinputfreq
, LL_RCC_PLL_GetDivider(),
1503 LL_RCC_PLLI2S_GetN(), LL_RCC_PLLI2S_GetQ(), LL_RCC_PLLI2S_GetDIVQ());
1506 #if defined(SPDIFRX)
1508 * @brief Return PLLI2S clock frequency used for SPDIFRX domain
1509 * @retval PLLI2S clock frequency (in Hz)
1511 uint32_t RCC_PLLI2S_GetFreqDomain_SPDIFRX(void)
1513 uint32_t pllinputfreq
= 0U, pllsource
= 0U;
1515 /* PLLI2S_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLI2SN
1516 SPDIFRX Domain clock = PLLI2S_VCO / PLLI2SP
1518 pllsource
= LL_RCC_PLL_GetMainSource();
1522 case LL_RCC_PLLSOURCE_HSI
: /* HSI used as PLLI2S clock source */
1523 pllinputfreq
= HSI_VALUE
;
1526 case LL_RCC_PLLSOURCE_HSE
: /* HSE used as PLLI2S clock source */
1527 pllinputfreq
= HSE_VALUE
;
1531 pllinputfreq
= HSI_VALUE
;
1535 return __LL_RCC_CALC_PLLI2S_SPDIFRX_FREQ(pllinputfreq
, LL_RCC_PLL_GetDivider(),
1536 LL_RCC_PLLI2S_GetN(), LL_RCC_PLLI2S_GetP());
1538 #endif /* SPDIFRX */
1541 * @brief Return PLLI2S clock frequency used for I2S domain
1542 * @retval PLLI2S clock frequency (in Hz)
1544 uint32_t RCC_PLLI2S_GetFreqDomain_I2S(void)
1546 uint32_t pllinputfreq
= 0U, pllsource
= 0U;
1548 /* PLLI2S_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLI2SN
1549 I2S Domain clock = PLLI2S_VCO / PLLI2SR
1551 pllsource
= LL_RCC_PLL_GetMainSource();
1555 case LL_RCC_PLLSOURCE_HSE
: /* HSE used as PLLI2S clock source */
1556 pllinputfreq
= HSE_VALUE
;
1559 case LL_RCC_PLLSOURCE_HSI
: /* HSI used as PLLI2S clock source */
1561 pllinputfreq
= HSI_VALUE
;
1564 return __LL_RCC_CALC_PLLI2S_I2S_FREQ(pllinputfreq
, LL_RCC_PLL_GetDivider(),
1565 LL_RCC_PLLI2S_GetN(), LL_RCC_PLLI2S_GetR());
1576 #endif /* defined(RCC) */
1582 #endif /* USE_FULL_LL_DRIVER */
1584 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/