2 ******************************************************************************
3 * @file stm32f4xx_ll_utils.c
4 * @author MCD Application Team
7 * @brief UTILS 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 /* Includes ------------------------------------------------------------------*/
38 #include "stm32f4xx_ll_utils.h"
39 #include "stm32f4xx_ll_rcc.h"
40 #include "stm32f4xx_ll_system.h"
41 #include "stm32f4xx_ll_pwr.h"
42 #ifdef USE_FULL_ASSERT
43 #include "stm32_assert.h"
45 #define assert_param(expr) ((void)0U)
46 #endif /* USE_FULL_ASSERT */
48 /** @addtogroup STM32F4xx_LL_Driver
52 /** @addtogroup UTILS_LL
56 /* Private types -------------------------------------------------------------*/
57 /* Private variables ---------------------------------------------------------*/
58 /* Private constants ---------------------------------------------------------*/
59 /** @addtogroup UTILS_LL_Private_Constants
62 #if defined(RCC_MAX_FREQUENCY_SCALE1)
63 #define UTILS_MAX_FREQUENCY_SCALE1 RCC_MAX_FREQUENCY /*!< Maximum frequency for system clock at power scale1, in Hz */
64 #endif /*RCC_MAX_FREQUENCY_SCALE1 */
65 #define UTILS_MAX_FREQUENCY_SCALE2 RCC_MAX_FREQUENCY_SCALE2 /*!< Maximum frequency for system clock at power scale2, in Hz */
66 #if defined(RCC_MAX_FREQUENCY_SCALE3)
67 #define UTILS_MAX_FREQUENCY_SCALE3 RCC_MAX_FREQUENCY_SCALE3 /*!< Maximum frequency for system clock at power scale3, in Hz */
68 #endif /* MAX_FREQUENCY_SCALE3 */
70 /* Defines used for PLL range */
71 #define UTILS_PLLVCO_INPUT_MIN RCC_PLLVCO_INPUT_MIN /*!< Frequency min for PLLVCO input, in Hz */
72 #define UTILS_PLLVCO_INPUT_MAX RCC_PLLVCO_INPUT_MAX /*!< Frequency max for PLLVCO input, in Hz */
73 #define UTILS_PLLVCO_OUTPUT_MIN RCC_PLLVCO_OUTPUT_MIN /*!< Frequency min for PLLVCO output, in Hz */
74 #define UTILS_PLLVCO_OUTPUT_MAX RCC_PLLVCO_OUTPUT_MAX /*!< Frequency max for PLLVCO output, in Hz */
76 /* Defines used for HSE range */
77 #define UTILS_HSE_FREQUENCY_MIN 4000000U /*!< Frequency min for HSE frequency, in Hz */
78 #define UTILS_HSE_FREQUENCY_MAX 26000000U /*!< Frequency max for HSE frequency, in Hz */
80 /* Defines used for FLASH latency according to HCLK Frequency */
81 #if defined(FLASH_SCALE1_LATENCY1_FREQ)
82 #define UTILS_SCALE1_LATENCY1_FREQ FLASH_SCALE1_LATENCY1_FREQ /*!< HCLK frequency to set FLASH latency 1 in power scale 1 */
84 #if defined(FLASH_SCALE1_LATENCY2_FREQ)
85 #define UTILS_SCALE1_LATENCY2_FREQ FLASH_SCALE1_LATENCY2_FREQ /*!< HCLK frequency to set FLASH latency 2 in power scale 1 */
87 #if defined(FLASH_SCALE1_LATENCY3_FREQ)
88 #define UTILS_SCALE1_LATENCY3_FREQ FLASH_SCALE1_LATENCY3_FREQ /*!< HCLK frequency to set FLASH latency 3 in power scale 1 */
90 #if defined(FLASH_SCALE1_LATENCY4_FREQ)
91 #define UTILS_SCALE1_LATENCY4_FREQ FLASH_SCALE1_LATENCY4_FREQ /*!< HCLK frequency to set FLASH latency 4 in power scale 1 */
93 #if defined(FLASH_SCALE1_LATENCY5_FREQ)
94 #define UTILS_SCALE1_LATENCY5_FREQ FLASH_SCALE1_LATENCY5_FREQ /*!< HCLK frequency to set FLASH latency 5 in power scale 1 */
96 #define UTILS_SCALE2_LATENCY1_FREQ FLASH_SCALE2_LATENCY1_FREQ /*!< HCLK frequency to set FLASH latency 1 in power scale 2 */
97 #define UTILS_SCALE2_LATENCY2_FREQ FLASH_SCALE2_LATENCY2_FREQ /*!< HCLK frequency to set FLASH latency 2 in power scale 2 */
98 #if defined(FLASH_SCALE2_LATENCY3_FREQ)
99 #define UTILS_SCALE2_LATENCY3_FREQ FLASH_SCALE2_LATENCY3_FREQ /*!< HCLK frequency to set FLASH latency 2 in power scale 2 */
101 #if defined(FLASH_SCALE2_LATENCY4_FREQ)
102 #define UTILS_SCALE2_LATENCY4_FREQ FLASH_SCALE2_LATENCY4_FREQ /*!< HCLK frequency to set FLASH latency 4 in power scale 2 */
104 #if defined(FLASH_SCALE2_LATENCY5_FREQ)
105 #define UTILS_SCALE2_LATENCY5_FREQ FLASH_SCALE2_LATENCY5_FREQ /*!< HCLK frequency to set FLASH latency 5 in power scale 2 */
107 #if defined(FLASH_SCALE3_LATENCY1_FREQ)
108 #define UTILS_SCALE3_LATENCY1_FREQ FLASH_SCALE3_LATENCY1_FREQ /*!< HCLK frequency to set FLASH latency 1 in power scale 3 */
110 #if defined(FLASH_SCALE3_LATENCY2_FREQ)
111 #define UTILS_SCALE3_LATENCY2_FREQ FLASH_SCALE3_LATENCY2_FREQ /*!< HCLK frequency to set FLASH latency 2 in power scale 3 */
113 #if defined(FLASH_SCALE3_LATENCY3_FREQ)
114 #define UTILS_SCALE3_LATENCY3_FREQ FLASH_SCALE3_LATENCY3_FREQ /*!< HCLK frequency to set FLASH latency 3 in power scale 3 */
116 #if defined(FLASH_SCALE3_LATENCY4_FREQ)
117 #define UTILS_SCALE3_LATENCY4_FREQ FLASH_SCALE3_LATENCY4_FREQ /*!< HCLK frequency to set FLASH latency 4 in power scale 3 */
119 #if defined(FLASH_SCALE3_LATENCY5_FREQ)
120 #define UTILS_SCALE3_LATENCY5_FREQ FLASH_SCALE3_LATENCY5_FREQ /*!< HCLK frequency to set FLASH latency 5 in power scale 3 */
126 /* Private macros ------------------------------------------------------------*/
127 /** @addtogroup UTILS_LL_Private_Macros
130 #define IS_LL_UTILS_SYSCLK_DIV(__VALUE__) (((__VALUE__) == LL_RCC_SYSCLK_DIV_1) \
131 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_2) \
132 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_4) \
133 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_8) \
134 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_16) \
135 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_64) \
136 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_128) \
137 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_256) \
138 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_512))
140 #define IS_LL_UTILS_APB1_DIV(__VALUE__) (((__VALUE__) == LL_RCC_APB1_DIV_1) \
141 || ((__VALUE__) == LL_RCC_APB1_DIV_2) \
142 || ((__VALUE__) == LL_RCC_APB1_DIV_4) \
143 || ((__VALUE__) == LL_RCC_APB1_DIV_8) \
144 || ((__VALUE__) == LL_RCC_APB1_DIV_16))
146 #define IS_LL_UTILS_APB2_DIV(__VALUE__) (((__VALUE__) == LL_RCC_APB2_DIV_1) \
147 || ((__VALUE__) == LL_RCC_APB2_DIV_2) \
148 || ((__VALUE__) == LL_RCC_APB2_DIV_4) \
149 || ((__VALUE__) == LL_RCC_APB2_DIV_8) \
150 || ((__VALUE__) == LL_RCC_APB2_DIV_16))
152 #define IS_LL_UTILS_PLLM_VALUE(__VALUE__) (((__VALUE__) == LL_RCC_PLLM_DIV_2) \
153 || ((__VALUE__) == LL_RCC_PLLM_DIV_3) \
154 || ((__VALUE__) == LL_RCC_PLLM_DIV_4) \
155 || ((__VALUE__) == LL_RCC_PLLM_DIV_5) \
156 || ((__VALUE__) == LL_RCC_PLLM_DIV_6) \
157 || ((__VALUE__) == LL_RCC_PLLM_DIV_7) \
158 || ((__VALUE__) == LL_RCC_PLLM_DIV_8) \
159 || ((__VALUE__) == LL_RCC_PLLM_DIV_9) \
160 || ((__VALUE__) == LL_RCC_PLLM_DIV_10) \
161 || ((__VALUE__) == LL_RCC_PLLM_DIV_11) \
162 || ((__VALUE__) == LL_RCC_PLLM_DIV_12) \
163 || ((__VALUE__) == LL_RCC_PLLM_DIV_13) \
164 || ((__VALUE__) == LL_RCC_PLLM_DIV_14) \
165 || ((__VALUE__) == LL_RCC_PLLM_DIV_15) \
166 || ((__VALUE__) == LL_RCC_PLLM_DIV_16) \
167 || ((__VALUE__) == LL_RCC_PLLM_DIV_17) \
168 || ((__VALUE__) == LL_RCC_PLLM_DIV_18) \
169 || ((__VALUE__) == LL_RCC_PLLM_DIV_19) \
170 || ((__VALUE__) == LL_RCC_PLLM_DIV_20) \
171 || ((__VALUE__) == LL_RCC_PLLM_DIV_21) \
172 || ((__VALUE__) == LL_RCC_PLLM_DIV_22) \
173 || ((__VALUE__) == LL_RCC_PLLM_DIV_23) \
174 || ((__VALUE__) == LL_RCC_PLLM_DIV_24) \
175 || ((__VALUE__) == LL_RCC_PLLM_DIV_25) \
176 || ((__VALUE__) == LL_RCC_PLLM_DIV_26) \
177 || ((__VALUE__) == LL_RCC_PLLM_DIV_27) \
178 || ((__VALUE__) == LL_RCC_PLLM_DIV_28) \
179 || ((__VALUE__) == LL_RCC_PLLM_DIV_29) \
180 || ((__VALUE__) == LL_RCC_PLLM_DIV_30) \
181 || ((__VALUE__) == LL_RCC_PLLM_DIV_31) \
182 || ((__VALUE__) == LL_RCC_PLLM_DIV_32) \
183 || ((__VALUE__) == LL_RCC_PLLM_DIV_33) \
184 || ((__VALUE__) == LL_RCC_PLLM_DIV_34) \
185 || ((__VALUE__) == LL_RCC_PLLM_DIV_35) \
186 || ((__VALUE__) == LL_RCC_PLLM_DIV_36) \
187 || ((__VALUE__) == LL_RCC_PLLM_DIV_37) \
188 || ((__VALUE__) == LL_RCC_PLLM_DIV_38) \
189 || ((__VALUE__) == LL_RCC_PLLM_DIV_39) \
190 || ((__VALUE__) == LL_RCC_PLLM_DIV_40) \
191 || ((__VALUE__) == LL_RCC_PLLM_DIV_41) \
192 || ((__VALUE__) == LL_RCC_PLLM_DIV_42) \
193 || ((__VALUE__) == LL_RCC_PLLM_DIV_43) \
194 || ((__VALUE__) == LL_RCC_PLLM_DIV_44) \
195 || ((__VALUE__) == LL_RCC_PLLM_DIV_45) \
196 || ((__VALUE__) == LL_RCC_PLLM_DIV_46) \
197 || ((__VALUE__) == LL_RCC_PLLM_DIV_47) \
198 || ((__VALUE__) == LL_RCC_PLLM_DIV_48) \
199 || ((__VALUE__) == LL_RCC_PLLM_DIV_49) \
200 || ((__VALUE__) == LL_RCC_PLLM_DIV_50) \
201 || ((__VALUE__) == LL_RCC_PLLM_DIV_51) \
202 || ((__VALUE__) == LL_RCC_PLLM_DIV_52) \
203 || ((__VALUE__) == LL_RCC_PLLM_DIV_53) \
204 || ((__VALUE__) == LL_RCC_PLLM_DIV_54) \
205 || ((__VALUE__) == LL_RCC_PLLM_DIV_55) \
206 || ((__VALUE__) == LL_RCC_PLLM_DIV_56) \
207 || ((__VALUE__) == LL_RCC_PLLM_DIV_57) \
208 || ((__VALUE__) == LL_RCC_PLLM_DIV_58) \
209 || ((__VALUE__) == LL_RCC_PLLM_DIV_59) \
210 || ((__VALUE__) == LL_RCC_PLLM_DIV_60) \
211 || ((__VALUE__) == LL_RCC_PLLM_DIV_61) \
212 || ((__VALUE__) == LL_RCC_PLLM_DIV_62) \
213 || ((__VALUE__) == LL_RCC_PLLM_DIV_63))
215 #define IS_LL_UTILS_PLLN_VALUE(__VALUE__) ((RCC_PLLN_MIN_VALUE <= (__VALUE__)) && ((__VALUE__) <= RCC_PLLN_MAX_VALUE))
217 #define IS_LL_UTILS_PLLP_VALUE(__VALUE__) (((__VALUE__) == LL_RCC_PLLP_DIV_2) \
218 || ((__VALUE__) == LL_RCC_PLLP_DIV_4) \
219 || ((__VALUE__) == LL_RCC_PLLP_DIV_6) \
220 || ((__VALUE__) == LL_RCC_PLLP_DIV_8))
222 #define IS_LL_UTILS_PLLVCO_INPUT(__VALUE__) ((UTILS_PLLVCO_INPUT_MIN <= (__VALUE__)) && ((__VALUE__) <= UTILS_PLLVCO_INPUT_MAX))
224 #define IS_LL_UTILS_PLLVCO_OUTPUT(__VALUE__) ((UTILS_PLLVCO_OUTPUT_MIN <= (__VALUE__)) && ((__VALUE__) <= UTILS_PLLVCO_OUTPUT_MAX))
226 #if !defined(RCC_MAX_FREQUENCY_SCALE1)
227 #define IS_LL_UTILS_PLL_FREQUENCY(__VALUE__) ((LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE2) ? ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE2) : \
228 ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE3))
230 #elif defined(RCC_MAX_FREQUENCY_SCALE3)
231 #define IS_LL_UTILS_PLL_FREQUENCY(__VALUE__) ((LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE1) ? ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE1) : \
232 (LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE2) ? ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE2) : \
233 ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE3))
236 #define IS_LL_UTILS_PLL_FREQUENCY(__VALUE__) ((LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE1) ? ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE1) : \
237 ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE2))
239 #endif /* RCC_MAX_FREQUENCY_SCALE1*/
240 #define IS_LL_UTILS_HSE_BYPASS(__STATE__) (((__STATE__) == LL_UTILS_HSEBYPASS_ON) \
241 || ((__STATE__) == LL_UTILS_HSEBYPASS_OFF))
243 #define IS_LL_UTILS_HSE_FREQUENCY(__FREQUENCY__) (((__FREQUENCY__) >= UTILS_HSE_FREQUENCY_MIN) && ((__FREQUENCY__) <= UTILS_HSE_FREQUENCY_MAX))
247 /* Private function prototypes -----------------------------------------------*/
248 /** @defgroup UTILS_LL_Private_Functions UTILS Private functions
251 static uint32_t UTILS_GetPLLOutputFrequency(uint32_t PLL_InputFrequency
,
252 LL_UTILS_PLLInitTypeDef
*UTILS_PLLInitStruct
);
253 static ErrorStatus
UTILS_SetFlashLatency(uint32_t HCLK_Frequency
);
254 static ErrorStatus
UTILS_EnablePLLAndSwitchSystem(uint32_t SYSCLK_Frequency
, LL_UTILS_ClkInitTypeDef
*UTILS_ClkInitStruct
);
255 static ErrorStatus
UTILS_PLL_IsBusy(void);
260 /* Exported functions --------------------------------------------------------*/
261 /** @addtogroup UTILS_LL_Exported_Functions
265 /** @addtogroup UTILS_LL_EF_DELAY
270 * @brief This function configures the Cortex-M SysTick source to have 1ms time base.
271 * @note When a RTOS is used, it is recommended to avoid changing the Systick
272 * configuration by calling this function, for a delay use rather osDelay RTOS service.
273 * @param HCLKFrequency HCLK frequency in Hz
274 * @note HCLK frequency can be calculated thanks to RCC helper macro or function @ref LL_RCC_GetSystemClocksFreq
277 void LL_Init1msTick(uint32_t HCLKFrequency
)
279 /* Use frequency provided in argument */
280 LL_InitTick(HCLKFrequency
, 1000U);
284 * @brief This function provides accurate delay (in milliseconds) based
285 * on SysTick counter flag
286 * @note When a RTOS is used, it is recommended to avoid using blocking delay
287 * and use rather osDelay service.
288 * @note To respect 1ms timebase, user should call @ref LL_Init1msTick function which
289 * will configure Systick to 1ms
290 * @param Delay specifies the delay time length, in milliseconds.
293 void LL_mDelay(uint32_t Delay
)
295 __IO
uint32_t tmp
= SysTick
->CTRL
; /* Clear the COUNTFLAG first */
296 /* Add this code to indicate that local variable is not used */
299 /* Add a period to guaranty minimum wait */
300 if(Delay
< LL_MAX_DELAY
)
307 if((SysTick
->CTRL
& SysTick_CTRL_COUNTFLAG_Msk
) != 0U)
318 /** @addtogroup UTILS_EF_SYSTEM
319 * @brief System Configuration functions
322 ===============================================================================
323 ##### System Configuration functions #####
324 ===============================================================================
326 System, AHB and APB buses clocks configuration
328 (+) The maximum frequency of the SYSCLK, HCLK, PCLK1 and PCLK2 is 180000000 Hz.
331 Depending on the device voltage range, the maximum frequency should be
332 adapted accordingly to the Refenece manual.
338 * @brief This function sets directly SystemCoreClock CMSIS variable.
339 * @note Variable can be calculated also through SystemCoreClockUpdate function.
340 * @param HCLKFrequency HCLK frequency in Hz (can be calculated thanks to RCC helper macro)
343 void LL_SetSystemCoreClock(uint32_t HCLKFrequency
)
345 /* HCLK clock frequency */
346 SystemCoreClock
= HCLKFrequency
;
350 * @brief This function configures system clock at maximum frequency with HSI as clock source of the PLL
351 * @note The application need to ensure that PLL is disabled.
352 * @note Function is based on the following formula:
353 * - PLL output frequency = (((HSI frequency / PLLM) * PLLN) / PLLP)
354 * - PLLM: ensure that the VCO input frequency ranges from @ref RCC_PLLVCO_INPUT_MIN to @ref RCC_PLLVCO_INPUT_MAX (PLLVCO_input = HSI frequency / PLLM)
355 * - PLLN: ensure that the VCO output frequency is between @ref RCC_PLLVCO_OUTPUT_MIN and @ref RCC_PLLVCO_OUTPUT_MAX (PLLVCO_output = PLLVCO_input * PLLN)
356 * - PLLP: ensure that max frequency at 180000000 Hz is reach (PLLVCO_output / PLLP)
357 * @param UTILS_PLLInitStruct pointer to a @ref LL_UTILS_PLLInitTypeDef structure that contains
358 * the configuration information for the PLL.
359 * @param UTILS_ClkInitStruct pointer to a @ref LL_UTILS_ClkInitTypeDef structure that contains
360 * the configuration information for the BUS prescalers.
361 * @retval An ErrorStatus enumeration value:
362 * - SUCCESS: Max frequency configuration done
363 * - ERROR: Max frequency configuration not done
365 ErrorStatus
LL_PLL_ConfigSystemClock_HSI(LL_UTILS_PLLInitTypeDef
*UTILS_PLLInitStruct
,
366 LL_UTILS_ClkInitTypeDef
*UTILS_ClkInitStruct
)
368 ErrorStatus status
= SUCCESS
;
369 uint32_t pllfreq
= 0U;
371 /* Check if one of the PLL is enabled */
372 if(UTILS_PLL_IsBusy() == SUCCESS
)
374 /* Calculate the new PLL output frequency */
375 pllfreq
= UTILS_GetPLLOutputFrequency(HSI_VALUE
, UTILS_PLLInitStruct
);
377 /* Enable HSI if not enabled */
378 if(LL_RCC_HSI_IsReady() != 1U)
381 while (LL_RCC_HSI_IsReady() != 1U)
383 /* Wait for HSI ready */
388 LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSI
, UTILS_PLLInitStruct
->PLLM
, UTILS_PLLInitStruct
->PLLN
,
389 UTILS_PLLInitStruct
->PLLP
);
391 /* Enable PLL and switch system clock to PLL */
392 status
= UTILS_EnablePLLAndSwitchSystem(pllfreq
, UTILS_ClkInitStruct
);
396 /* Current PLL configuration cannot be modified */
404 * @brief This function configures system clock with HSE as clock source of the PLL
405 * @note The application need to ensure that PLL is disabled.
406 * - PLL output frequency = (((HSI frequency / PLLM) * PLLN) / PLLP)
407 * - PLLM: ensure that the VCO input frequency ranges from @ref RCC_PLLVCO_INPUT_MIN to @ref RCC_PLLVCO_INPUT_MAX (PLLVCO_input = HSI frequency / PLLM)
408 * - PLLN: ensure that the VCO output frequency is between @ref RCC_PLLVCO_OUTPUT_MIN and @ref RCC_PLLVCO_OUTPUT_MAX (PLLVCO_output = PLLVCO_input * PLLN)
409 * - PLLP: ensure that max frequency at 180000000 Hz is reach (PLLVCO_output / PLLP)
410 * @param HSEFrequency Value between Min_Data = 4000000 and Max_Data = 26000000
411 * @param HSEBypass This parameter can be one of the following values:
412 * @arg @ref LL_UTILS_HSEBYPASS_ON
413 * @arg @ref LL_UTILS_HSEBYPASS_OFF
414 * @param UTILS_PLLInitStruct pointer to a @ref LL_UTILS_PLLInitTypeDef structure that contains
415 * the configuration information for the PLL.
416 * @param UTILS_ClkInitStruct pointer to a @ref LL_UTILS_ClkInitTypeDef structure that contains
417 * the configuration information for the BUS prescalers.
418 * @retval An ErrorStatus enumeration value:
419 * - SUCCESS: Max frequency configuration done
420 * - ERROR: Max frequency configuration not done
422 ErrorStatus
LL_PLL_ConfigSystemClock_HSE(uint32_t HSEFrequency
, uint32_t HSEBypass
,
423 LL_UTILS_PLLInitTypeDef
*UTILS_PLLInitStruct
, LL_UTILS_ClkInitTypeDef
*UTILS_ClkInitStruct
)
425 ErrorStatus status
= SUCCESS
;
426 uint32_t pllfreq
= 0U;
428 /* Check the parameters */
429 assert_param(IS_LL_UTILS_HSE_FREQUENCY(HSEFrequency
));
430 assert_param(IS_LL_UTILS_HSE_BYPASS(HSEBypass
));
432 /* Check if one of the PLL is enabled */
433 if(UTILS_PLL_IsBusy() == SUCCESS
)
435 /* Calculate the new PLL output frequency */
436 pllfreq
= UTILS_GetPLLOutputFrequency(HSEFrequency
, UTILS_PLLInitStruct
);
438 /* Enable HSE if not enabled */
439 if(LL_RCC_HSE_IsReady() != 1U)
441 /* Check if need to enable HSE bypass feature or not */
442 if(HSEBypass
== LL_UTILS_HSEBYPASS_ON
)
444 LL_RCC_HSE_EnableBypass();
448 LL_RCC_HSE_DisableBypass();
453 while (LL_RCC_HSE_IsReady() != 1U)
455 /* Wait for HSE ready */
460 LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSE
, UTILS_PLLInitStruct
->PLLM
, UTILS_PLLInitStruct
->PLLN
,
461 UTILS_PLLInitStruct
->PLLP
);
463 /* Enable PLL and switch system clock to PLL */
464 status
= UTILS_EnablePLLAndSwitchSystem(pllfreq
, UTILS_ClkInitStruct
);
468 /* Current PLL configuration cannot be modified */
483 /** @addtogroup UTILS_LL_Private_Functions
487 * @brief Update number of Flash wait states in line with new frequency and current
489 * @note This Function support ONLY devices with supply voltage (voltage range) between 2.7V and 3.6V
490 * @param HCLK_Frequency HCLK frequency
491 * @retval An ErrorStatus enumeration value:
492 * - SUCCESS: Latency has been modified
493 * - ERROR: Latency cannot be modified
495 static ErrorStatus
UTILS_SetFlashLatency(uint32_t HCLK_Frequency
)
497 ErrorStatus status
= SUCCESS
;
499 uint32_t latency
= LL_FLASH_LATENCY_0
; /* default value 0WS */
501 /* Frequency cannot be equal to 0 */
502 if(HCLK_Frequency
== 0U)
508 if(LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE1
)
510 #if defined (UTILS_SCALE1_LATENCY5_FREQ)
511 if((HCLK_Frequency
> UTILS_SCALE1_LATENCY5_FREQ
)&&(latency
== LL_FLASH_LATENCY_0
))
513 latency
= LL_FLASH_LATENCY_5
;
515 #endif /*UTILS_SCALE1_LATENCY5_FREQ */
516 #if defined (UTILS_SCALE1_LATENCY4_FREQ)
517 if((HCLK_Frequency
> UTILS_SCALE1_LATENCY4_FREQ
)&&(latency
== LL_FLASH_LATENCY_0
))
519 latency
= LL_FLASH_LATENCY_4
;
521 #endif /* UTILS_SCALE1_LATENCY4_FREQ */
522 #if defined (UTILS_SCALE1_LATENCY3_FREQ)
523 if((HCLK_Frequency
> UTILS_SCALE1_LATENCY3_FREQ
)&&(latency
== LL_FLASH_LATENCY_0
))
525 latency
= LL_FLASH_LATENCY_3
;
527 #endif /* UTILS_SCALE1_LATENCY3_FREQ */
528 #if defined (UTILS_SCALE1_LATENCY2_FREQ)
529 if((HCLK_Frequency
> UTILS_SCALE1_LATENCY2_FREQ
)&&(latency
== LL_FLASH_LATENCY_0
))
531 latency
= LL_FLASH_LATENCY_2
;
535 if((HCLK_Frequency
> UTILS_SCALE1_LATENCY1_FREQ
)&&(latency
== LL_FLASH_LATENCY_0
))
537 latency
= LL_FLASH_LATENCY_1
;
540 #endif /* UTILS_SCALE1_LATENCY2_FREQ */
542 if(LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE2
)
544 #if defined (UTILS_SCALE2_LATENCY5_FREQ)
545 if((HCLK_Frequency
> UTILS_SCALE2_LATENCY5_FREQ
)&&(latency
== LL_FLASH_LATENCY_0
))
547 latency
= LL_FLASH_LATENCY_5
;
549 #endif /*UTILS_SCALE1_LATENCY5_FREQ */
550 #if defined (UTILS_SCALE2_LATENCY4_FREQ)
551 if((HCLK_Frequency
> UTILS_SCALE2_LATENCY4_FREQ
)&&(latency
== LL_FLASH_LATENCY_0
))
553 latency
= LL_FLASH_LATENCY_4
;
555 #endif /*UTILS_SCALE1_LATENCY4_FREQ */
556 #if defined (UTILS_SCALE2_LATENCY3_FREQ)
557 if((HCLK_Frequency
> UTILS_SCALE2_LATENCY3_FREQ
)&&(latency
== LL_FLASH_LATENCY_0
))
559 latency
= LL_FLASH_LATENCY_3
;
561 #endif /*UTILS_SCALE1_LATENCY3_FREQ */
562 if((HCLK_Frequency
> UTILS_SCALE2_LATENCY2_FREQ
)&&(latency
== LL_FLASH_LATENCY_0
))
564 latency
= LL_FLASH_LATENCY_2
;
568 if((HCLK_Frequency
> UTILS_SCALE2_LATENCY1_FREQ
)&&(latency
== LL_FLASH_LATENCY_0
))
570 latency
= LL_FLASH_LATENCY_1
;
574 #if defined (LL_PWR_REGU_VOLTAGE_SCALE3)
575 if(LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE3
)
577 #if defined (UTILS_SCALE3_LATENCY3_FREQ)
578 if((HCLK_Frequency
> UTILS_SCALE3_LATENCY3_FREQ
)&&(latency
== LL_FLASH_LATENCY_0
))
580 latency
= LL_FLASH_LATENCY_3
;
582 #endif /*UTILS_SCALE1_LATENCY3_FREQ */
583 #if defined (UTILS_SCALE3_LATENCY2_FREQ)
584 if((HCLK_Frequency
> UTILS_SCALE3_LATENCY2_FREQ
)&&(latency
== LL_FLASH_LATENCY_0
))
586 latency
= LL_FLASH_LATENCY_2
;
590 if((HCLK_Frequency
> UTILS_SCALE3_LATENCY1_FREQ
)&&(latency
== LL_FLASH_LATENCY_0
))
592 latency
= LL_FLASH_LATENCY_1
;
596 #endif /*UTILS_SCALE1_LATENCY2_FREQ */
597 #endif /* LL_PWR_REGU_VOLTAGE_SCALE3 */
599 LL_FLASH_SetLatency(latency
);
601 /* Check that the new number of wait states is taken into account to access the Flash
602 memory by reading the FLASH_ACR register */
603 if(LL_FLASH_GetLatency() != latency
)
612 * @brief Function to check that PLL can be modified
613 * @param PLL_InputFrequency PLL input frequency (in Hz)
614 * @param UTILS_PLLInitStruct pointer to a @ref LL_UTILS_PLLInitTypeDef structure that contains
615 * the configuration information for the PLL.
616 * @retval PLL output frequency (in Hz)
618 static uint32_t UTILS_GetPLLOutputFrequency(uint32_t PLL_InputFrequency
, LL_UTILS_PLLInitTypeDef
*UTILS_PLLInitStruct
)
620 uint32_t pllfreq
= 0U;
622 /* Check the parameters */
623 assert_param(IS_LL_UTILS_PLLM_VALUE(UTILS_PLLInitStruct
->PLLM
));
624 assert_param(IS_LL_UTILS_PLLN_VALUE(UTILS_PLLInitStruct
->PLLN
));
625 assert_param(IS_LL_UTILS_PLLP_VALUE(UTILS_PLLInitStruct
->PLLP
));
627 /* Check different PLL parameters according to RM */
628 /* - PLLM: ensure that the VCO input frequency ranges from @ref UTILS_PLLVCO_INPUT_MIN to @ref UTILS_PLLVCO_INPUT_MAX MHz. */
629 pllfreq
= PLL_InputFrequency
/ (UTILS_PLLInitStruct
->PLLM
& (RCC_PLLCFGR_PLLM
>> RCC_PLLCFGR_PLLM_Pos
));
630 assert_param(IS_LL_UTILS_PLLVCO_INPUT(pllfreq
));
632 /* - PLLN: ensure that the VCO output frequency is between @ref UTILS_PLLVCO_OUTPUT_MIN and @ref UTILS_PLLVCO_OUTPUT_MAX .*/
633 pllfreq
= pllfreq
* (UTILS_PLLInitStruct
->PLLN
& (RCC_PLLCFGR_PLLN
>> RCC_PLLCFGR_PLLN_Pos
));
634 assert_param(IS_LL_UTILS_PLLVCO_OUTPUT(pllfreq
));
636 /* - PLLP: ensure that max frequency at @ref RCC_MAX_FREQUENCY Hz is reached */
637 pllfreq
= pllfreq
/ (((UTILS_PLLInitStruct
->PLLP
>> RCC_PLLCFGR_PLLP_Pos
) + 1) * 2);
638 assert_param(IS_LL_UTILS_PLL_FREQUENCY(pllfreq
));
644 * @brief Function to check that PLL can be modified
645 * @retval An ErrorStatus enumeration value:
646 * - SUCCESS: PLL modification can be done
647 * - ERROR: PLL is busy
649 static ErrorStatus
UTILS_PLL_IsBusy(void)
651 ErrorStatus status
= SUCCESS
;
653 /* Check if PLL is busy*/
654 if(LL_RCC_PLL_IsReady() != 0U)
656 /* PLL configuration cannot be modified */
660 #if defined(RCC_PLLSAI_SUPPORT)
661 /* Check if PLLSAI is busy*/
662 if(LL_RCC_PLLSAI_IsReady() != 0U)
664 /* PLLSAI1 configuration cannot be modified */
667 #endif /*RCC_PLLSAI_SUPPORT*/
668 #if defined(RCC_PLLI2S_SUPPORT)
669 /* Check if PLLI2S is busy*/
670 if(LL_RCC_PLLI2S_IsReady() != 0U)
672 /* PLLI2S configuration cannot be modified */
675 #endif /*RCC_PLLI2S_SUPPORT*/
680 * @brief Function to enable PLL and switch system clock to PLL
681 * @param SYSCLK_Frequency SYSCLK frequency
682 * @param UTILS_ClkInitStruct pointer to a @ref LL_UTILS_ClkInitTypeDef structure that contains
683 * the configuration information for the BUS prescalers.
684 * @retval An ErrorStatus enumeration value:
685 * - SUCCESS: No problem to switch system to PLL
686 * - ERROR: Problem to switch system to PLL
688 static ErrorStatus
UTILS_EnablePLLAndSwitchSystem(uint32_t SYSCLK_Frequency
, LL_UTILS_ClkInitTypeDef
*UTILS_ClkInitStruct
)
690 ErrorStatus status
= SUCCESS
;
691 uint32_t hclk_frequency
= 0U;
693 assert_param(IS_LL_UTILS_SYSCLK_DIV(UTILS_ClkInitStruct
->AHBCLKDivider
));
694 assert_param(IS_LL_UTILS_APB1_DIV(UTILS_ClkInitStruct
->APB1CLKDivider
));
695 assert_param(IS_LL_UTILS_APB2_DIV(UTILS_ClkInitStruct
->APB2CLKDivider
));
697 /* Calculate HCLK frequency */
698 hclk_frequency
= __LL_RCC_CALC_HCLK_FREQ(SYSCLK_Frequency
, UTILS_ClkInitStruct
->AHBCLKDivider
);
700 /* Increasing the number of wait states because of higher CPU frequency */
701 if(SystemCoreClock
< hclk_frequency
)
703 /* Set FLASH latency to highest latency */
704 status
= UTILS_SetFlashLatency(hclk_frequency
);
707 /* Update system clock configuration */
708 if(status
== SUCCESS
)
712 while (LL_RCC_PLL_IsReady() != 1U)
714 /* Wait for PLL ready */
717 /* Sysclk activation on the main PLL */
718 LL_RCC_SetAHBPrescaler(UTILS_ClkInitStruct
->AHBCLKDivider
);
719 LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL
);
720 while (LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL
)
722 /* Wait for system clock switch to PLL */
725 /* Set APB1 & APB2 prescaler*/
726 LL_RCC_SetAPB1Prescaler(UTILS_ClkInitStruct
->APB1CLKDivider
);
727 LL_RCC_SetAPB2Prescaler(UTILS_ClkInitStruct
->APB2CLKDivider
);
730 /* Decreasing the number of wait states because of lower CPU frequency */
731 if(SystemCoreClock
> hclk_frequency
)
733 /* Set FLASH latency to lowest latency */
734 status
= UTILS_SetFlashLatency(hclk_frequency
);
737 /* Update SystemCoreClock variable */
738 if(status
== SUCCESS
)
740 LL_SetSystemCoreClock(hclk_frequency
);
758 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/