2 ******************************************************************************
3 * @file stm32f7xx_ll_rcc.c
4 * @author MCD Application Team
7 * @brief RCC LL module driver.
8 ******************************************************************************
11 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
13 * Redistribution and use in source and binary forms, with or without modification,
14 * are permitted provided that the following conditions are met:
15 * 1. Redistributions of source code must retain the above copyright notice,
16 * this list of conditions and the following disclaimer.
17 * 2. Redistributions in binary form must reproduce the above copyright notice,
18 * this list of conditions and the following disclaimer in the documentation
19 * and/or other materials provided with the distribution.
20 * 3. Neither the name of STMicroelectronics nor the names of its contributors
21 * may be used to endorse or promote products derived from this software
22 * without specific prior written permission.
24 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
25 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
26 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
27 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
28 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
29 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
30 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
32 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
33 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
35 ******************************************************************************
37 #if defined(USE_FULL_LL_DRIVER)
39 /* Includes ------------------------------------------------------------------*/
40 #include "stm32f7xx_ll_rcc.h"
41 #ifdef USE_FULL_ASSERT
42 #include "stm32_assert.h"
44 #define assert_param(expr) ((void)0U)
47 /** @addtogroup STM32F7xx_LL_Driver
53 /** @addtogroup RCC_LL
57 /* Private types -------------------------------------------------------------*/
58 /* Private variables ---------------------------------------------------------*/
59 /* Private constants ---------------------------------------------------------*/
60 /* Private macros ------------------------------------------------------------*/
61 /** @addtogroup RCC_LL_Private_Macros
64 #define IS_LL_RCC_USART_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_USART1_CLKSOURCE) \
65 || ((__VALUE__) == LL_RCC_USART2_CLKSOURCE) \
66 || ((__VALUE__) == LL_RCC_USART3_CLKSOURCE) \
67 || ((__VALUE__) == LL_RCC_USART6_CLKSOURCE))
69 #define IS_LL_RCC_UART_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_UART4_CLKSOURCE) \
70 || ((__VALUE__) == LL_RCC_UART5_CLKSOURCE) \
71 || ((__VALUE__) == LL_RCC_UART7_CLKSOURCE) \
72 || ((__VALUE__) == LL_RCC_UART8_CLKSOURCE))
75 #define IS_LL_RCC_I2C_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_I2C1_CLKSOURCE) \
76 || ((__VALUE__) == LL_RCC_I2C2_CLKSOURCE) \
77 || ((__VALUE__) == LL_RCC_I2C3_CLKSOURCE) \
78 || ((__VALUE__) == LL_RCC_I2C4_CLKSOURCE))
80 #define IS_LL_RCC_I2C_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_I2C1_CLKSOURCE) \
81 || ((__VALUE__) == LL_RCC_I2C2_CLKSOURCE) \
82 || ((__VALUE__) == LL_RCC_I2C3_CLKSOURCE))
85 #define IS_LL_RCC_LPTIM_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_LPTIM1_CLKSOURCE))
87 #define IS_LL_RCC_SAI_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_SAI1_CLKSOURCE) \
88 || ((__VALUE__) == LL_RCC_SAI2_CLKSOURCE))
91 #define IS_LL_RCC_SDMMC_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_SDMMC1_CLKSOURCE) \
92 || ((__VALUE__) == LL_RCC_SDMMC2_CLKSOURCE))
94 #define IS_LL_RCC_SDMMC_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_SDMMC1_CLKSOURCE))
97 #define IS_LL_RCC_RNG_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_RNG_CLKSOURCE))
99 #define IS_LL_RCC_USB_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_USB_CLKSOURCE))
101 #if defined(DFSDM1_Channel0)
102 #define IS_LL_RCC_DFSDM_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_DFSDM1_CLKSOURCE))
104 #define IS_LL_RCC_DFSDM_AUDIO_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_DFSDM1_AUDIO_CLKSOURCE))
105 #endif /* DFSDM1_Channel0 */
107 #define IS_LL_RCC_I2S_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_I2S1_CLKSOURCE))
110 #define IS_LL_RCC_CEC_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_CEC_CLKSOURCE))
114 #define IS_LL_RCC_DSI_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_DSI_CLKSOURCE))
118 #define IS_LL_RCC_LTDC_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_LTDC_CLKSOURCE))
122 #define IS_LL_RCC_SPDIFRX_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_SPDIFRX1_CLKSOURCE))
129 /* Private function prototypes -----------------------------------------------*/
130 /** @defgroup RCC_LL_Private_Functions RCC Private functions
133 uint32_t RCC_GetSystemClockFreq(void);
134 uint32_t RCC_GetHCLKClockFreq(uint32_t SYSCLK_Frequency
);
135 uint32_t RCC_GetPCLK1ClockFreq(uint32_t HCLK_Frequency
);
136 uint32_t RCC_GetPCLK2ClockFreq(uint32_t HCLK_Frequency
);
137 uint32_t RCC_PLL_GetFreqDomain_SYS(void);
138 uint32_t RCC_PLL_GetFreqDomain_SAI(void);
139 uint32_t RCC_PLL_GetFreqDomain_48M(void);
141 uint32_t RCC_PLL_GetFreqDomain_DSI(void);
143 uint32_t RCC_PLLSAI_GetFreqDomain_SAI(void);
144 uint32_t RCC_PLLSAI_GetFreqDomain_48M(void);
146 uint32_t RCC_PLLSAI_GetFreqDomain_LTDC(void);
148 uint32_t RCC_PLLI2S_GetFreqDomain_I2S(void);
149 uint32_t RCC_PLLI2S_GetFreqDomain_SAI(void);
151 uint32_t RCC_PLLI2S_GetFreqDomain_SPDIFRX(void);
158 /* Exported functions --------------------------------------------------------*/
159 /** @addtogroup RCC_LL_Exported_Functions
163 /** @addtogroup RCC_LL_EF_Init
168 * @brief Reset the RCC clock configuration to the default reset state.
169 * @note The default reset state of the clock configuration is given below:
170 * - HSI ON and used as system clock source
172 * - AHB, APB1 and APB2 prescaler set to 1.
174 * - All interrupts disabled
175 * @note This function doesn't modify the configuration of the
176 * - Peripheral clocks
177 * - LSI, LSE and RTC clocks
178 * @retval An ErrorStatus enumeration value:
179 * - SUCCESS: RCC registers are de-initialized
180 * - ERROR: not applicable
182 ErrorStatus
LL_RCC_DeInit(void)
184 uint32_t vl_mask
= 0U;
189 /* Reset CFGR register */
190 LL_RCC_WriteReg(CFGR
, 0x00000000U
);
192 vl_mask
= 0xFFFFFFFFU
;
194 /* Reset HSEON, PLLSYSON bits */
195 CLEAR_BIT(vl_mask
, (RCC_CR_HSEON
| RCC_CR_HSEBYP
| RCC_CR_PLLON
| RCC_CR_CSSON
));
197 /* Reset PLLSAION bit */
198 CLEAR_BIT(vl_mask
, RCC_CR_PLLSAION
);
200 /* Reset PLLI2SON bit */
201 CLEAR_BIT(vl_mask
, RCC_CR_PLLI2SON
);
203 /* Write new mask in CR register */
204 LL_RCC_WriteReg(CR
, vl_mask
);
206 /* Set HSITRIM bits to the reset value*/
207 LL_RCC_HSI_SetCalibTrimming(0x10U
);
209 /* Reset PLLCFGR register */
210 LL_RCC_WriteReg(PLLCFGR
, 0x24003010U
);
212 /* Reset PLLI2SCFGR register */
213 LL_RCC_WriteReg(PLLI2SCFGR
, 0x24003000U
);
215 /* Reset PLLSAICFGR register */
216 LL_RCC_WriteReg(PLLSAICFGR
, 0x24003000U
);
218 /* Reset HSEBYP bit */
219 LL_RCC_HSE_DisableBypass();
221 /* Disable all interrupts */
222 LL_RCC_WriteReg(CIR
, 0x00000000U
);
231 /** @addtogroup RCC_LL_EF_Get_Freq
232 * @brief Return the frequencies of different on chip clocks; System, AHB, APB1 and APB2 buses clocks
233 * and different peripheral clocks available on the device.
234 * @note If SYSCLK source is HSI, function returns values based on HSI_VALUE(**)
235 * @note If SYSCLK source is HSE, function returns values based on HSE_VALUE(***)
236 * @note If SYSCLK source is PLL, function returns values based on HSE_VALUE(***)
237 * or HSI_VALUE(**) multiplied/divided by the PLL factors.
238 * @note (**) HSI_VALUE is a constant defined in this file (default value
239 * 16 MHz) but the real value may vary depending on the variations
240 * in voltage and temperature.
241 * @note (***) HSE_VALUE is a constant defined in this file (default value
242 * 25 MHz), user has to ensure that HSE_VALUE is same as the real
243 * frequency of the crystal used. Otherwise, this function may
245 * @note The result of this function could be incorrect when using fractional
246 * value for HSE crystal.
247 * @note This function can be used by the user application to compute the
248 * baud-rate for the communication peripherals or configure other parameters.
253 * @brief Return the frequencies of different on chip clocks; System, AHB, APB1 and APB2 buses clocks
254 * @note Each time SYSCLK, HCLK, PCLK1 and/or PCLK2 clock changes, this function
255 * must be called to update structure fields. Otherwise, any
256 * configuration based on this function will be incorrect.
257 * @param RCC_Clocks pointer to a @ref LL_RCC_ClocksTypeDef structure which will hold the clocks frequencies
260 void LL_RCC_GetSystemClocksFreq(LL_RCC_ClocksTypeDef
*RCC_Clocks
)
262 /* Get SYSCLK frequency */
263 RCC_Clocks
->SYSCLK_Frequency
= RCC_GetSystemClockFreq();
265 /* HCLK clock frequency */
266 RCC_Clocks
->HCLK_Frequency
= RCC_GetHCLKClockFreq(RCC_Clocks
->SYSCLK_Frequency
);
268 /* PCLK1 clock frequency */
269 RCC_Clocks
->PCLK1_Frequency
= RCC_GetPCLK1ClockFreq(RCC_Clocks
->HCLK_Frequency
);
271 /* PCLK2 clock frequency */
272 RCC_Clocks
->PCLK2_Frequency
= RCC_GetPCLK2ClockFreq(RCC_Clocks
->HCLK_Frequency
);
276 * @brief Return USARTx clock frequency
277 * @param USARTxSource This parameter can be one of the following values:
278 * @arg @ref LL_RCC_USART1_CLKSOURCE
279 * @arg @ref LL_RCC_USART2_CLKSOURCE
280 * @arg @ref LL_RCC_USART3_CLKSOURCE
281 * @arg @ref LL_RCC_USART6_CLKSOURCE
282 * @retval USART clock frequency (in Hz)
283 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator (HSI or LSE) is not ready
285 uint32_t LL_RCC_GetUSARTClockFreq(uint32_t USARTxSource
)
287 uint32_t usart_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
289 /* Check parameter */
290 assert_param(IS_LL_RCC_USART_CLKSOURCE(USARTxSource
));
292 if (USARTxSource
== LL_RCC_USART1_CLKSOURCE
)
294 /* USART1CLK clock frequency */
295 switch (LL_RCC_GetUSARTClockSource(USARTxSource
))
297 case LL_RCC_USART1_CLKSOURCE_SYSCLK
: /* USART1 Clock is System Clock */
298 usart_frequency
= RCC_GetSystemClockFreq();
301 case LL_RCC_USART1_CLKSOURCE_HSI
: /* USART1 Clock is HSI Osc. */
302 if (LL_RCC_HSI_IsReady())
304 usart_frequency
= HSI_VALUE
;
308 case LL_RCC_USART1_CLKSOURCE_LSE
: /* USART1 Clock is LSE Osc. */
309 if (LL_RCC_LSE_IsReady())
311 usart_frequency
= LSE_VALUE
;
315 case LL_RCC_USART1_CLKSOURCE_PCLK2
: /* USART1 Clock is PCLK2 */
317 usart_frequency
= RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
321 else if (USARTxSource
== LL_RCC_USART2_CLKSOURCE
)
323 /* USART2CLK clock frequency */
324 switch (LL_RCC_GetUSARTClockSource(USARTxSource
))
326 case LL_RCC_USART2_CLKSOURCE_SYSCLK
: /* USART2 Clock is System Clock */
327 usart_frequency
= RCC_GetSystemClockFreq();
330 case LL_RCC_USART2_CLKSOURCE_HSI
: /* USART2 Clock is HSI Osc. */
331 if (LL_RCC_HSI_IsReady())
333 usart_frequency
= HSI_VALUE
;
337 case LL_RCC_USART2_CLKSOURCE_LSE
: /* USART2 Clock is LSE Osc. */
338 if (LL_RCC_LSE_IsReady())
340 usart_frequency
= LSE_VALUE
;
344 case LL_RCC_USART2_CLKSOURCE_PCLK1
: /* USART2 Clock is PCLK1 */
346 usart_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
350 else if (USARTxSource
== LL_RCC_USART6_CLKSOURCE
)
352 /* USART6CLK clock frequency */
353 switch (LL_RCC_GetUSARTClockSource(USARTxSource
))
355 case LL_RCC_USART6_CLKSOURCE_SYSCLK
: /* USART6 Clock is System Clock */
356 usart_frequency
= RCC_GetSystemClockFreq();
359 case LL_RCC_USART6_CLKSOURCE_HSI
: /* USART6 Clock is HSI Osc. */
360 if (LL_RCC_HSI_IsReady())
362 usart_frequency
= HSI_VALUE
;
366 case LL_RCC_USART6_CLKSOURCE_LSE
: /* USART6 Clock is LSE Osc. */
367 if (LL_RCC_LSE_IsReady())
369 usart_frequency
= LSE_VALUE
;
373 case LL_RCC_USART6_CLKSOURCE_PCLK2
: /* USART6 Clock is PCLK2 */
375 usart_frequency
= RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
381 if (USARTxSource
== LL_RCC_USART3_CLKSOURCE
)
383 /* USART3CLK clock frequency */
384 switch (LL_RCC_GetUSARTClockSource(USARTxSource
))
386 case LL_RCC_USART3_CLKSOURCE_SYSCLK
: /* USART3 Clock is System Clock */
387 usart_frequency
= RCC_GetSystemClockFreq();
390 case LL_RCC_USART3_CLKSOURCE_HSI
: /* USART3 Clock is HSI Osc. */
391 if (LL_RCC_HSI_IsReady())
393 usart_frequency
= HSI_VALUE
;
397 case LL_RCC_USART3_CLKSOURCE_LSE
: /* USART3 Clock is LSE Osc. */
398 if (LL_RCC_LSE_IsReady())
400 usart_frequency
= LSE_VALUE
;
404 case LL_RCC_USART3_CLKSOURCE_PCLK1
: /* USART3 Clock is PCLK1 */
406 usart_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
411 return usart_frequency
;
415 * @brief Return UARTx clock frequency
416 * @param UARTxSource This parameter can be one of the following values:
417 * @arg @ref LL_RCC_UART4_CLKSOURCE
418 * @arg @ref LL_RCC_UART5_CLKSOURCE
419 * @arg @ref LL_RCC_UART7_CLKSOURCE
420 * @arg @ref LL_RCC_UART8_CLKSOURCE
421 * @retval UART clock frequency (in Hz)
422 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator (HSI or LSE) is not ready
424 uint32_t LL_RCC_GetUARTClockFreq(uint32_t UARTxSource
)
426 uint32_t uart_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
428 /* Check parameter */
429 assert_param(IS_LL_RCC_UART_CLKSOURCE(UARTxSource
));
431 if (UARTxSource
== LL_RCC_UART4_CLKSOURCE
)
433 /* UART4CLK clock frequency */
434 switch (LL_RCC_GetUARTClockSource(UARTxSource
))
436 case LL_RCC_UART4_CLKSOURCE_SYSCLK
: /* UART4 Clock is System Clock */
437 uart_frequency
= RCC_GetSystemClockFreq();
440 case LL_RCC_UART4_CLKSOURCE_HSI
: /* UART4 Clock is HSI Osc. */
441 if (LL_RCC_HSI_IsReady())
443 uart_frequency
= HSI_VALUE
;
447 case LL_RCC_UART4_CLKSOURCE_LSE
: /* UART4 Clock is LSE Osc. */
448 if (LL_RCC_LSE_IsReady())
450 uart_frequency
= LSE_VALUE
;
454 case LL_RCC_UART4_CLKSOURCE_PCLK1
: /* UART4 Clock is PCLK1 */
456 uart_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
460 else if (UARTxSource
== LL_RCC_UART5_CLKSOURCE
)
462 /* UART5CLK clock frequency */
463 switch (LL_RCC_GetUARTClockSource(UARTxSource
))
465 case LL_RCC_UART5_CLKSOURCE_SYSCLK
: /* UART5 Clock is System Clock */
466 uart_frequency
= RCC_GetSystemClockFreq();
469 case LL_RCC_UART5_CLKSOURCE_HSI
: /* UART5 Clock is HSI Osc. */
470 if (LL_RCC_HSI_IsReady())
472 uart_frequency
= HSI_VALUE
;
476 case LL_RCC_UART5_CLKSOURCE_LSE
: /* UART5 Clock is LSE Osc. */
477 if (LL_RCC_LSE_IsReady())
479 uart_frequency
= LSE_VALUE
;
483 case LL_RCC_UART5_CLKSOURCE_PCLK1
: /* UART5 Clock is PCLK1 */
485 uart_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
489 else if (UARTxSource
== LL_RCC_UART7_CLKSOURCE
)
491 /* UART7CLK clock frequency */
492 switch (LL_RCC_GetUARTClockSource(UARTxSource
))
494 case LL_RCC_UART7_CLKSOURCE_SYSCLK
: /* UART7 Clock is System Clock */
495 uart_frequency
= RCC_GetSystemClockFreq();
498 case LL_RCC_UART7_CLKSOURCE_HSI
: /* UART7 Clock is HSI Osc. */
499 if (LL_RCC_HSI_IsReady())
501 uart_frequency
= HSI_VALUE
;
505 case LL_RCC_UART7_CLKSOURCE_LSE
: /* UART7 Clock is LSE Osc. */
506 if (LL_RCC_LSE_IsReady())
508 uart_frequency
= LSE_VALUE
;
512 case LL_RCC_UART7_CLKSOURCE_PCLK1
: /* UART7 Clock is PCLK1 */
514 uart_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
520 if (UARTxSource
== LL_RCC_UART8_CLKSOURCE
)
522 /* UART8CLK clock frequency */
523 switch (LL_RCC_GetUARTClockSource(UARTxSource
))
525 case LL_RCC_UART8_CLKSOURCE_SYSCLK
: /* UART8 Clock is System Clock */
526 uart_frequency
= RCC_GetSystemClockFreq();
529 case LL_RCC_UART8_CLKSOURCE_HSI
: /* UART8 Clock is HSI Osc. */
530 if (LL_RCC_HSI_IsReady())
532 uart_frequency
= HSI_VALUE
;
536 case LL_RCC_UART8_CLKSOURCE_LSE
: /* UART8 Clock is LSE Osc. */
537 if (LL_RCC_LSE_IsReady())
539 uart_frequency
= LSE_VALUE
;
543 case LL_RCC_UART8_CLKSOURCE_PCLK1
: /* UART8 Clock is PCLK1 */
545 uart_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
550 return uart_frequency
;
554 * @brief Return I2Cx clock frequency
555 * @param I2CxSource This parameter can be one of the following values:
556 * @arg @ref LL_RCC_I2C1_CLKSOURCE
557 * @arg @ref LL_RCC_I2C2_CLKSOURCE
558 * @arg @ref LL_RCC_I2C3_CLKSOURCE
559 * @arg @ref LL_RCC_I2C4_CLKSOURCE (*)
561 * (*) value not defined in all devices.
562 * @retval I2C clock frequency (in Hz)
563 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that HSI oscillator is not ready
565 uint32_t LL_RCC_GetI2CClockFreq(uint32_t I2CxSource
)
567 uint32_t i2c_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
569 /* Check parameter */
570 assert_param(IS_LL_RCC_I2C_CLKSOURCE(I2CxSource
));
572 if (I2CxSource
== LL_RCC_I2C1_CLKSOURCE
)
574 /* I2C1 CLK clock frequency */
575 switch (LL_RCC_GetI2CClockSource(I2CxSource
))
577 case LL_RCC_I2C1_CLKSOURCE_SYSCLK
: /* I2C1 Clock is System Clock */
578 i2c_frequency
= RCC_GetSystemClockFreq();
581 case LL_RCC_I2C1_CLKSOURCE_HSI
: /* I2C1 Clock is HSI Osc. */
582 if (LL_RCC_HSI_IsReady())
584 i2c_frequency
= HSI_VALUE
;
588 case LL_RCC_I2C1_CLKSOURCE_PCLK1
: /* I2C1 Clock is PCLK1 */
590 i2c_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
594 else if (I2CxSource
== LL_RCC_I2C2_CLKSOURCE
)
596 /* I2C2 CLK clock frequency */
597 switch (LL_RCC_GetI2CClockSource(I2CxSource
))
599 case LL_RCC_I2C2_CLKSOURCE_SYSCLK
: /* I2C2 Clock is System Clock */
600 i2c_frequency
= RCC_GetSystemClockFreq();
603 case LL_RCC_I2C2_CLKSOURCE_HSI
: /* I2C2 Clock is HSI Osc. */
604 if (LL_RCC_HSI_IsReady())
606 i2c_frequency
= HSI_VALUE
;
610 case LL_RCC_I2C2_CLKSOURCE_PCLK1
: /* I2C2 Clock is PCLK1 */
612 i2c_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
616 else if (I2CxSource
== LL_RCC_I2C3_CLKSOURCE
)
618 /* I2C3 CLK clock frequency */
619 switch (LL_RCC_GetI2CClockSource(I2CxSource
))
621 case LL_RCC_I2C3_CLKSOURCE_SYSCLK
: /* I2C3 Clock is System Clock */
622 i2c_frequency
= RCC_GetSystemClockFreq();
625 case LL_RCC_I2C3_CLKSOURCE_HSI
: /* I2C3 Clock is HSI Osc. */
626 if (LL_RCC_HSI_IsReady())
628 i2c_frequency
= HSI_VALUE
;
632 case LL_RCC_I2C3_CLKSOURCE_PCLK1
: /* I2C3 Clock is PCLK1 */
634 i2c_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
641 if (I2CxSource
== LL_RCC_I2C4_CLKSOURCE
)
643 /* I2C4 CLK clock frequency */
644 switch (LL_RCC_GetI2CClockSource(I2CxSource
))
646 case LL_RCC_I2C4_CLKSOURCE_SYSCLK
: /* I2C4 Clock is System Clock */
647 i2c_frequency
= RCC_GetSystemClockFreq();
650 case LL_RCC_I2C4_CLKSOURCE_HSI
: /* I2C4 Clock is HSI Osc. */
651 if (LL_RCC_HSI_IsReady())
653 i2c_frequency
= HSI_VALUE
;
657 case LL_RCC_I2C4_CLKSOURCE_PCLK1
: /* I2C4 Clock is PCLK1 */
659 i2c_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
666 return i2c_frequency
;
670 * @brief Return I2Sx clock frequency
671 * @param I2SxSource This parameter can be one of the following values:
672 * @arg @ref LL_RCC_I2S1_CLKSOURCE
673 * @retval I2S clock frequency (in Hz)
674 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that PLLI2S oscillator is not ready
676 uint32_t LL_RCC_GetI2SClockFreq(uint32_t I2SxSource
)
678 uint32_t i2s_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
680 /* Check parameter */
681 assert_param(IS_LL_RCC_I2S_CLKSOURCE(I2SxSource
));
683 if (I2SxSource
== LL_RCC_I2S1_CLKSOURCE
)
685 /* I2S1 CLK clock frequency */
686 switch (LL_RCC_GetI2SClockSource(I2SxSource
))
688 case LL_RCC_I2S1_CLKSOURCE_PLLI2S
: /* I2S1 Clock is PLLI2S */
689 if (LL_RCC_PLLI2S_IsReady())
691 i2s_frequency
= RCC_PLLI2S_GetFreqDomain_I2S();
695 case LL_RCC_I2S1_CLKSOURCE_PIN
: /* I2S1 Clock is External clock */
697 i2s_frequency
= EXTERNAL_CLOCK_VALUE
;
702 return i2s_frequency
;
706 * @brief Return LPTIMx clock frequency
707 * @param LPTIMxSource This parameter can be one of the following values:
708 * @arg @ref LL_RCC_LPTIM1_CLKSOURCE
709 * @retval LPTIM clock frequency (in Hz)
710 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator (HSI, LSI or LSE) is not ready
712 uint32_t LL_RCC_GetLPTIMClockFreq(uint32_t LPTIMxSource
)
714 uint32_t lptim_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
716 /* Check parameter */
717 assert_param(IS_LL_RCC_LPTIM_CLKSOURCE(LPTIMxSource
));
719 if (LPTIMxSource
== LL_RCC_LPTIM1_CLKSOURCE
)
721 /* LPTIM1CLK clock frequency */
722 switch (LL_RCC_GetLPTIMClockSource(LPTIMxSource
))
724 case LL_RCC_LPTIM1_CLKSOURCE_LSI
: /* LPTIM1 Clock is LSI Osc. */
725 if (LL_RCC_LSI_IsReady())
727 lptim_frequency
= LSI_VALUE
;
731 case LL_RCC_LPTIM1_CLKSOURCE_HSI
: /* LPTIM1 Clock is HSI Osc. */
732 if (LL_RCC_HSI_IsReady())
734 lptim_frequency
= HSI_VALUE
;
738 case LL_RCC_LPTIM1_CLKSOURCE_LSE
: /* LPTIM1 Clock is LSE Osc. */
739 if (LL_RCC_LSE_IsReady())
741 lptim_frequency
= LSE_VALUE
;
745 case LL_RCC_LPTIM1_CLKSOURCE_PCLK1
: /* LPTIM1 Clock is PCLK1 */
747 lptim_frequency
= RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
752 return lptim_frequency
;
756 * @brief Return SAIx clock frequency
757 * @param SAIxSource This parameter can be one of the following values:
758 * @arg @ref LL_RCC_SAI1_CLKSOURCE
759 * @arg @ref LL_RCC_SAI2_CLKSOURCE
760 * @retval SAI clock frequency (in Hz)
761 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that PLL is not ready
762 * - @ref LL_RCC_PERIPH_FREQUENCY_NA indicates that external clock is used
764 uint32_t LL_RCC_GetSAIClockFreq(uint32_t SAIxSource
)
766 uint32_t sai_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
768 /* Check parameter */
769 assert_param(IS_LL_RCC_SAI_CLKSOURCE(SAIxSource
));
771 if (SAIxSource
== LL_RCC_SAI1_CLKSOURCE
)
773 /* SAI1CLK clock frequency */
774 switch (LL_RCC_GetSAIClockSource(SAIxSource
))
776 case LL_RCC_SAI1_CLKSOURCE_PLLSAI
: /* PLLSAI clock used as SAI1 clock source */
777 if (LL_RCC_PLLSAI_IsReady())
779 sai_frequency
= RCC_PLLSAI_GetFreqDomain_SAI();
783 case LL_RCC_SAI1_CLKSOURCE_PLLI2S
: /* PLLI2S clock used as SAI1 clock source */
784 if (LL_RCC_PLLI2S_IsReady())
786 sai_frequency
= RCC_PLLI2S_GetFreqDomain_SAI();
790 #if defined(RCC_SAI1SEL_PLLSRC_SUPPORT)
791 case LL_RCC_SAI1_CLKSOURCE_PLLSRC
:
792 switch (LL_RCC_PLL_GetMainSource())
794 case LL_RCC_PLLSOURCE_HSE
: /* HSE clock used as SAI1 clock source */
795 if (LL_RCC_HSE_IsReady())
797 sai_frequency
= HSE_VALUE
;
801 case LL_RCC_PLLSOURCE_HSI
: /* HSI clock used as SAI1 clock source */
803 if (LL_RCC_HSI_IsReady())
805 sai_frequency
= HSI_VALUE
;
810 #endif /* RCC_SAI1SEL_PLLSRC_SUPPORT */
811 case LL_RCC_SAI1_CLKSOURCE_PIN
: /* External input clock used as SAI1 clock source */
813 sai_frequency
= LL_RCC_PERIPH_FREQUENCY_NA
;
819 if (SAIxSource
== LL_RCC_SAI2_CLKSOURCE
)
821 /* SAI2CLK clock frequency */
822 switch (LL_RCC_GetSAIClockSource(SAIxSource
))
824 case LL_RCC_SAI2_CLKSOURCE_PLLSAI
: /* PLLSAI clock used as SAI2 clock source */
825 if (LL_RCC_PLLSAI_IsReady())
827 sai_frequency
= RCC_PLLSAI_GetFreqDomain_SAI();
831 case LL_RCC_SAI2_CLKSOURCE_PLLI2S
: /* PLLI2S clock used as SAI2 clock source */
832 if (LL_RCC_PLLI2S_IsReady())
834 sai_frequency
= RCC_PLLI2S_GetFreqDomain_SAI();
838 #if defined(RCC_SAI2SEL_PLLSRC_SUPPORT)
839 case LL_RCC_SAI2_CLKSOURCE_PLLSRC
:
840 switch (LL_RCC_PLL_GetMainSource())
842 case LL_RCC_PLLSOURCE_HSE
: /* HSE clock used as SAI2 clock source */
843 if (LL_RCC_HSE_IsReady())
845 sai_frequency
= HSE_VALUE
;
849 case LL_RCC_PLLSOURCE_HSI
: /* HSI clock used as SAI2 clock source */
851 if (LL_RCC_HSI_IsReady())
853 sai_frequency
= HSI_VALUE
;
858 #endif /* RCC_SAI2SEL_PLLSRC_SUPPORT */
859 case LL_RCC_SAI2_CLKSOURCE_PIN
: /* External input clock used as SAI2 clock source */
861 sai_frequency
= LL_RCC_PERIPH_FREQUENCY_NA
;
867 return sai_frequency
;
871 * @brief Return SDMMCx clock frequency
872 * @param SDMMCxSource This parameter can be one of the following values:
873 * @arg @ref LL_RCC_SDMMC1_CLKSOURCE
874 * @arg @ref LL_RCC_SDMMC2_CLKSOURCE (*)
876 * (*) value not defined in all devices.
877 * @retval SDMMC clock frequency (in Hz)
878 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator PLL is not ready
880 uint32_t LL_RCC_GetSDMMCClockFreq(uint32_t SDMMCxSource
)
882 uint32_t sdmmc_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
884 /* Check parameter */
885 assert_param(IS_LL_RCC_SDMMC_CLKSOURCE(SDMMCxSource
));
887 if (SDMMCxSource
== LL_RCC_SDMMC1_CLKSOURCE
)
889 /* SDMMC1CLK clock frequency */
890 switch (LL_RCC_GetSDMMCClockSource(SDMMCxSource
))
892 case LL_RCC_SDMMC1_CLKSOURCE_PLL48CLK
: /* PLL48 clock used as SDMMC1 clock source */
893 switch (LL_RCC_GetCK48MClockSource(LL_RCC_CK48M_CLKSOURCE
))
895 case LL_RCC_CK48M_CLKSOURCE_PLL
: /* PLL clock used as 48Mhz domain clock */
896 if (LL_RCC_PLL_IsReady())
898 sdmmc_frequency
= RCC_PLL_GetFreqDomain_48M();
902 case LL_RCC_CK48M_CLKSOURCE_PLLSAI
: /* PLLSAI clock used as 48Mhz domain clock */
904 if (LL_RCC_PLLSAI_IsReady())
906 sdmmc_frequency
= RCC_PLLSAI_GetFreqDomain_48M();
912 case LL_RCC_SDMMC1_CLKSOURCE_SYSCLK
: /* PLL clock used as SDMMC1 clock source */
914 sdmmc_frequency
= RCC_GetSystemClockFreq();
921 /* SDMMC2CLK clock frequency */
922 switch (LL_RCC_GetSDMMCClockSource(SDMMCxSource
))
924 case LL_RCC_SDMMC2_CLKSOURCE_PLL48CLK
: /* PLL48 clock used as SDMMC2 clock source */
925 switch (LL_RCC_GetCK48MClockSource(LL_RCC_CK48M_CLKSOURCE
))
927 case LL_RCC_CK48M_CLKSOURCE_PLL
: /* PLL clock used as 48Mhz domain clock */
928 if (LL_RCC_PLL_IsReady())
930 sdmmc_frequency
= RCC_PLL_GetFreqDomain_48M();
934 case LL_RCC_CK48M_CLKSOURCE_PLLSAI
: /* PLLSAI clock used as 48Mhz domain clock */
936 if (LL_RCC_PLLSAI_IsReady())
938 sdmmc_frequency
= RCC_PLLSAI_GetFreqDomain_48M();
944 case LL_RCC_SDMMC2_CLKSOURCE_SYSCLK
: /* PLL clock used as SDMMC2 clock source */
946 sdmmc_frequency
= RCC_GetSystemClockFreq();
952 return sdmmc_frequency
;
956 * @brief Return RNGx clock frequency
957 * @param RNGxSource This parameter can be one of the following values:
958 * @arg @ref LL_RCC_RNG_CLKSOURCE
959 * @retval RNG clock frequency (in Hz)
960 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready
962 uint32_t LL_RCC_GetRNGClockFreq(uint32_t RNGxSource
)
964 uint32_t rng_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
966 /* Check parameter */
967 assert_param(IS_LL_RCC_RNG_CLKSOURCE(RNGxSource
));
969 /* RNGCLK clock frequency */
970 switch (LL_RCC_GetRNGClockSource(RNGxSource
))
972 case LL_RCC_RNG_CLKSOURCE_PLL
: /* PLL clock used as RNG clock source */
973 if (LL_RCC_PLL_IsReady())
975 rng_frequency
= RCC_PLL_GetFreqDomain_48M();
979 case LL_RCC_RNG_CLKSOURCE_PLLSAI
: /* PLLSAI clock used as RNG clock source */
981 if (LL_RCC_PLLSAI_IsReady())
983 rng_frequency
= RCC_PLLSAI_GetFreqDomain_48M();
988 return rng_frequency
;
993 * @brief Return CEC clock frequency
994 * @param CECxSource This parameter can be one of the following values:
995 * @arg @ref LL_RCC_CEC_CLKSOURCE
996 * @retval CEC clock frequency (in Hz)
997 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator (HSI or LSE) is not ready
999 uint32_t LL_RCC_GetCECClockFreq(uint32_t CECxSource
)
1001 uint32_t cec_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
1003 /* Check parameter */
1004 assert_param(IS_LL_RCC_CEC_CLKSOURCE(CECxSource
));
1006 /* CECCLK clock frequency */
1007 switch (LL_RCC_GetCECClockSource(CECxSource
))
1009 case LL_RCC_CEC_CLKSOURCE_LSE
: /* CEC Clock is LSE Osc. */
1010 if (LL_RCC_LSE_IsReady())
1012 cec_frequency
= LSE_VALUE
;
1016 case LL_RCC_CEC_CLKSOURCE_HSI_DIV488
: /* CEC Clock is HSI Osc. */
1018 if (LL_RCC_HSI_IsReady())
1020 cec_frequency
= HSI_VALUE
/488U;
1025 return cec_frequency
;
1030 * @brief Return USBx clock frequency
1031 * @param USBxSource This parameter can be one of the following values:
1032 * @arg @ref LL_RCC_USB_CLKSOURCE
1033 * @retval USB clock frequency (in Hz)
1035 uint32_t LL_RCC_GetUSBClockFreq(uint32_t USBxSource
)
1037 uint32_t usb_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
1039 /* Check parameter */
1040 assert_param(IS_LL_RCC_USB_CLKSOURCE(USBxSource
));
1042 /* USBCLK clock frequency */
1043 switch (LL_RCC_GetUSBClockSource(USBxSource
))
1045 case LL_RCC_USB_CLKSOURCE_PLL
: /* PLL clock used as USB clock source */
1046 if (LL_RCC_PLL_IsReady())
1048 usb_frequency
= RCC_PLL_GetFreqDomain_48M();
1052 case LL_RCC_USB_CLKSOURCE_PLLSAI
: /* PLLSAI clock used as USB clock source */
1054 if (LL_RCC_PLLSAI_IsReady())
1056 usb_frequency
= RCC_PLLSAI_GetFreqDomain_48M();
1061 return usb_frequency
;
1064 #if defined(DFSDM1_Channel0)
1066 * @brief Return DFSDMx clock frequency
1067 * @param DFSDMxSource This parameter can be one of the following values:
1068 * @arg @ref LL_RCC_DFSDM1_CLKSOURCE
1069 * @retval DFSDM clock frequency (in Hz)
1071 uint32_t LL_RCC_GetDFSDMClockFreq(uint32_t DFSDMxSource
)
1073 uint32_t dfsdm_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
1075 /* Check parameter */
1076 assert_param(IS_LL_RCC_DFSDM_CLKSOURCE(DFSDMxSource
));
1078 /* DFSDM1CLK clock frequency */
1079 switch (LL_RCC_GetDFSDMClockSource(DFSDMxSource
))
1081 case LL_RCC_DFSDM1_CLKSOURCE_SYSCLK
: /* DFSDM1 Clock is SYSCLK */
1082 dfsdm_frequency
= RCC_GetSystemClockFreq();
1085 case LL_RCC_DFSDM1_CLKSOURCE_PCLK2
: /* DFSDM1 Clock is PCLK2 */
1087 dfsdm_frequency
= RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
1091 return dfsdm_frequency
;
1095 * @brief Return DFSDMx Audio clock frequency
1096 * @param DFSDMxSource This parameter can be one of the following values:
1097 * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE
1098 * @retval DFSDM clock frequency (in Hz)
1099 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready
1101 uint32_t LL_RCC_GetDFSDMAudioClockFreq(uint32_t DFSDMxSource
)
1103 uint32_t dfsdm_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
1105 /* Check parameter */
1106 assert_param(IS_LL_RCC_DFSDM_AUDIO_CLKSOURCE(DFSDMxSource
));
1108 /* DFSDM1CLK clock frequency */
1109 switch (LL_RCC_GetDFSDMAudioClockSource(DFSDMxSource
))
1111 case LL_RCC_DFSDM1_AUDIO_CLKSOURCE_SAI1
: /* SAI1 clock used as DFSDM1 audio clock */
1112 dfsdm_frequency
= LL_RCC_GetSAIClockFreq(LL_RCC_SAI1_CLKSOURCE
);
1115 case LL_RCC_DFSDM1_AUDIO_CLKSOURCE_SAI2
: /* SAI2 clock used as DFSDM1 audio clock */
1117 dfsdm_frequency
= LL_RCC_GetSAIClockFreq(LL_RCC_SAI2_CLKSOURCE
);
1121 return dfsdm_frequency
;
1123 #endif /* DFSDM1_Channel0 */
1127 * @brief Return DSI clock frequency
1128 * @param DSIxSource This parameter can be one of the following values:
1129 * @arg @ref LL_RCC_DSI_CLKSOURCE
1130 * @retval DSI clock frequency (in Hz)
1131 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready
1132 * - @ref LL_RCC_PERIPH_FREQUENCY_NA indicates that external clock is used
1134 uint32_t LL_RCC_GetDSIClockFreq(uint32_t DSIxSource
)
1136 uint32_t dsi_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
1138 /* Check parameter */
1139 assert_param(IS_LL_RCC_DSI_CLKSOURCE(DSIxSource
));
1141 /* DSICLK clock frequency */
1142 switch (LL_RCC_GetDSIClockSource(DSIxSource
))
1144 case LL_RCC_DSI_CLKSOURCE_PLL
: /* DSI Clock is PLL Osc. */
1145 if (LL_RCC_PLL_IsReady())
1147 dsi_frequency
= RCC_PLL_GetFreqDomain_DSI();
1151 case LL_RCC_DSI_CLKSOURCE_PHY
: /* DSI Clock is DSI physical clock. */
1153 dsi_frequency
= LL_RCC_PERIPH_FREQUENCY_NA
;
1157 return dsi_frequency
;
1163 * @brief Return LTDC clock frequency
1164 * @param LTDCxSource This parameter can be one of the following values:
1165 * @arg @ref LL_RCC_LTDC_CLKSOURCE
1166 * @retval LTDC clock frequency (in Hz)
1167 * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator PLLSAI is not ready
1169 uint32_t LL_RCC_GetLTDCClockFreq(uint32_t 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 (void)SPDIFRXxSource
;
1197 uint32_t spdifrx_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
1199 /* Check parameter */
1200 assert_param(IS_LL_RCC_SPDIFRX_CLKSOURCE(SPDIFRXxSource
));
1202 if (LL_RCC_PLLI2S_IsReady())
1204 spdifrx_frequency
= RCC_PLLI2S_GetFreqDomain_SPDIFRX();
1207 return spdifrx_frequency
;
1209 #endif /* SPDIFRX */
1219 /** @addtogroup RCC_LL_Private_Functions
1224 * @brief Return SYSTEM clock frequency
1225 * @retval SYSTEM clock frequency (in Hz)
1227 uint32_t RCC_GetSystemClockFreq(void)
1229 uint32_t frequency
= 0U;
1231 /* Get SYSCLK source -------------------------------------------------------*/
1232 switch (LL_RCC_GetSysClkSource())
1234 case LL_RCC_SYS_CLKSOURCE_STATUS_HSI
: /* HSI used as system clock source */
1235 frequency
= HSI_VALUE
;
1238 case LL_RCC_SYS_CLKSOURCE_STATUS_HSE
: /* HSE used as system clock source */
1239 frequency
= HSE_VALUE
;
1242 case LL_RCC_SYS_CLKSOURCE_STATUS_PLL
: /* PLL used as system clock source */
1243 frequency
= RCC_PLL_GetFreqDomain_SYS();
1247 frequency
= HSI_VALUE
;
1255 * @brief Return HCLK clock frequency
1256 * @param SYSCLK_Frequency SYSCLK clock frequency
1257 * @retval HCLK clock frequency (in Hz)
1259 uint32_t RCC_GetHCLKClockFreq(uint32_t SYSCLK_Frequency
)
1261 /* HCLK clock frequency */
1262 return __LL_RCC_CALC_HCLK_FREQ(SYSCLK_Frequency
, LL_RCC_GetAHBPrescaler());
1266 * @brief Return PCLK1 clock frequency
1267 * @param HCLK_Frequency HCLK clock frequency
1268 * @retval PCLK1 clock frequency (in Hz)
1270 uint32_t RCC_GetPCLK1ClockFreq(uint32_t HCLK_Frequency
)
1272 /* PCLK1 clock frequency */
1273 return __LL_RCC_CALC_PCLK1_FREQ(HCLK_Frequency
, LL_RCC_GetAPB1Prescaler());
1277 * @brief Return PCLK2 clock frequency
1278 * @param HCLK_Frequency HCLK clock frequency
1279 * @retval PCLK2 clock frequency (in Hz)
1281 uint32_t RCC_GetPCLK2ClockFreq(uint32_t HCLK_Frequency
)
1283 /* PCLK2 clock frequency */
1284 return __LL_RCC_CALC_PCLK2_FREQ(HCLK_Frequency
, LL_RCC_GetAPB2Prescaler());
1288 * @brief Return PLL clock frequency used for system domain
1289 * @retval PLL clock frequency (in Hz)
1291 uint32_t RCC_PLL_GetFreqDomain_SYS(void)
1293 uint32_t pllinputfreq
= 0U, pllsource
= 0U;
1295 /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN
1296 SYSCLK = PLL_VCO / PLLP
1298 pllsource
= LL_RCC_PLL_GetMainSource();
1302 case LL_RCC_PLLSOURCE_HSI
: /* HSI used as PLL clock source */
1303 pllinputfreq
= HSI_VALUE
;
1306 case LL_RCC_PLLSOURCE_HSE
: /* HSE used as PLL clock source */
1307 pllinputfreq
= HSE_VALUE
;
1311 pllinputfreq
= HSI_VALUE
;
1314 return __LL_RCC_CALC_PLLCLK_FREQ(pllinputfreq
, LL_RCC_PLL_GetDivider(),
1315 LL_RCC_PLL_GetN(), LL_RCC_PLL_GetP());
1319 * @brief Return PLL clock frequency used for 48 MHz domain
1320 * @retval PLL clock frequency (in Hz)
1322 uint32_t RCC_PLL_GetFreqDomain_48M(void)
1324 uint32_t pllinputfreq
= 0U, pllsource
= 0U;
1326 /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM ) * PLLN
1327 48M Domain clock = PLL_VCO / PLLQ
1329 pllsource
= LL_RCC_PLL_GetMainSource();
1333 case LL_RCC_PLLSOURCE_HSI
: /* HSI used as PLL clock source */
1334 pllinputfreq
= HSI_VALUE
;
1337 case LL_RCC_PLLSOURCE_HSE
: /* HSE used as PLL clock source */
1338 pllinputfreq
= HSE_VALUE
;
1342 pllinputfreq
= HSI_VALUE
;
1345 return __LL_RCC_CALC_PLLCLK_48M_FREQ(pllinputfreq
, LL_RCC_PLL_GetDivider(),
1346 LL_RCC_PLL_GetN(), LL_RCC_PLL_GetQ());
1351 * @brief Return PLL clock frequency used for DSI clock
1352 * @retval PLL clock frequency (in Hz)
1354 uint32_t RCC_PLL_GetFreqDomain_DSI(void)
1356 uint32_t pllinputfreq
= 0U, pllsource
= 0U;
1358 /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN
1359 DSICLK = PLL_VCO / PLLR
1361 pllsource
= LL_RCC_PLL_GetMainSource();
1365 case LL_RCC_PLLSOURCE_HSE
: /* HSE used as PLL clock source */
1366 pllinputfreq
= HSE_VALUE
;
1369 case LL_RCC_PLLSOURCE_HSI
: /* HSI used as PLL clock source */
1371 pllinputfreq
= HSI_VALUE
;
1374 return __LL_RCC_CALC_PLLCLK_DSI_FREQ(pllinputfreq
, LL_RCC_PLL_GetDivider(),
1375 LL_RCC_PLL_GetN(), LL_RCC_PLL_GetR());
1380 * @brief Return PLLSAI clock frequency used for SAI1 and SAI2 domains
1381 * @retval PLLSAI clock frequency (in Hz)
1383 uint32_t RCC_PLLSAI_GetFreqDomain_SAI(void)
1385 uint32_t pllinputfreq
= 0U, pllsource
= 0U;
1387 /* PLLSAI_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLSAIN
1388 SAI1 and SAI2 domains clock = (PLLSAI_VCO / PLLSAIQ) / PLLSAIDIVQ
1390 pllsource
= LL_RCC_PLL_GetMainSource();
1394 case LL_RCC_PLLSOURCE_HSI
: /* HSI used as PLLSAI clock source */
1395 pllinputfreq
= HSI_VALUE
;
1398 case LL_RCC_PLLSOURCE_HSE
: /* HSE used as PLLSAI clock source */
1399 pllinputfreq
= HSE_VALUE
;
1403 pllinputfreq
= HSI_VALUE
;
1406 return __LL_RCC_CALC_PLLSAI_SAI_FREQ(pllinputfreq
, LL_RCC_PLL_GetDivider(),
1407 LL_RCC_PLLSAI_GetN(), LL_RCC_PLLSAI_GetQ(), LL_RCC_PLLSAI_GetDIVQ());
1411 * @brief Return PLLSAI clock frequency used for 48Mhz domain
1412 * @retval PLLSAI clock frequency (in Hz)
1414 uint32_t RCC_PLLSAI_GetFreqDomain_48M(void)
1416 uint32_t pllinputfreq
= 0U, pllsource
= 0U;
1418 /* PLLSAI_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLSAIN
1419 48M Domain clock = PLLSAI_VCO / PLLSAIP
1421 pllsource
= LL_RCC_PLL_GetMainSource();
1425 case LL_RCC_PLLSOURCE_HSI
: /* HSI used as PLLSAI clock source */
1426 pllinputfreq
= HSI_VALUE
;
1429 case LL_RCC_PLLSOURCE_HSE
: /* HSE used as PLLSAI clock source */
1430 pllinputfreq
= HSE_VALUE
;
1434 pllinputfreq
= HSI_VALUE
;
1437 return __LL_RCC_CALC_PLLSAI_48M_FREQ(pllinputfreq
, LL_RCC_PLL_GetDivider(),
1438 LL_RCC_PLLSAI_GetN(), LL_RCC_PLLSAI_GetP());
1443 * @brief Return PLLSAI clock frequency used for LTDC domain
1444 * @retval PLLSAI clock frequency (in Hz)
1446 uint32_t RCC_PLLSAI_GetFreqDomain_LTDC(void)
1448 uint32_t pllinputfreq
= 0U, pllsource
= 0U;
1450 /* PLLSAI_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLSAIN
1451 LTDC Domain clock = (PLLSAI_VCO / PLLSAIR) / PLLSAIDIVR
1453 pllsource
= LL_RCC_PLL_GetMainSource();
1457 case LL_RCC_PLLSOURCE_HSI
: /* HSI used as PLLSAI clock source */
1458 pllinputfreq
= HSI_VALUE
;
1461 case LL_RCC_PLLSOURCE_HSE
: /* HSE used as PLLSAI clock source */
1462 pllinputfreq
= HSE_VALUE
;
1466 pllinputfreq
= HSI_VALUE
;
1469 return __LL_RCC_CALC_PLLSAI_LTDC_FREQ(pllinputfreq
, LL_RCC_PLL_GetDivider(),
1470 LL_RCC_PLLSAI_GetN(), LL_RCC_PLLSAI_GetR(), LL_RCC_PLLSAI_GetDIVR());
1475 * @brief Return PLLI2S clock frequency used for SAI1 and SAI2 domains
1476 * @retval PLLI2S clock frequency (in Hz)
1478 uint32_t RCC_PLLI2S_GetFreqDomain_SAI(void)
1480 uint32_t pllinputfreq
= 0U, pllsource
= 0U;
1482 /* PLLI2S_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLI2SN
1483 SAI1 and SAI2 domains clock = (PLLI2S_VCO / PLLI2SQ) / PLLI2SDIVQ
1485 pllsource
= LL_RCC_PLL_GetMainSource();
1489 case LL_RCC_PLLSOURCE_HSI
: /* HSI used as PLLI2S clock source */
1490 pllinputfreq
= HSI_VALUE
;
1493 case LL_RCC_PLLSOURCE_HSE
: /* HSE used as PLLI2S clock source */
1494 pllinputfreq
= HSE_VALUE
;
1498 pllinputfreq
= HSI_VALUE
;
1501 return __LL_RCC_CALC_PLLI2S_SAI_FREQ(pllinputfreq
, LL_RCC_PLL_GetDivider(),
1502 LL_RCC_PLLI2S_GetN(), LL_RCC_PLLI2S_GetQ(), LL_RCC_PLLI2S_GetDIVQ());
1505 #if defined(SPDIFRX)
1507 * @brief Return PLLI2S clock frequency used for SPDIFRX domain
1508 * @retval PLLI2S clock frequency (in Hz)
1510 uint32_t RCC_PLLI2S_GetFreqDomain_SPDIFRX(void)
1512 uint32_t pllinputfreq
= 0U, pllsource
= 0U;
1514 /* PLLI2S_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLI2SN
1515 SPDIFRX Domain clock = PLLI2S_VCO / PLLI2SP
1517 pllsource
= LL_RCC_PLL_GetMainSource();
1521 case LL_RCC_PLLSOURCE_HSI
: /* HSI used as PLLI2S clock source */
1522 pllinputfreq
= HSI_VALUE
;
1525 case LL_RCC_PLLSOURCE_HSE
: /* HSE used as PLLI2S clock source */
1526 pllinputfreq
= HSE_VALUE
;
1530 pllinputfreq
= HSI_VALUE
;
1534 return __LL_RCC_CALC_PLLI2S_SPDIFRX_FREQ(pllinputfreq
, LL_RCC_PLL_GetDivider(),
1535 LL_RCC_PLLI2S_GetN(), LL_RCC_PLLI2S_GetP());
1537 #endif /* SPDIFRX */
1540 * @brief Return PLLI2S clock frequency used for I2S domain
1541 * @retval PLLI2S clock frequency (in Hz)
1543 uint32_t RCC_PLLI2S_GetFreqDomain_I2S(void)
1545 uint32_t pllinputfreq
= 0U, pllsource
= 0U;
1547 /* PLLI2S_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLI2SN
1548 I2S Domain clock = PLLI2S_VCO / PLLI2SR
1550 pllsource
= LL_RCC_PLL_GetMainSource();
1554 case LL_RCC_PLLSOURCE_HSE
: /* HSE used as PLLI2S clock source */
1555 pllinputfreq
= HSE_VALUE
;
1558 case LL_RCC_PLLSOURCE_HSI
: /* HSI used as PLLI2S clock source */
1560 pllinputfreq
= HSI_VALUE
;
1563 return __LL_RCC_CALC_PLLI2S_I2S_FREQ(pllinputfreq
, LL_RCC_PLL_GetDivider(),
1564 LL_RCC_PLLI2S_GetN(), LL_RCC_PLLI2S_GetR());
1575 #endif /* defined(RCC) */
1581 #endif /* USE_FULL_LL_DRIVER */
1583 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/