F1 and F3 HAL / LL libraries
[betaflight.git] / lib / main / STM32F3 / Drivers / STM32F3xx_HAL_Driver / Src / stm32f3xx_ll_rcc.c
blobec5613f0f570bf55e359f84cd2a4f3fb28093dc1
1 /**
2 ******************************************************************************
3 * @file stm32f3xx_ll_rcc.c
4 * @author MCD Application Team
5 * @brief RCC LL module driver.
6 ******************************************************************************
7 * @attention
9 * <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
11 * Redistribution and use in source and binary forms, with or without modification,
12 * are permitted provided that the following conditions are met:
13 * 1. Redistributions of source code must retain the above copyright notice,
14 * this list of conditions and the following disclaimer.
15 * 2. Redistributions in binary form must reproduce the above copyright notice,
16 * this list of conditions and the following disclaimer in the documentation
17 * and/or other materials provided with the distribution.
18 * 3. Neither the name of STMicroelectronics nor the names of its contributors
19 * may be used to endorse or promote products derived from this software
20 * without specific prior written permission.
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
23 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
24 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
25 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
33 ******************************************************************************
35 #if defined(USE_FULL_LL_DRIVER)
37 /* Includes ------------------------------------------------------------------*/
38 #include "stm32f3xx_ll_rcc.h"
39 #ifdef USE_FULL_ASSERT
40 #include "stm32_assert.h"
41 #else
42 #define assert_param(expr) ((void)0U)
43 #endif /* USE_FULL_ASSERT */
44 /** @addtogroup STM32F3xx_LL_Driver
45 * @{
48 #if defined(RCC)
50 /** @defgroup RCC_LL RCC
51 * @{
54 /* Private types -------------------------------------------------------------*/
55 /* Private variables ---------------------------------------------------------*/
56 /** @addtogroup RCC_LL_Private_Variables
57 * @{
59 #if defined(RCC_CFGR2_ADC1PRES) || defined(RCC_CFGR2_ADCPRE12) || defined(RCC_CFGR2_ADCPRE34)
60 const uint16_t aADCPrescTable[16] = {1U, 2U, 4U, 6U, 8U, 10U, 12U, 16U, 32U, 64U, 128U, 256U, 256U, 256U, 256U, 256U};
61 #endif /* RCC_CFGR2_ADC1PRES || RCC_CFGR2_ADCPRE12 || RCC_CFGR2_ADCPRE34 */
62 #if defined(RCC_CFGR_SDPRE)
63 const uint8_t aSDADCPrescTable[16] = {2U, 4U, 6U, 8U, 10U, 12U, 14U, 16U, 20U, 24U, 28U, 32U, 36U, 40U, 44U, 48U};
64 #endif /* RCC_CFGR_SDPRE */
65 /**
66 * @}
70 /* Private constants ---------------------------------------------------------*/
71 /* Private macros ------------------------------------------------------------*/
72 /** @addtogroup RCC_LL_Private_Macros
73 * @{
75 #if defined(RCC_CFGR3_USART2SW) && defined(RCC_CFGR3_USART3SW)
76 #define IS_LL_RCC_USART_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_USART1_CLKSOURCE) \
77 || ((__VALUE__) == LL_RCC_USART2_CLKSOURCE) \
78 || ((__VALUE__) == LL_RCC_USART3_CLKSOURCE))
79 #elif defined(RCC_CFGR3_USART2SW) && !defined(RCC_CFGR3_USART3SW)
80 #define IS_LL_RCC_USART_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_USART1_CLKSOURCE) \
81 || ((__VALUE__) == LL_RCC_USART2_CLKSOURCE))
82 #elif defined(RCC_CFGR3_USART3SW) && !defined(RCC_CFGR3_USART2SW)
83 #define IS_LL_RCC_USART_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_USART1_CLKSOURCE) \
84 || ((__VALUE__) == LL_RCC_USART3_CLKSOURCE))
85 #else
86 #define IS_LL_RCC_USART_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_USART1_CLKSOURCE))
87 #endif /* RCC_CFGR3_USART2SW && RCC_CFGR3_USART3SW */
89 #if defined(UART4) && defined(UART5)
90 #define IS_LL_RCC_UART_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_UART4_CLKSOURCE) \
91 || ((__VALUE__) == LL_RCC_UART5_CLKSOURCE))
92 #elif defined(UART4)
93 #define IS_LL_RCC_UART_INSTANCE(__VALUE__) ((__VALUE__) == LL_RCC_UART4_CLKSOURCE)
94 #elif defined(UART5)
95 #define IS_LL_RCC_UART_INSTANCE(__VALUE__) ((__VALUE__) == LL_RCC_UART5_CLKSOURCE)
96 #endif /* UART4 && UART5*/
98 #if defined(RCC_CFGR3_I2C2SW) && defined(RCC_CFGR3_I2C3SW)
99 #define IS_LL_RCC_I2C_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_I2C1_CLKSOURCE) \
100 || ((__VALUE__) == LL_RCC_I2C2_CLKSOURCE) \
101 || ((__VALUE__) == LL_RCC_I2C3_CLKSOURCE))
103 #elif defined(RCC_CFGR3_I2C2SW) && !defined(RCC_CFGR3_I2C3SW)
104 #define IS_LL_RCC_I2C_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_I2C1_CLKSOURCE) \
105 || ((__VALUE__) == LL_RCC_I2C2_CLKSOURCE))
107 #elif defined(RCC_CFGR3_I2C3SW) && !defined(RCC_CFGR3_I2C2SW)
108 #define IS_LL_RCC_I2C_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_I2C1_CLKSOURCE) \
109 || ((__VALUE__) == LL_RCC_I2C3_CLKSOURCE))
111 #else
112 #define IS_LL_RCC_I2C_CLKSOURCE(__VALUE__) ((__VALUE__) == LL_RCC_I2C1_CLKSOURCE)
113 #endif /* RCC_CFGR3_I2C2SW && RCC_CFGR3_I2C3SW */
115 #define IS_LL_RCC_I2S_CLKSOURCE(__VALUE__) ((__VALUE__) == LL_RCC_I2S_CLKSOURCE)
117 #if defined(USB)
118 #define IS_LL_RCC_USB_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_USB_CLKSOURCE))
119 #endif /* USB */
121 #if defined(RCC_CFGR_ADCPRE)
122 #define IS_LL_RCC_ADC_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_ADC_CLKSOURCE))
123 #else
124 #if defined(RCC_CFGR2_ADC1PRES)
125 #define IS_LL_RCC_ADC_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_ADC1_CLKSOURCE))
126 #elif defined(RCC_CFGR2_ADCPRE12) && defined(RCC_CFGR2_ADCPRE34)
127 #define IS_LL_RCC_ADC_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_ADC12_CLKSOURCE) \
128 || ((__VALUE__) == LL_RCC_ADC34_CLKSOURCE))
129 #else /* RCC_CFGR2_ADCPRE12 */
130 #define IS_LL_RCC_ADC_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_ADC12_CLKSOURCE))
131 #endif /* RCC_CFGR2_ADC1PRES */
132 #endif /* RCC_CFGR_ADCPRE */
134 #if defined(RCC_CFGR_SDPRE)
135 #define IS_LL_RCC_SDADC_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_SDADC_CLKSOURCE))
136 #endif /* RCC_CFGR_SDPRE */
138 #if defined(CEC)
139 #define IS_LL_RCC_CEC_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_CEC_CLKSOURCE))
140 #endif /* CEC */
142 #if defined(RCC_CFGR3_TIMSW)
143 #if defined(RCC_CFGR3_TIM8SW) && defined(RCC_CFGR3_TIM15SW) && defined(RCC_CFGR3_TIM16SW) \
144 && defined(RCC_CFGR3_TIM17SW) && defined(RCC_CFGR3_TIM20SW) && defined(RCC_CFGR3_TIM2SW) \
145 && defined(RCC_CFGR3_TIM34SW)
147 #define IS_LL_RCC_TIM_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_TIM1_CLKSOURCE) \
148 || ((__VALUE__) == LL_RCC_TIM2_CLKSOURCE) \
149 || ((__VALUE__) == LL_RCC_TIM8_CLKSOURCE) \
150 || ((__VALUE__) == LL_RCC_TIM15_CLKSOURCE) \
151 || ((__VALUE__) == LL_RCC_TIM16_CLKSOURCE) \
152 || ((__VALUE__) == LL_RCC_TIM17_CLKSOURCE) \
153 || ((__VALUE__) == LL_RCC_TIM20_CLKSOURCE) \
154 || ((__VALUE__) == LL_RCC_TIM34_CLKSOURCE))
156 #elif !defined(RCC_CFGR3_TIM8SW) && defined(RCC_CFGR3_TIM15SW) && defined(RCC_CFGR3_TIM16SW) \
157 && defined(RCC_CFGR3_TIM17SW) && !defined(RCC_CFGR3_TIM20SW) && defined(RCC_CFGR3_TIM2SW) \
158 && defined(RCC_CFGR3_TIM34SW)
160 #define IS_LL_RCC_TIM_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_TIM1_CLKSOURCE) \
161 || ((__VALUE__) == LL_RCC_TIM2_CLKSOURCE) \
162 || ((__VALUE__) == LL_RCC_TIM15_CLKSOURCE) \
163 || ((__VALUE__) == LL_RCC_TIM16_CLKSOURCE) \
164 || ((__VALUE__) == LL_RCC_TIM17_CLKSOURCE) \
165 || ((__VALUE__) == LL_RCC_TIM34_CLKSOURCE))
167 #elif defined(RCC_CFGR3_TIM8SW) && !defined(RCC_CFGR3_TIM15SW) && !defined(RCC_CFGR3_TIM16SW) \
168 && !defined(RCC_CFGR3_TIM17SW) && !defined(RCC_CFGR3_TIM20SW) && !defined(RCC_CFGR3_TIM2SW) \
169 && !defined(RCC_CFGR3_TIM34SW)
171 #define IS_LL_RCC_TIM_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_TIM1_CLKSOURCE) \
172 || ((__VALUE__) == LL_RCC_TIM8_CLKSOURCE))
174 #elif !defined(RCC_CFGR3_TIM8SW) && defined(RCC_CFGR3_TIM15SW) && defined(RCC_CFGR3_TIM16SW) \
175 && defined(RCC_CFGR3_TIM17SW) && !defined(RCC_CFGR3_TIM20SW) && !defined(RCC_CFGR3_TIM2SW) \
176 && !defined(RCC_CFGR3_TIM34SW)
178 #define IS_LL_RCC_TIM_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_TIM1_CLKSOURCE) \
179 || ((__VALUE__) == LL_RCC_TIM15_CLKSOURCE) \
180 || ((__VALUE__) == LL_RCC_TIM16_CLKSOURCE) \
181 || ((__VALUE__) == LL_RCC_TIM17_CLKSOURCE))
183 #elif !defined(RCC_CFGR3_TIM8SW) && !defined(RCC_CFGR3_TIM15SW) && !defined(RCC_CFGR3_TIM16SW) \
184 && !defined(RCC_CFGR3_TIM17SW) && !defined(RCC_CFGR3_TIM20SW) && !defined(RCC_CFGR3_TIM2SW) \
185 && !defined(RCC_CFGR3_TIM34SW)
187 #define IS_LL_RCC_TIM_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_TIM1_CLKSOURCE))
189 #else
190 #error "Miss macro"
191 #endif /* RCC_CFGR3_TIMxSW */
192 #endif /* RCC_CFGR3_TIMSW */
194 #if defined(HRTIM1)
195 #define IS_LL_RCC_HRTIM_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_HRTIM1_CLKSOURCE))
196 #endif /* HRTIM1 */
199 * @}
202 /* Private function prototypes -----------------------------------------------*/
203 /** @defgroup RCC_LL_Private_Functions RCC Private functions
204 * @{
206 uint32_t RCC_GetSystemClockFreq(void);
207 uint32_t RCC_GetHCLKClockFreq(uint32_t SYSCLK_Frequency);
208 uint32_t RCC_GetPCLK1ClockFreq(uint32_t HCLK_Frequency);
209 uint32_t RCC_GetPCLK2ClockFreq(uint32_t HCLK_Frequency);
210 uint32_t RCC_PLL_GetFreqDomain_SYS(void);
212 * @}
216 /* Exported functions --------------------------------------------------------*/
217 /** @addtogroup RCC_LL_Exported_Functions
218 * @{
221 /** @addtogroup RCC_LL_EF_Init
222 * @{
226 * @brief Reset the RCC clock configuration to the default reset state.
227 * @note The default reset state of the clock configuration is given below:
228 * - HSI ON and used as system clock source
229 * - HSE and PLL OFF
230 * - AHB, APB1 and APB2 prescaler set to 1.
231 * - CSS, MCO OFF
232 * - All interrupts disabled
233 * @note This function doesn't modify the configuration of the
234 * - Peripheral clocks
235 * - LSI, LSE and RTC clocks
236 * @retval An ErrorStatus enumeration value:
237 * - SUCCESS: RCC registers are de-initialized
238 * - ERROR: not applicable
240 ErrorStatus LL_RCC_DeInit(void)
242 uint32_t vl_mask = 0U;
244 /* Set HSION bit */
245 LL_RCC_HSI_Enable();
247 /* Set HSITRIM bits to the reset value*/
248 LL_RCC_HSI_SetCalibTrimming(0x10U);
250 /* Reset SW, HPRE, PPRE and MCOSEL bits */
251 vl_mask = 0xFFFFFFFFU;
252 CLEAR_BIT(vl_mask, (RCC_CFGR_SW | RCC_CFGR_HPRE | RCC_CFGR_PPRE1 | RCC_CFGR_PPRE2 | RCC_CFGR_MCOSEL));
253 LL_RCC_WriteReg(CFGR, vl_mask);
255 /* Reset HSEON, CSSON, PLLON bits */
256 vl_mask = 0xFFFFFFFFU;
257 CLEAR_BIT(vl_mask, (RCC_CR_PLLON | RCC_CR_CSSON | RCC_CR_HSEON));
258 LL_RCC_WriteReg(CR, vl_mask);
260 /* Reset HSEBYP bit */
261 LL_RCC_HSE_DisableBypass();
263 /* Reset CFGR register */
264 LL_RCC_WriteReg(CFGR, 0x00000000U);
266 /* Reset CFGR2 register */
267 LL_RCC_WriteReg(CFGR2, 0x00000000U);
269 /* Reset CFGR3 register */
270 LL_RCC_WriteReg(CFGR3, 0x00000000U);
272 /* Clear pending flags */
273 vl_mask = (LL_RCC_CIR_LSIRDYC | LL_RCC_CIR_LSERDYC | LL_RCC_CIR_HSIRDYC | LL_RCC_CIR_HSERDYC | LL_RCC_CIR_PLLRDYC | LL_RCC_CIR_CSSC);
274 SET_BIT(RCC->CIR, vl_mask);
276 /* Disable all interrupts */
277 LL_RCC_WriteReg(CIR, 0x00000000U);
279 return SUCCESS;
283 * @}
286 /** @addtogroup RCC_LL_EF_Get_Freq
287 * @brief Return the frequencies of different on chip clocks; System, AHB, APB1 and APB2 buses clocks
288 * and different peripheral clocks available on the device.
289 * @note If SYSCLK source is HSI, function returns values based on HSI_VALUE(**)
290 * @note If SYSCLK source is HSE, function returns values based on HSE_VALUE(***)
291 * @note If SYSCLK source is PLL, function returns values based on
292 * HSI_VALUE(**) or HSE_VALUE(***) multiplied/divided by the PLL factors.
293 * @note (**) HSI_VALUE is a defined constant but the real value may vary
294 * depending on the variations in voltage and temperature.
295 * @note (***) HSE_VALUE is a defined constant, user has to ensure that
296 * HSE_VALUE is same as the real frequency of the crystal used.
297 * Otherwise, this function may have wrong result.
298 * @note The result of this function could be incorrect when using fractional
299 * value for HSE crystal.
300 * @note This function can be used by the user application to compute the
301 * baud-rate for the communication peripherals or configure other parameters.
302 * @{
306 * @brief Return the frequencies of different on chip clocks; System, AHB, APB1 and APB2 buses clocks
307 * @note Each time SYSCLK, HCLK, PCLK1 and/or PCLK2 clock changes, this function
308 * must be called to update structure fields. Otherwise, any
309 * configuration based on this function will be incorrect.
310 * @param RCC_Clocks pointer to a @ref LL_RCC_ClocksTypeDef structure which will hold the clocks frequencies
311 * @retval None
313 void LL_RCC_GetSystemClocksFreq(LL_RCC_ClocksTypeDef *RCC_Clocks)
315 /* Get SYSCLK frequency */
316 RCC_Clocks->SYSCLK_Frequency = RCC_GetSystemClockFreq();
318 /* HCLK clock frequency */
319 RCC_Clocks->HCLK_Frequency = RCC_GetHCLKClockFreq(RCC_Clocks->SYSCLK_Frequency);
321 /* PCLK1 clock frequency */
322 RCC_Clocks->PCLK1_Frequency = RCC_GetPCLK1ClockFreq(RCC_Clocks->HCLK_Frequency);
324 /* PCLK2 clock frequency */
325 RCC_Clocks->PCLK2_Frequency = RCC_GetPCLK2ClockFreq(RCC_Clocks->HCLK_Frequency);
329 * @brief Return USARTx clock frequency
330 * @param USARTxSource This parameter can be one of the following values:
331 * @arg @ref LL_RCC_USART1_CLKSOURCE
332 * @arg @ref LL_RCC_USART2_CLKSOURCE (*)
333 * @arg @ref LL_RCC_USART3_CLKSOURCE (*)
335 * (*) value not defined in all devices.
336 * @retval USART clock frequency (in Hz)
337 * @arg @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator (HSI or LSE) is not ready
339 uint32_t LL_RCC_GetUSARTClockFreq(uint32_t USARTxSource)
341 uint32_t usart_frequency = LL_RCC_PERIPH_FREQUENCY_NO;
343 /* Check parameter */
344 assert_param(IS_LL_RCC_USART_CLKSOURCE(USARTxSource));
345 #if defined(RCC_CFGR3_USART1SW)
346 if (USARTxSource == LL_RCC_USART1_CLKSOURCE)
348 /* USART1CLK clock frequency */
349 switch (LL_RCC_GetUSARTClockSource(USARTxSource))
351 case LL_RCC_USART1_CLKSOURCE_SYSCLK: /* USART1 Clock is System Clock */
352 usart_frequency = RCC_GetSystemClockFreq();
353 break;
355 case LL_RCC_USART1_CLKSOURCE_HSI: /* USART1 Clock is HSI Osc. */
356 if (LL_RCC_HSI_IsReady())
358 usart_frequency = HSI_VALUE;
360 break;
362 case LL_RCC_USART1_CLKSOURCE_LSE: /* USART1 Clock is LSE Osc. */
363 if (LL_RCC_LSE_IsReady())
365 usart_frequency = LSE_VALUE;
367 break;
369 #if defined(RCC_CFGR3_USART1SW_PCLK1)
370 case LL_RCC_USART1_CLKSOURCE_PCLK1: /* USART1 Clock is PCLK1 */
371 default:
372 usart_frequency = RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
373 #else
374 case LL_RCC_USART1_CLKSOURCE_PCLK2: /* USART1 Clock is PCLK2 */
375 default:
376 usart_frequency = RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
377 #endif /* RCC_CFGR3_USART1SW_PCLK1 */
378 break;
381 #endif /* RCC_CFGR3_USART1SW */
383 #if defined(RCC_CFGR3_USART2SW)
384 if (USARTxSource == LL_RCC_USART2_CLKSOURCE)
386 /* USART2CLK clock frequency */
387 switch (LL_RCC_GetUSARTClockSource(USARTxSource))
389 case LL_RCC_USART2_CLKSOURCE_SYSCLK: /* USART2 Clock is System Clock */
390 usart_frequency = RCC_GetSystemClockFreq();
391 break;
393 case LL_RCC_USART2_CLKSOURCE_HSI: /* USART2 Clock is HSI Osc. */
394 if (LL_RCC_HSI_IsReady())
396 usart_frequency = HSI_VALUE;
398 break;
400 case LL_RCC_USART2_CLKSOURCE_LSE: /* USART2 Clock is LSE Osc. */
401 if (LL_RCC_LSE_IsReady())
403 usart_frequency = LSE_VALUE;
405 break;
407 case LL_RCC_USART2_CLKSOURCE_PCLK1: /* USART2 Clock is PCLK1 */
408 default:
409 usart_frequency = RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
410 break;
413 #endif /* RCC_CFGR3_USART2SW */
415 #if defined(RCC_CFGR3_USART3SW)
416 if (USARTxSource == LL_RCC_USART3_CLKSOURCE)
418 /* USART3CLK clock frequency */
419 switch (LL_RCC_GetUSARTClockSource(USARTxSource))
421 case LL_RCC_USART3_CLKSOURCE_SYSCLK: /* USART3 Clock is System Clock */
422 usart_frequency = RCC_GetSystemClockFreq();
423 break;
425 case LL_RCC_USART3_CLKSOURCE_HSI: /* USART3 Clock is HSI Osc. */
426 if (LL_RCC_HSI_IsReady())
428 usart_frequency = HSI_VALUE;
430 break;
432 case LL_RCC_USART3_CLKSOURCE_LSE: /* USART3 Clock is LSE Osc. */
433 if (LL_RCC_LSE_IsReady())
435 usart_frequency = LSE_VALUE;
437 break;
439 case LL_RCC_USART3_CLKSOURCE_PCLK1: /* USART3 Clock is PCLK1 */
440 default:
441 usart_frequency = RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
442 break;
446 #endif /* RCC_CFGR3_USART3SW */
447 return usart_frequency;
450 #if defined(UART4) || defined(UART5)
452 * @brief Return UARTx clock frequency
453 * @param UARTxSource This parameter can be one of the following values:
454 * @arg @ref LL_RCC_UART4_CLKSOURCE
455 * @arg @ref LL_RCC_UART5_CLKSOURCE
456 * @retval UART clock frequency (in Hz)
457 * @arg @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator (HSI or LSE) is not ready
459 uint32_t LL_RCC_GetUARTClockFreq(uint32_t UARTxSource)
461 uint32_t uart_frequency = LL_RCC_PERIPH_FREQUENCY_NO;
463 /* Check parameter */
464 assert_param(IS_LL_RCC_UART_CLKSOURCE(UARTxSource));
466 #if defined(UART4)
467 if (UARTxSource == LL_RCC_UART4_CLKSOURCE)
469 /* UART4CLK clock frequency */
470 switch (LL_RCC_GetUARTClockSource(UARTxSource))
472 case LL_RCC_UART4_CLKSOURCE_SYSCLK: /* UART4 Clock is System Clock */
473 uart_frequency = RCC_GetSystemClockFreq();
474 break;
476 case LL_RCC_UART4_CLKSOURCE_HSI: /* UART4 Clock is HSI Osc. */
477 if (LL_RCC_HSI_IsReady())
479 uart_frequency = HSI_VALUE;
481 break;
483 case LL_RCC_UART4_CLKSOURCE_LSE: /* UART4 Clock is LSE Osc. */
484 if (LL_RCC_LSE_IsReady())
486 uart_frequency = LSE_VALUE;
488 break;
490 case LL_RCC_UART4_CLKSOURCE_PCLK1: /* UART4 Clock is PCLK1 */
491 default:
492 uart_frequency = RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
493 break;
496 #endif /* UART4 */
498 #if defined(UART5)
499 if (UARTxSource == LL_RCC_UART5_CLKSOURCE)
501 /* UART5CLK clock frequency */
502 switch (LL_RCC_GetUARTClockSource(UARTxSource))
504 case LL_RCC_UART5_CLKSOURCE_SYSCLK: /* UART5 Clock is System Clock */
505 uart_frequency = RCC_GetSystemClockFreq();
506 break;
508 case LL_RCC_UART5_CLKSOURCE_HSI: /* UART5 Clock is HSI Osc. */
509 if (LL_RCC_HSI_IsReady())
511 uart_frequency = HSI_VALUE;
513 break;
515 case LL_RCC_UART5_CLKSOURCE_LSE: /* UART5 Clock is LSE Osc. */
516 if (LL_RCC_LSE_IsReady())
518 uart_frequency = LSE_VALUE;
520 break;
522 case LL_RCC_UART5_CLKSOURCE_PCLK1: /* UART5 Clock is PCLK1 */
523 default:
524 uart_frequency = RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
525 break;
528 #endif /* UART5 */
530 return uart_frequency;
532 #endif /* UART4 || UART5 */
535 * @brief Return I2Cx clock frequency
536 * @param I2CxSource This parameter can be one of the following values:
537 * @arg @ref LL_RCC_I2C1_CLKSOURCE
538 * @arg @ref LL_RCC_I2C2_CLKSOURCE (*)
539 * @arg @ref LL_RCC_I2C3_CLKSOURCE (*)
541 * (*) value not defined in all devices
542 * @retval I2C clock frequency (in Hz)
543 * @arg @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that HSI oscillator is not ready
545 uint32_t LL_RCC_GetI2CClockFreq(uint32_t I2CxSource)
547 uint32_t i2c_frequency = LL_RCC_PERIPH_FREQUENCY_NO;
549 /* Check parameter */
550 assert_param(IS_LL_RCC_I2C_CLKSOURCE(I2CxSource));
552 /* I2C1 CLK clock frequency */
553 if (I2CxSource == LL_RCC_I2C1_CLKSOURCE)
555 switch (LL_RCC_GetI2CClockSource(I2CxSource))
557 case LL_RCC_I2C1_CLKSOURCE_SYSCLK: /* I2C1 Clock is System Clock */
558 i2c_frequency = RCC_GetSystemClockFreq();
559 break;
561 case LL_RCC_I2C1_CLKSOURCE_HSI: /* I2C1 Clock is HSI Osc. */
562 default:
563 if (LL_RCC_HSI_IsReady())
565 i2c_frequency = HSI_VALUE;
567 break;
571 #if defined(RCC_CFGR3_I2C2SW)
572 /* I2C2 CLK clock frequency */
573 if (I2CxSource == LL_RCC_I2C2_CLKSOURCE)
575 switch (LL_RCC_GetI2CClockSource(I2CxSource))
577 case LL_RCC_I2C2_CLKSOURCE_SYSCLK: /* I2C2 Clock is System Clock */
578 i2c_frequency = RCC_GetSystemClockFreq();
579 break;
581 case LL_RCC_I2C2_CLKSOURCE_HSI: /* I2C2 Clock is HSI Osc. */
582 default:
583 if (LL_RCC_HSI_IsReady())
585 i2c_frequency = HSI_VALUE;
587 break;
590 #endif /*RCC_CFGR3_I2C2SW*/
592 #if defined(RCC_CFGR3_I2C3SW)
593 /* I2C3 CLK clock frequency */
594 if (I2CxSource == LL_RCC_I2C3_CLKSOURCE)
596 switch (LL_RCC_GetI2CClockSource(I2CxSource))
598 case LL_RCC_I2C3_CLKSOURCE_SYSCLK: /* I2C3 Clock is System Clock */
599 i2c_frequency = RCC_GetSystemClockFreq();
600 break;
602 case LL_RCC_I2C3_CLKSOURCE_HSI: /* I2C3 Clock is HSI Osc. */
603 default:
604 if (LL_RCC_HSI_IsReady())
606 i2c_frequency = HSI_VALUE;
608 break;
611 #endif /*RCC_CFGR3_I2C3SW*/
613 return i2c_frequency;
616 #if defined(RCC_CFGR_I2SSRC)
618 * @brief Return I2Sx clock frequency
619 * @param I2SxSource This parameter can be one of the following values:
620 * @arg @ref LL_RCC_I2S_CLKSOURCE
621 * @retval I2S clock frequency (in Hz)
622 * @arg @ref LL_RCC_PERIPH_FREQUENCY_NA indicates that external clock is used */
623 uint32_t LL_RCC_GetI2SClockFreq(uint32_t I2SxSource)
625 uint32_t i2s_frequency = LL_RCC_PERIPH_FREQUENCY_NO;
627 /* Check parameter */
628 assert_param(IS_LL_RCC_I2S_CLKSOURCE(I2SxSource));
630 /* I2S1CLK clock frequency */
631 switch (LL_RCC_GetI2SClockSource(I2SxSource))
633 case LL_RCC_I2S_CLKSOURCE_SYSCLK: /*!< System clock selected as I2S clock source */
634 i2s_frequency = RCC_GetSystemClockFreq();
635 break;
637 case LL_RCC_I2S_CLKSOURCE_PIN: /*!< External clock selected as I2S clock source */
638 default:
639 i2s_frequency = LL_RCC_PERIPH_FREQUENCY_NA;
640 break;
643 return i2s_frequency;
645 #endif /* RCC_CFGR_I2SSRC */
646 #if defined(USB)
648 * @brief Return USBx clock frequency
649 * @param USBxSource This parameter can be one of the following values:
650 * @arg @ref LL_RCC_USB_CLKSOURCE
651 * @retval USB clock frequency (in Hz)
652 * @arg @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator (HSI48) or PLL is not ready
653 * @arg @ref LL_RCC_PERIPH_FREQUENCY_NA indicates that no clock source selected
655 uint32_t LL_RCC_GetUSBClockFreq(uint32_t USBxSource)
657 uint32_t usb_frequency = LL_RCC_PERIPH_FREQUENCY_NO;
659 /* Check parameter */
660 assert_param(IS_LL_RCC_USB_CLKSOURCE(USBxSource));
662 /* USBCLK clock frequency */
663 switch (LL_RCC_GetUSBClockSource(USBxSource))
665 case LL_RCC_USB_CLKSOURCE_PLL: /* PLL clock used as USB clock source */
666 if (LL_RCC_PLL_IsReady())
668 usb_frequency = RCC_PLL_GetFreqDomain_SYS();
670 break;
672 case LL_RCC_USB_CLKSOURCE_PLL_DIV_1_5: /* PLL clock used as USB clock source */
673 default:
674 if (LL_RCC_PLL_IsReady())
676 usb_frequency = (RCC_PLL_GetFreqDomain_SYS() * 3U) / 2U;
678 break;
681 return usb_frequency;
683 #endif /* USB */
685 #if defined(RCC_CFGR_ADCPRE) || defined(RCC_CFGR2_ADC1PRES) || defined(RCC_CFGR2_ADCPRE12) || defined(RCC_CFGR2_ADCPRE34)
687 * @brief Return ADCx clock frequency
688 * @param ADCxSource This parameter can be one of the following values:
689 * @arg @ref LL_RCC_ADC_CLKSOURCE (*)
690 * @arg @ref LL_RCC_ADC1_CLKSOURCE (*)
691 * @arg @ref LL_RCC_ADC12_CLKSOURCE (*)
692 * @arg @ref LL_RCC_ADC34_CLKSOURCE (*)
694 * (*) value not defined in all devices
695 * @retval ADC clock frequency (in Hz)
697 uint32_t LL_RCC_GetADCClockFreq(uint32_t ADCxSource)
699 uint32_t adc_prescaler = 0U;
700 uint32_t adc_frequency = LL_RCC_PERIPH_FREQUENCY_NO;
702 /* Check parameter */
703 assert_param(IS_LL_RCC_ADC_CLKSOURCE(ADCxSource));
705 /* Get ADC prescaler */
706 adc_prescaler = LL_RCC_GetADCClockSource(ADCxSource);
708 #if defined(RCC_CFGR_ADCPRE)
709 /* ADC frequency = PCLK2 frequency / ADC prescaler (2, 4, 6 or 8) */
710 adc_frequency = RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()))
711 / (((adc_prescaler >> POSITION_VAL(ADCxSource)) + 1U) * 2U);
712 #else
713 if ((adc_prescaler & 0x0000FFFFU) == ((uint32_t)0x00000000U))
715 /* ADC frequency = HCLK frequency */
716 adc_frequency = RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq());
718 else
720 /* ADC frequency = PCLK2 frequency / ADC prescaler (from 1 to 256) */
721 adc_frequency = RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()))
722 / (aADCPrescTable[((adc_prescaler & 0x0000FFFFU) >> POSITION_VAL(ADCxSource)) & 0xFU]);
724 #endif /* RCC_CFGR_ADCPRE */
726 return adc_frequency;
728 #endif /*RCC_CFGR_ADCPRE || RCC_CFGR2_ADC1PRES || RCC_CFGR2_ADCPRE12 || RCC_CFGR2_ADCPRE34 */
730 #if defined(RCC_CFGR_SDPRE)
732 * @brief Return SDADCx clock frequency
733 * @param SDADCxSource This parameter can be one of the following values:
734 * @arg @ref LL_RCC_SDADC_CLKSOURCE
735 * @retval SDADC clock frequency (in Hz)
737 uint32_t LL_RCC_GetSDADCClockFreq(uint32_t SDADCxSource)
739 uint32_t sdadc_prescaler = 0U;
740 uint32_t sdadc_frequency = LL_RCC_PERIPH_FREQUENCY_NO;
742 /* Check parameter */
743 assert_param(IS_LL_RCC_SDADC_CLKSOURCE(SDADCxSource));
745 /* Get SDADC prescaler */
746 sdadc_prescaler = LL_RCC_GetSDADCClockSource(SDADCxSource);
748 /* SDADC frequency = SYSTEM frequency / SDADC prescaler (from 2 to 48) */
749 sdadc_frequency = RCC_GetSystemClockFreq()
750 / (aSDADCPrescTable[(sdadc_prescaler >> POSITION_VAL(SDADCxSource)) & 0xFU]);
752 return sdadc_frequency;
754 #endif /*RCC_CFGR_SDPRE */
756 #if defined(CEC)
758 * @brief Return CECx clock frequency
759 * @param CECxSource This parameter can be one of the following values:
760 * @arg @ref LL_RCC_CEC_CLKSOURCE
761 * @retval CEC clock frequency (in Hz)
762 * @arg @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillators (HSI or LSE) are not ready
764 uint32_t LL_RCC_GetCECClockFreq(uint32_t CECxSource)
766 uint32_t cec_frequency = LL_RCC_PERIPH_FREQUENCY_NO;
768 /* Check parameter */
769 assert_param(IS_LL_RCC_CEC_CLKSOURCE(CECxSource));
771 /* CECCLK clock frequency */
772 switch (LL_RCC_GetCECClockSource(CECxSource))
774 case LL_RCC_CEC_CLKSOURCE_HSI_DIV244: /* HSI / 244 clock used as CEC clock source */
775 if (LL_RCC_HSI_IsReady())
777 cec_frequency = HSI_VALUE / 244U;
779 break;
781 case LL_RCC_CEC_CLKSOURCE_LSE: /* LSE clock used as CEC clock source */
782 default:
783 if (LL_RCC_LSE_IsReady())
785 cec_frequency = LSE_VALUE;
787 break;
790 return cec_frequency;
792 #endif /* CEC */
794 #if defined(RCC_CFGR3_TIMSW)
796 * @brief Return TIMx clock frequency
797 * @param TIMxSource This parameter can be one of the following values:
798 * @arg @ref LL_RCC_TIM1_CLKSOURCE
799 * @arg @ref LL_RCC_TIM8_CLKSOURCE (*)
800 * @arg @ref LL_RCC_TIM15_CLKSOURCE (*)
801 * @arg @ref LL_RCC_TIM16_CLKSOURCE (*)
802 * @arg @ref LL_RCC_TIM17_CLKSOURCE (*)
803 * @arg @ref LL_RCC_TIM20_CLKSOURCE (*)
804 * @arg @ref LL_RCC_TIM2_CLKSOURCE (*)
805 * @arg @ref LL_RCC_TIM34_CLKSOURCE (*)
807 * (*) value not defined in all devices
808 * @retval TIM clock frequency (in Hz)
810 uint32_t LL_RCC_GetTIMClockFreq(uint32_t TIMxSource)
812 uint32_t tim_frequency = LL_RCC_PERIPH_FREQUENCY_NO;
814 /* Check parameter */
815 assert_param(IS_LL_RCC_TIM_CLKSOURCE(TIMxSource));
817 if (TIMxSource == LL_RCC_TIM1_CLKSOURCE)
819 /* TIM1CLK clock frequency */
820 if (LL_RCC_GetTIMClockSource(LL_RCC_TIM1_CLKSOURCE) == LL_RCC_TIM1_CLKSOURCE_PCLK2)
822 /* PCLK2 used as TIM1 clock source */
823 tim_frequency = RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
825 else /* LL_RCC_TIM1_CLKSOURCE_PLL */
827 /* PLL clock used as TIM1 clock source */
828 tim_frequency = RCC_PLL_GetFreqDomain_SYS();
832 #if defined(RCC_CFGR3_TIM8SW)
833 if (TIMxSource == LL_RCC_TIM8_CLKSOURCE)
835 /* TIM8CLK clock frequency */
836 if (LL_RCC_GetTIMClockSource(LL_RCC_TIM8_CLKSOURCE) == LL_RCC_TIM8_CLKSOURCE_PCLK2)
838 /* PCLK2 used as TIM8 clock source */
839 tim_frequency = RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
841 else /* LL_RCC_TIM8_CLKSOURCE_PLL */
843 /* PLL clock used as TIM8 clock source */
844 tim_frequency = RCC_PLL_GetFreqDomain_SYS();
847 #endif /*RCC_CFGR3_TIM8SW*/
849 #if defined(RCC_CFGR3_TIM15SW)
850 if (TIMxSource == LL_RCC_TIM15_CLKSOURCE)
852 /* TIM15CLK clock frequency */
853 if (LL_RCC_GetTIMClockSource(LL_RCC_TIM15_CLKSOURCE) == LL_RCC_TIM15_CLKSOURCE_PCLK2)
855 /* PCLK2 used as TIM15 clock source */
856 tim_frequency = RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
858 else /* LL_RCC_TIM15_CLKSOURCE_PLL */
860 /* PLL clock used as TIM15 clock source */
861 tim_frequency = RCC_PLL_GetFreqDomain_SYS();
864 #endif /*RCC_CFGR3_TIM15SW*/
866 #if defined(RCC_CFGR3_TIM16SW)
867 if (TIMxSource == LL_RCC_TIM16_CLKSOURCE)
869 /* TIM16CLK clock frequency */
870 if (LL_RCC_GetTIMClockSource(LL_RCC_TIM16_CLKSOURCE) == LL_RCC_TIM16_CLKSOURCE_PCLK2)
872 /* PCLK2 used as TIM16 clock source */
873 tim_frequency = RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
875 else /* LL_RCC_TIM16_CLKSOURCE_PLL */
877 /* PLL clock used as TIM16 clock source */
878 tim_frequency = RCC_PLL_GetFreqDomain_SYS();
881 #endif /*RCC_CFGR3_TIM16SW*/
883 #if defined(RCC_CFGR3_TIM17SW)
884 if (TIMxSource == LL_RCC_TIM17_CLKSOURCE)
886 /* TIM17CLK clock frequency */
887 if (LL_RCC_GetTIMClockSource(LL_RCC_TIM17_CLKSOURCE) == LL_RCC_TIM17_CLKSOURCE_PCLK2)
889 /* PCLK2 used as TIM17 clock source */
890 tim_frequency = RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
892 else /* LL_RCC_TIM17_CLKSOURCE_PLL */
894 /* PLL clock used as TIM17 clock source */
895 tim_frequency = RCC_PLL_GetFreqDomain_SYS();
898 #endif /*RCC_CFGR3_TIM17SW*/
900 #if defined(RCC_CFGR3_TIM20SW)
901 if (TIMxSource == LL_RCC_TIM20_CLKSOURCE)
903 /* TIM20CLK clock frequency */
904 if (LL_RCC_GetTIMClockSource(LL_RCC_TIM20_CLKSOURCE) == LL_RCC_TIM20_CLKSOURCE_PCLK2)
906 /* PCLK2 used as TIM20 clock source */
907 tim_frequency = RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
909 else /* LL_RCC_TIM20_CLKSOURCE_PLL */
911 /* PLL clock used as TIM20 clock source */
912 tim_frequency = RCC_PLL_GetFreqDomain_SYS();
915 #endif /*RCC_CFGR3_TIM20SW*/
917 #if defined(RCC_CFGR3_TIM2SW)
918 if (TIMxSource == LL_RCC_TIM2_CLKSOURCE)
920 /* TIM2CLK clock frequency */
921 if (LL_RCC_GetTIMClockSource(LL_RCC_TIM2_CLKSOURCE) == LL_RCC_TIM2_CLKSOURCE_PCLK1)
923 /* PCLK1 used as TIM2 clock source */
924 tim_frequency = RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
926 else /* LL_RCC_TIM2_CLKSOURCE_PLL */
928 /* PLL clock used as TIM2 clock source */
929 tim_frequency = RCC_PLL_GetFreqDomain_SYS();
932 #endif /*RCC_CFGR3_TIM2SW*/
934 #if defined(RCC_CFGR3_TIM34SW)
935 if (TIMxSource == LL_RCC_TIM34_CLKSOURCE)
937 /* TIM3/4 CLK clock frequency */
938 if (LL_RCC_GetTIMClockSource(LL_RCC_TIM34_CLKSOURCE) == LL_RCC_TIM34_CLKSOURCE_PCLK1)
940 /* PCLK1 used as TIM3/4 clock source */
941 tim_frequency = RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
943 else /* LL_RCC_TIM34_CLKSOURCE_PLL */
945 /* PLL clock used as TIM3/4 clock source */
946 tim_frequency = RCC_PLL_GetFreqDomain_SYS();
949 #endif /*RCC_CFGR3_TIM34SW*/
951 return tim_frequency;
953 #endif /*RCC_CFGR3_TIMSW*/
955 #if defined(HRTIM1)
957 * @brief Return HRTIMx clock frequency
958 * @param HRTIMxSource This parameter can be one of the following values:
959 * @arg @ref LL_RCC_HRTIM1_CLKSOURCE
960 * @retval HRTIM clock frequency (in Hz)
962 uint32_t LL_RCC_GetHRTIMClockFreq(uint32_t HRTIMxSource)
964 uint32_t hrtim_frequency = LL_RCC_PERIPH_FREQUENCY_NO;
966 /* Check parameter */
967 assert_param(IS_LL_RCC_HRTIM_CLKSOURCE(HRTIMxSource));
969 /* HRTIM1CLK clock frequency */
970 if (LL_RCC_GetHRTIMClockSource(LL_RCC_HRTIM1_CLKSOURCE) == LL_RCC_HRTIM1_CLKSOURCE_PCLK2)
972 /* PCLK2 used as HRTIM1 clock source */
973 hrtim_frequency = RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
975 else /* LL_RCC_HRTIM1_CLKSOURCE_PLL */
977 /* PLL clock used as HRTIM1 clock source */
978 hrtim_frequency = RCC_PLL_GetFreqDomain_SYS();
981 return hrtim_frequency;
983 #endif /* HRTIM1 */
986 * @}
990 * @}
993 /** @addtogroup RCC_LL_Private_Functions
994 * @{
998 * @brief Return SYSTEM clock frequency
999 * @retval SYSTEM clock frequency (in Hz)
1001 uint32_t RCC_GetSystemClockFreq(void)
1003 uint32_t frequency = 0U;
1005 /* Get SYSCLK source -------------------------------------------------------*/
1006 switch (LL_RCC_GetSysClkSource())
1008 case LL_RCC_SYS_CLKSOURCE_STATUS_HSI: /* HSI used as system clock source */
1009 frequency = HSI_VALUE;
1010 break;
1012 case LL_RCC_SYS_CLKSOURCE_STATUS_HSE: /* HSE used as system clock source */
1013 frequency = HSE_VALUE;
1014 break;
1016 case LL_RCC_SYS_CLKSOURCE_STATUS_PLL: /* PLL used as system clock source */
1017 frequency = RCC_PLL_GetFreqDomain_SYS();
1018 break;
1020 default:
1021 frequency = HSI_VALUE;
1022 break;
1025 return frequency;
1029 * @brief Return HCLK clock frequency
1030 * @param SYSCLK_Frequency SYSCLK clock frequency
1031 * @retval HCLK clock frequency (in Hz)
1033 uint32_t RCC_GetHCLKClockFreq(uint32_t SYSCLK_Frequency)
1035 /* HCLK clock frequency */
1036 return __LL_RCC_CALC_HCLK_FREQ(SYSCLK_Frequency, LL_RCC_GetAHBPrescaler());
1040 * @brief Return PCLK1 clock frequency
1041 * @param HCLK_Frequency HCLK clock frequency
1042 * @retval PCLK1 clock frequency (in Hz)
1044 uint32_t RCC_GetPCLK1ClockFreq(uint32_t HCLK_Frequency)
1046 /* PCLK1 clock frequency */
1047 return __LL_RCC_CALC_PCLK1_FREQ(HCLK_Frequency, LL_RCC_GetAPB1Prescaler());
1051 * @brief Return PCLK2 clock frequency
1052 * @param HCLK_Frequency HCLK clock frequency
1053 * @retval PCLK2 clock frequency (in Hz)
1055 uint32_t RCC_GetPCLK2ClockFreq(uint32_t HCLK_Frequency)
1057 /* PCLK2 clock frequency */
1058 return __LL_RCC_CALC_PCLK2_FREQ(HCLK_Frequency, LL_RCC_GetAPB2Prescaler());
1062 * @brief Return PLL clock frequency used for system domain
1063 * @retval PLL clock frequency (in Hz)
1065 uint32_t RCC_PLL_GetFreqDomain_SYS(void)
1067 uint32_t pllinputfreq = 0U, pllsource = 0U;
1069 /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL divider) * PLL Multiplicator */
1071 /* Get PLL source */
1072 pllsource = LL_RCC_PLL_GetMainSource();
1074 switch (pllsource)
1076 #if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
1077 case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLL clock source */
1078 pllinputfreq = HSI_VALUE;
1079 #else
1080 case LL_RCC_PLLSOURCE_HSI_DIV_2: /* HSI used as PLL clock source */
1081 pllinputfreq = HSI_VALUE / 2U;
1082 #endif /* RCC_PLLSRC_PREDIV1_SUPPORT */
1083 break;
1085 case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLL clock source */
1086 pllinputfreq = HSE_VALUE;
1087 break;
1089 default:
1090 #if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
1091 pllinputfreq = HSI_VALUE;
1092 #else
1093 pllinputfreq = HSI_VALUE / 2U;
1094 #endif /* RCC_PLLSRC_PREDIV1_SUPPORT */
1095 break;
1097 #if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
1098 return __LL_RCC_CALC_PLLCLK_FREQ(pllinputfreq, LL_RCC_PLL_GetMultiplicator(), LL_RCC_PLL_GetPrediv());
1099 #else
1100 return __LL_RCC_CALC_PLLCLK_FREQ((pllinputfreq / (LL_RCC_PLL_GetPrediv() + 1U)), LL_RCC_PLL_GetMultiplicator());
1101 #endif /* RCC_PLLSRC_PREDIV1_SUPPORT */
1104 * @}
1108 * @}
1111 #endif /* defined(RCC) */
1114 * @}
1117 #endif /* USE_FULL_LL_DRIVER */
1119 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/