2 ******************************************************************************
3 * @file stm32f1xx_ll_rcc.c
4 * @author MCD Application Team
7 * @brief RCC LL module driver.
8 ******************************************************************************
11 * <h2><center>© COPYRIGHT(c) 2016 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 "stm32f1xx_ll_rcc.h"
41 #ifdef USE_FULL_ASSERT
42 #include "stm32_assert.h"
44 #define assert_param(expr) ((void)0U)
45 #endif /* USE_FULL_ASSERT */
46 /** @addtogroup STM32F1xx_LL_Driver
52 /** @defgroup RCC_LL RCC
56 /* Private types -------------------------------------------------------------*/
57 /* Private variables ---------------------------------------------------------*/
58 /* Private constants ---------------------------------------------------------*/
59 /* Private macros ------------------------------------------------------------*/
60 /** @addtogroup RCC_LL_Private_Macros
63 #if defined(RCC_PLLI2S_SUPPORT)
64 #define IS_LL_RCC_I2S_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_I2S2_CLKSOURCE) \
65 || ((__VALUE__) == LL_RCC_I2S3_CLKSOURCE))
66 #endif /* RCC_PLLI2S_SUPPORT */
68 #if defined(USB) || defined(USB_OTG_FS)
69 #define IS_LL_RCC_USB_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_USB_CLKSOURCE))
72 #define IS_LL_RCC_ADC_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_ADC_CLKSOURCE))
77 /* Private function prototypes -----------------------------------------------*/
78 /** @defgroup RCC_LL_Private_Functions RCC Private functions
81 uint32_t RCC_GetSystemClockFreq(void);
82 uint32_t RCC_GetHCLKClockFreq(uint32_t SYSCLK_Frequency
);
83 uint32_t RCC_GetPCLK1ClockFreq(uint32_t HCLK_Frequency
);
84 uint32_t RCC_GetPCLK2ClockFreq(uint32_t HCLK_Frequency
);
85 uint32_t RCC_PLL_GetFreqDomain_SYS(void);
86 #if defined(RCC_PLLI2S_SUPPORT)
87 uint32_t RCC_PLLI2S_GetFreqDomain_I2S(void);
88 #endif /* RCC_PLLI2S_SUPPORT */
89 #if defined(RCC_PLL2_SUPPORT)
90 uint32_t RCC_PLL2_GetFreqClockFreq(void);
91 #endif /* RCC_PLL2_SUPPORT */
96 /* Exported functions --------------------------------------------------------*/
97 /** @addtogroup RCC_LL_Exported_Functions
101 /** @addtogroup RCC_LL_EF_Init
106 * @brief Reset the RCC clock configuration to the default reset state.
107 * @note The default reset state of the clock configuration is given below:
108 * - HSI ON and used as system clock source
109 * - HSE PLL, PLL2, PLL3 OFF
110 * - AHB, APB1 and APB2 prescaler set to 1.
112 * - All interrupts disabled
113 * @note This function doesn't modify the configuration of the
114 * - Peripheral clocks
115 * - LSI, LSE and RTC clocks
116 * @retval An ErrorStatus enumeration value:
117 * - SUCCESS: RCC registers are de-initialized
118 * - ERROR: not applicable
120 ErrorStatus
LL_RCC_DeInit(void)
122 uint32_t vl_mask
= 0U;
127 /* Reset SW, HPRE, PPRE, MCOSEL, PLLXTPRE, PLLSRC and ADCPRE bits */
128 vl_mask
= 0xFFFFFFFFU
;
129 CLEAR_BIT(vl_mask
, (RCC_CFGR_SW
| RCC_CFGR_HPRE
| RCC_CFGR_PPRE1
| RCC_CFGR_PPRE2
| RCC_CFGR_MCOSEL
|\
130 RCC_CFGR_PLLXTPRE
| RCC_CFGR_PLLSRC
| RCC_CFGR_ADCPRE
));
133 /* Reset USBPRE bit */
134 CLEAR_BIT(vl_mask
, RCC_CFGR_USBPRE
);
135 #elif defined(USB_OTG_FS)
136 /* Reset OTGFSPRE bit */
137 CLEAR_BIT(vl_mask
, RCC_CFGR_OTGFSPRE
);
140 #if defined(RCC_CFGR_PLLMULL2)
141 /* Set PLL multiplication factor to 2 */
142 vl_mask
|= RCC_CFGR_PLLMULL2
;
144 /* Set PLL multiplication factor to 4 */
145 vl_mask
|= RCC_CFGR_PLLMULL4
;
146 #endif /* RCC_CFGR_PLLMULL2 */
148 LL_RCC_WriteReg(CFGR
, vl_mask
);
150 /* Reset HSEON, HSEBYP, CSSON, PLLON bits */
151 vl_mask
= 0xFFFFFFFFU
;
152 CLEAR_BIT(vl_mask
, (RCC_CR_PLLON
| RCC_CR_CSSON
| RCC_CR_HSEON
| RCC_CR_HSEBYP
));
154 #if defined(RCC_CR_PLL2ON)
155 /* Reset PLL2ON bit */
156 CLEAR_BIT(vl_mask
, RCC_CR_PLL2ON
);
157 #endif /* RCC_CR_PLL2ON */
159 #if defined(RCC_CR_PLL3ON)
160 /* Reset PLL3ON bit */
161 CLEAR_BIT(vl_mask
, RCC_CR_PLL3ON
);
162 #endif /* RCC_CR_PLL3ON */
164 LL_RCC_WriteReg(CR
, vl_mask
);
166 /* Set HSITRIM bits to the reset value */
167 LL_RCC_HSI_SetCalibTrimming(0x10U
);
169 #if defined(RCC_CFGR2_PREDIV1)
170 /* Reset CFGR2 register */
171 vl_mask
= 0x00000000U
;
173 #if defined(RCC_PLL2_SUPPORT)
174 /* Set PLL2 multiplication factor to 8 */
175 vl_mask
|= RCC_CFGR2_PLL2MUL8
;
176 #endif /* RCC_PLL2_SUPPORT */
178 #if defined(RCC_PLLI2S_SUPPORT)
179 /* Set PLL3 multiplication factor to 8 */
180 vl_mask
|= RCC_CFGR2_PLL3MUL8
;
181 #endif /* RCC_PLLI2S_SUPPORT */
183 LL_RCC_WriteReg(CFGR2
, vl_mask
);
184 #endif /* RCC_CFGR2_PREDIV1 */
186 /* Disable all interrupts */
187 LL_RCC_WriteReg(CIR
, 0x00000000U
);
196 /** @addtogroup RCC_LL_EF_Get_Freq
197 * @brief Return the frequencies of different on chip clocks; System, AHB, APB1 and APB2 buses clocks
198 * and different peripheral clocks available on the device.
199 * @note If SYSCLK source is HSI, function returns values based on HSI_VALUE(**)
200 * @note If SYSCLK source is HSE, function returns values based on HSE_VALUE(***)
201 * @note If SYSCLK source is PLL, function returns values based on
202 * HSI_VALUE(**) or HSE_VALUE(***) multiplied/divided by the PLL factors.
203 * @note (**) HSI_VALUE is a defined constant but the real value may vary
204 * depending on the variations in voltage and temperature.
205 * @note (***) HSE_VALUE is a defined constant, user has to ensure that
206 * HSE_VALUE is same as the real frequency of the crystal used.
207 * Otherwise, this function may have wrong result.
208 * @note The result of this function could be incorrect when using fractional
209 * value for HSE crystal.
210 * @note This function can be used by the user application to compute the
211 * baud-rate for the communication peripherals or configure other parameters.
216 * @brief Return the frequencies of different on chip clocks; System, AHB, APB1 and APB2 buses clocks
217 * @note Each time SYSCLK, HCLK, PCLK1 and/or PCLK2 clock changes, this function
218 * must be called to update structure fields. Otherwise, any
219 * configuration based on this function will be incorrect.
220 * @param RCC_Clocks pointer to a @ref LL_RCC_ClocksTypeDef structure which will hold the clocks frequencies
223 void LL_RCC_GetSystemClocksFreq(LL_RCC_ClocksTypeDef
*RCC_Clocks
)
225 /* Get SYSCLK frequency */
226 RCC_Clocks
->SYSCLK_Frequency
= RCC_GetSystemClockFreq();
228 /* HCLK clock frequency */
229 RCC_Clocks
->HCLK_Frequency
= RCC_GetHCLKClockFreq(RCC_Clocks
->SYSCLK_Frequency
);
231 /* PCLK1 clock frequency */
232 RCC_Clocks
->PCLK1_Frequency
= RCC_GetPCLK1ClockFreq(RCC_Clocks
->HCLK_Frequency
);
234 /* PCLK2 clock frequency */
235 RCC_Clocks
->PCLK2_Frequency
= RCC_GetPCLK2ClockFreq(RCC_Clocks
->HCLK_Frequency
);
238 #if defined(RCC_CFGR2_I2S2SRC)
240 * @brief Return I2Sx clock frequency
241 * @param I2SxSource This parameter can be one of the following values:
242 * @arg @ref LL_RCC_I2S2_CLKSOURCE
243 * @arg @ref LL_RCC_I2S3_CLKSOURCE
244 * @retval I2S clock frequency (in Hz)
246 uint32_t LL_RCC_GetI2SClockFreq(uint32_t I2SxSource
)
248 uint32_t i2s_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
250 /* Check parameter */
251 assert_param(IS_LL_RCC_I2S_CLKSOURCE(I2SxSource
));
253 /* I2S1CLK clock frequency */
254 switch (LL_RCC_GetI2SClockSource(I2SxSource
))
256 case LL_RCC_I2S2_CLKSOURCE_SYSCLK
: /*!< System clock selected as I2S clock source */
257 case LL_RCC_I2S3_CLKSOURCE_SYSCLK
:
258 i2s_frequency
= RCC_GetSystemClockFreq();
261 case LL_RCC_I2S2_CLKSOURCE_PLLI2S_VCO
: /*!< PLLI2S oscillator clock selected as I2S clock source */
262 case LL_RCC_I2S3_CLKSOURCE_PLLI2S_VCO
:
264 i2s_frequency
= RCC_PLLI2S_GetFreqDomain_I2S() * 2U;
268 return i2s_frequency
;
270 #endif /* RCC_CFGR2_I2S2SRC */
272 #if defined(USB) || defined(USB_OTG_FS)
274 * @brief Return USBx clock frequency
275 * @param USBxSource This parameter can be one of the following values:
276 * @arg @ref LL_RCC_USB_CLKSOURCE
277 * @retval USB clock frequency (in Hz)
278 * @arg @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator (HSI), HSE or PLL is not ready
280 uint32_t LL_RCC_GetUSBClockFreq(uint32_t USBxSource
)
282 uint32_t usb_frequency
= LL_RCC_PERIPH_FREQUENCY_NO
;
284 /* Check parameter */
285 assert_param(IS_LL_RCC_USB_CLKSOURCE(USBxSource
));
287 /* USBCLK clock frequency */
288 switch (LL_RCC_GetUSBClockSource(USBxSource
))
290 #if defined(RCC_CFGR_USBPRE)
291 case LL_RCC_USB_CLKSOURCE_PLL
: /* PLL clock used as USB clock source */
292 if (LL_RCC_PLL_IsReady())
294 usb_frequency
= RCC_PLL_GetFreqDomain_SYS();
298 case LL_RCC_USB_CLKSOURCE_PLL_DIV_1_5
: /* PLL clock divided by 1.5 used as USB clock source */
300 if (LL_RCC_PLL_IsReady())
302 usb_frequency
= (RCC_PLL_GetFreqDomain_SYS() * 3U) / 2U;
305 #endif /* RCC_CFGR_USBPRE */
306 #if defined(RCC_CFGR_OTGFSPRE)
310 case LL_RCC_USB_CLKSOURCE_PLL_DIV_2
: /* PLL clock used as USB clock source */
311 if (LL_RCC_PLL_IsReady())
313 usb_frequency
= RCC_PLL_GetFreqDomain_SYS();
318 = (2 x PLLCLK) / 3 */
319 case LL_RCC_USB_CLKSOURCE_PLL_DIV_3
: /* PLL clock divided by 3 used as USB clock source */
321 if (LL_RCC_PLL_IsReady())
323 usb_frequency
= (RCC_PLL_GetFreqDomain_SYS() * 2U) / 3U;
326 #endif /* RCC_CFGR_OTGFSPRE */
329 return usb_frequency
;
334 * @brief Return ADCx clock frequency
335 * @param ADCxSource This parameter can be one of the following values:
336 * @arg @ref LL_RCC_ADC_CLKSOURCE
337 * @retval ADC clock frequency (in Hz)
339 uint32_t LL_RCC_GetADCClockFreq(uint32_t ADCxSource
)
341 uint32_t adc_prescaler
= 0U;
342 uint32_t adc_frequency
= 0U;
344 /* Check parameter */
345 assert_param(IS_LL_RCC_ADC_CLKSOURCE(ADCxSource
));
347 /* Get ADC prescaler */
348 adc_prescaler
= LL_RCC_GetADCClockSource(ADCxSource
);
350 /* ADC frequency = PCLK2 frequency / ADC prescaler (2, 4, 6 or 8) */
351 adc_frequency
= RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()))
352 / (((adc_prescaler
>> POSITION_VAL(ADCxSource
)) + 1U) * 2U);
354 return adc_frequency
;
365 /** @addtogroup RCC_LL_Private_Functions
370 * @brief Return SYSTEM clock frequency
371 * @retval SYSTEM clock frequency (in Hz)
373 uint32_t RCC_GetSystemClockFreq(void)
375 uint32_t frequency
= 0U;
377 /* Get SYSCLK source -------------------------------------------------------*/
378 switch (LL_RCC_GetSysClkSource())
380 case LL_RCC_SYS_CLKSOURCE_STATUS_HSI
: /* HSI used as system clock source */
381 frequency
= HSI_VALUE
;
384 case LL_RCC_SYS_CLKSOURCE_STATUS_HSE
: /* HSE used as system clock source */
385 frequency
= HSE_VALUE
;
388 case LL_RCC_SYS_CLKSOURCE_STATUS_PLL
: /* PLL used as system clock source */
389 frequency
= RCC_PLL_GetFreqDomain_SYS();
393 frequency
= HSI_VALUE
;
401 * @brief Return HCLK clock frequency
402 * @param SYSCLK_Frequency SYSCLK clock frequency
403 * @retval HCLK clock frequency (in Hz)
405 uint32_t RCC_GetHCLKClockFreq(uint32_t SYSCLK_Frequency
)
407 /* HCLK clock frequency */
408 return __LL_RCC_CALC_HCLK_FREQ(SYSCLK_Frequency
, LL_RCC_GetAHBPrescaler());
412 * @brief Return PCLK1 clock frequency
413 * @param HCLK_Frequency HCLK clock frequency
414 * @retval PCLK1 clock frequency (in Hz)
416 uint32_t RCC_GetPCLK1ClockFreq(uint32_t HCLK_Frequency
)
418 /* PCLK1 clock frequency */
419 return __LL_RCC_CALC_PCLK1_FREQ(HCLK_Frequency
, LL_RCC_GetAPB1Prescaler());
423 * @brief Return PCLK2 clock frequency
424 * @param HCLK_Frequency HCLK clock frequency
425 * @retval PCLK2 clock frequency (in Hz)
427 uint32_t RCC_GetPCLK2ClockFreq(uint32_t HCLK_Frequency
)
429 /* PCLK2 clock frequency */
430 return __LL_RCC_CALC_PCLK2_FREQ(HCLK_Frequency
, LL_RCC_GetAPB2Prescaler());
434 * @brief Return PLL clock frequency used for system domain
435 * @retval PLL clock frequency (in Hz)
437 uint32_t RCC_PLL_GetFreqDomain_SYS(void)
439 uint32_t pllinputfreq
= 0U, pllsource
= 0U;
441 /* PLL_VCO = (HSE_VALUE, HSI_VALUE or PLL2 / PLL Predivider) * PLL Multiplicator */
444 pllsource
= LL_RCC_PLL_GetMainSource();
448 case LL_RCC_PLLSOURCE_HSI_DIV_2
: /* HSI used as PLL clock source */
449 pllinputfreq
= HSI_VALUE
/ 2U;
452 case LL_RCC_PLLSOURCE_HSE
: /* HSE used as PLL clock source */
453 pllinputfreq
= HSE_VALUE
/ (LL_RCC_PLL_GetPrediv() + 1U);
456 #if defined(RCC_PLL2_SUPPORT)
457 case LL_RCC_PLLSOURCE_PLL2
: /* PLL2 used as PLL clock source */
458 pllinputfreq
= RCC_PLL2_GetFreqClockFreq() / (LL_RCC_PLL_GetPrediv() + 1U);
460 #endif /* RCC_PLL2_SUPPORT */
463 pllinputfreq
= HSI_VALUE
/ 2U;
466 return __LL_RCC_CALC_PLLCLK_FREQ(pllinputfreq
, LL_RCC_PLL_GetMultiplicator());
469 #if defined(RCC_PLL2_SUPPORT)
471 * @brief Return PLL clock frequency used for system domain
472 * @retval PLL clock frequency (in Hz)
474 uint32_t RCC_PLL2_GetFreqClockFreq(void)
476 return __LL_RCC_CALC_PLL2CLK_FREQ(HSE_VALUE
, LL_RCC_PLL2_GetMultiplicator(), LL_RCC_HSE_GetPrediv2());
478 #endif /* RCC_PLL2_SUPPORT */
480 #if defined(RCC_PLLI2S_SUPPORT)
482 * @brief Return PLL clock frequency used for system domain
483 * @retval PLL clock frequency (in Hz)
485 uint32_t RCC_PLLI2S_GetFreqDomain_I2S(void)
487 return __LL_RCC_CALC_PLLI2SCLK_FREQ(HSE_VALUE
, LL_RCC_PLLI2S_GetMultiplicator(), LL_RCC_HSE_GetPrediv2());
489 #endif /* RCC_PLLI2S_SUPPORT */
499 #endif /* defined(RCC) */
505 #endif /* USE_FULL_LL_DRIVER */
507 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/