2 ******************************************************************************
3 * @file stm32f3xx_ll_utils.c
4 * @author MCD Application Team
5 * @brief UTILS LL module driver.
6 ******************************************************************************
9 * <h2><center>© 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 /* Includes ------------------------------------------------------------------*/
36 #include "stm32f3xx_ll_rcc.h"
37 #include "stm32f3xx_ll_utils.h"
38 #include "stm32f3xx_ll_system.h"
39 #include "stm32f3xx_ll_pwr.h"
40 #ifdef USE_FULL_ASSERT
41 #include "stm32_assert.h"
43 #define assert_param(expr) ((void)0U)
46 /** @addtogroup STM32F3xx_LL_Driver
50 /** @addtogroup UTILS_LL
54 /* Private types -------------------------------------------------------------*/
55 /* Private variables ---------------------------------------------------------*/
56 /* Private constants ---------------------------------------------------------*/
57 /** @addtogroup UTILS_LL_Private_Constants
61 /* Defines used for PLL range */
62 #define UTILS_PLL_OUTPUT_MAX 72000000U /*!< Frequency max for PLL output, in Hz */
64 /* Defines used for HSE range */
65 #define UTILS_HSE_FREQUENCY_MIN 4000000U /*!< Frequency min for HSE frequency, in Hz */
66 #define UTILS_HSE_FREQUENCY_MAX 32000000U /*!< Frequency max for HSE frequency, in Hz */
68 /* Defines used for FLASH latency according to SYSCLK Frequency */
69 #define UTILS_LATENCY1_FREQ 24000000U /*!< SYSCLK frequency to set FLASH latency 1 */
70 #define UTILS_LATENCY2_FREQ 48000000U /*!< SYSCLK frequency to set FLASH latency 2 */
74 /* Private macros ------------------------------------------------------------*/
75 /** @addtogroup UTILS_LL_Private_Macros
78 #define IS_LL_UTILS_SYSCLK_DIV(__VALUE__) (((__VALUE__) == LL_RCC_SYSCLK_DIV_1) \
79 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_2) \
80 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_4) \
81 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_8) \
82 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_16) \
83 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_64) \
84 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_128) \
85 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_256) \
86 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_512))
88 #define IS_LL_UTILS_APB1_DIV(__VALUE__) (((__VALUE__) == LL_RCC_APB1_DIV_1) \
89 || ((__VALUE__) == LL_RCC_APB1_DIV_2) \
90 || ((__VALUE__) == LL_RCC_APB1_DIV_4) \
91 || ((__VALUE__) == LL_RCC_APB1_DIV_8) \
92 || ((__VALUE__) == LL_RCC_APB1_DIV_16))
94 #define IS_LL_UTILS_APB2_DIV(__VALUE__) (((__VALUE__) == LL_RCC_APB2_DIV_1) \
95 || ((__VALUE__) == LL_RCC_APB2_DIV_2) \
96 || ((__VALUE__) == LL_RCC_APB2_DIV_4) \
97 || ((__VALUE__) == LL_RCC_APB2_DIV_8) \
98 || ((__VALUE__) == LL_RCC_APB2_DIV_16))
100 #define IS_LL_UTILS_PLLMUL_VALUE(__VALUE__) (((__VALUE__) == LL_RCC_PLL_MUL_2) \
101 || ((__VALUE__) == LL_RCC_PLL_MUL_3) \
102 || ((__VALUE__) == LL_RCC_PLL_MUL_4) \
103 || ((__VALUE__) == LL_RCC_PLL_MUL_5) \
104 || ((__VALUE__) == LL_RCC_PLL_MUL_6) \
105 || ((__VALUE__) == LL_RCC_PLL_MUL_7) \
106 || ((__VALUE__) == LL_RCC_PLL_MUL_8) \
107 || ((__VALUE__) == LL_RCC_PLL_MUL_9) \
108 || ((__VALUE__) == LL_RCC_PLL_MUL_10) \
109 || ((__VALUE__) == LL_RCC_PLL_MUL_11) \
110 || ((__VALUE__) == LL_RCC_PLL_MUL_12) \
111 || ((__VALUE__) == LL_RCC_PLL_MUL_13) \
112 || ((__VALUE__) == LL_RCC_PLL_MUL_14) \
113 || ((__VALUE__) == LL_RCC_PLL_MUL_15) \
114 || ((__VALUE__) == LL_RCC_PLL_MUL_16))
116 #define IS_LL_UTILS_PREDIV_VALUE(__VALUE__) (((__VALUE__) == LL_RCC_PREDIV_DIV_1) || ((__VALUE__) == LL_RCC_PREDIV_DIV_2) || \
117 ((__VALUE__) == LL_RCC_PREDIV_DIV_3) || ((__VALUE__) == LL_RCC_PREDIV_DIV_4) || \
118 ((__VALUE__) == LL_RCC_PREDIV_DIV_5) || ((__VALUE__) == LL_RCC_PREDIV_DIV_6) || \
119 ((__VALUE__) == LL_RCC_PREDIV_DIV_7) || ((__VALUE__) == LL_RCC_PREDIV_DIV_8) || \
120 ((__VALUE__) == LL_RCC_PREDIV_DIV_9) || ((__VALUE__) == LL_RCC_PREDIV_DIV_10) || \
121 ((__VALUE__) == LL_RCC_PREDIV_DIV_11) || ((__VALUE__) == LL_RCC_PREDIV_DIV_12) || \
122 ((__VALUE__) == LL_RCC_PREDIV_DIV_13) || ((__VALUE__) == LL_RCC_PREDIV_DIV_14) || \
123 ((__VALUE__) == LL_RCC_PREDIV_DIV_15) || ((__VALUE__) == LL_RCC_PREDIV_DIV_16))
125 #define IS_LL_UTILS_PLL_FREQUENCY(__VALUE__) ((__VALUE__) <= UTILS_PLL_OUTPUT_MAX)
128 #define IS_LL_UTILS_HSE_BYPASS(__STATE__) (((__STATE__) == LL_UTILS_HSEBYPASS_ON) \
129 || ((__STATE__) == LL_UTILS_HSEBYPASS_OFF))
131 #define IS_LL_UTILS_HSE_FREQUENCY(__FREQUENCY__) (((__FREQUENCY__) >= UTILS_HSE_FREQUENCY_MIN) && ((__FREQUENCY__) <= UTILS_HSE_FREQUENCY_MAX))
135 /* Private function prototypes -----------------------------------------------*/
136 /** @defgroup UTILS_LL_Private_Functions UTILS Private functions
139 static uint32_t UTILS_GetPLLOutputFrequency(uint32_t PLL_InputFrequency
,
140 LL_UTILS_PLLInitTypeDef
*UTILS_PLLInitStruct
);
141 #if defined(FLASH_ACR_LATENCY)
142 static ErrorStatus
UTILS_SetFlashLatency(uint32_t Frequency
);
143 #endif /* FLASH_ACR_LATENCY */
144 static ErrorStatus
UTILS_EnablePLLAndSwitchSystem(uint32_t SYSCLK_Frequency
, LL_UTILS_ClkInitTypeDef
*UTILS_ClkInitStruct
);
145 static ErrorStatus
UTILS_PLL_IsBusy(void);
150 /* Exported functions --------------------------------------------------------*/
151 /** @addtogroup UTILS_LL_Exported_Functions
155 /** @addtogroup UTILS_LL_EF_DELAY
160 * @brief This function configures the Cortex-M SysTick source to have 1ms time base.
161 * @note When a RTOS is used, it is recommended to avoid changing the Systick
162 * configuration by calling this function, for a delay use rather osDelay RTOS service.
163 * @param HCLKFrequency HCLK frequency in Hz
164 * @note HCLK frequency can be calculated thanks to RCC helper macro or function @ref LL_RCC_GetSystemClocksFreq
167 void LL_Init1msTick(uint32_t HCLKFrequency
)
169 /* Use frequency provided in argument */
170 LL_InitTick(HCLKFrequency
, 1000U);
174 * @brief This function provides accurate delay (in milliseconds) based
175 * on SysTick counter flag
176 * @note When a RTOS is used, it is recommended to avoid using blocking delay
177 * and use rather osDelay service.
178 * @note To respect 1ms timebase, user should call @ref LL_Init1msTick function which
179 * will configure Systick to 1ms
180 * @param Delay specifies the delay time length, in milliseconds.
183 void LL_mDelay(uint32_t Delay
)
185 __IO
uint32_t tmp
= SysTick
->CTRL
; /* Clear the COUNTFLAG first */
186 /* Add this code to indicate that local variable is not used */
189 /* Add a period to guaranty minimum wait */
190 if (Delay
< LL_MAX_DELAY
)
197 if ((SysTick
->CTRL
& SysTick_CTRL_COUNTFLAG_Msk
) != 0U)
208 /** @addtogroup UTILS_EF_SYSTEM
209 * @brief System Configuration functions
212 ===============================================================================
213 ##### System Configuration functions #####
214 ===============================================================================
216 System, AHB and APB buses clocks configuration
218 (+) The maximum frequency of the SYSCLK, HCLK, PCLK1 and PCLK2 is 72000000 Hz.
221 Depending on the SYSCLK frequency, the flash latency should be adapted accordingly:
222 (++) +-----------------------------------------------+
223 (++) | Latency | SYSCLK clock frequency (MHz) |
224 (++) |---------------|-------------------------------|
225 (++) |0WS(1CPU cycle)| 0 < SYSCLK <= 24 |
226 (++) |---------------|-------------------------------|
227 (++) |1WS(2CPU cycle)| 24 < SYSCLK <= 48 |
228 (++) |---------------|-------------------------------|
229 (++) |2WS(3CPU cycle)| 48 < SYSCLK <= 72 |
230 (++) +-----------------------------------------------+
236 * @brief This function sets directly SystemCoreClock CMSIS variable.
237 * @note Variable can be calculated also through SystemCoreClockUpdate function.
238 * @param HCLKFrequency HCLK frequency in Hz (can be calculated thanks to RCC helper macro)
241 void LL_SetSystemCoreClock(uint32_t HCLKFrequency
)
243 /* HCLK clock frequency */
244 SystemCoreClock
= HCLKFrequency
;
248 * @brief This function configures system clock with HSI as clock source of the PLL
249 * @note The application need to ensure that PLL is disabled.
250 * @note Function is based on the following formula:
251 * - PLL output frequency = ((HSI frequency / PREDIV) * PLLMUL)
252 * - PREDIV: Set to 2 for few devices
253 * - PLLMUL: The application software must set correctly the PLL multiplication factor to
255 * @note FLASH latency can be modified through this function.
256 * @param UTILS_PLLInitStruct pointer to a @ref LL_UTILS_PLLInitTypeDef structure that contains
257 * the configuration information for the PLL.
258 * @param UTILS_ClkInitStruct pointer to a @ref LL_UTILS_ClkInitTypeDef structure that contains
259 * the configuration information for the BUS prescalers.
260 * @retval An ErrorStatus enumeration value:
261 * - SUCCESS: Max frequency configuration done
262 * - ERROR: Max frequency configuration not done
264 ErrorStatus
LL_PLL_ConfigSystemClock_HSI(LL_UTILS_PLLInitTypeDef
*UTILS_PLLInitStruct
,
265 LL_UTILS_ClkInitTypeDef
*UTILS_ClkInitStruct
)
267 ErrorStatus status
= SUCCESS
;
268 uint32_t pllfreq
= 0U;
270 /* Check if one of the PLL is enabled */
271 if (UTILS_PLL_IsBusy() == SUCCESS
)
273 #if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
274 /* Check PREDIV value */
275 assert_param(IS_LL_UTILS_PREDIV_VALUE(UTILS_PLLInitStruct
->PLLDiv
));
277 /* Force PREDIV value to 2 */
278 UTILS_PLLInitStruct
->Prediv
= LL_RCC_PREDIV_DIV_2
;
279 #endif /*RCC_PLLSRC_PREDIV1_SUPPORT*/
280 /* Calculate the new PLL output frequency */
281 pllfreq
= UTILS_GetPLLOutputFrequency(HSI_VALUE
, UTILS_PLLInitStruct
);
283 /* Enable HSI if not enabled */
284 if (LL_RCC_HSI_IsReady() != 1U)
287 while (LL_RCC_HSI_IsReady() != 1U)
289 /* Wait for HSI ready */
294 #if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
295 LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSI
, UTILS_PLLInitStruct
->PLLMul
, UTILS_PLLInitStruct
->PLLDiv
);
297 LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSI_DIV_2
, UTILS_PLLInitStruct
->PLLMul
);
298 #endif /*RCC_PLLSRC_PREDIV1_SUPPORT*/
300 /* Enable PLL and switch system clock to PLL */
301 status
= UTILS_EnablePLLAndSwitchSystem(pllfreq
, UTILS_ClkInitStruct
);
305 /* Current PLL configuration cannot be modified */
313 * @brief This function configures system clock with HSE as clock source of the PLL
314 * @note The application need to ensure that PLL is disabled.
315 * @note Function is based on the following formula:
316 * - PLL output frequency = ((HSI frequency / PREDIV) * PLLMUL)
317 * - PREDIV: Set to 2 for few devices
318 * - PLLMUL: The application software must set correctly the PLL multiplication factor to
319 * not exceed @ref UTILS_PLL_OUTPUT_MAX
320 * @note FLASH latency can be modified through this function.
321 * @param HSEFrequency Value between Min_Data = 4000000 and Max_Data = 32000000
322 * @param HSEBypass This parameter can be one of the following values:
323 * @arg @ref LL_UTILS_HSEBYPASS_ON
324 * @arg @ref LL_UTILS_HSEBYPASS_OFF
325 * @param UTILS_PLLInitStruct pointer to a @ref LL_UTILS_PLLInitTypeDef structure that contains
326 * the configuration information for the PLL.
327 * @param UTILS_ClkInitStruct pointer to a @ref LL_UTILS_ClkInitTypeDef structure that contains
328 * the configuration information for the BUS prescalers.
329 * @retval An ErrorStatus enumeration value:
330 * - SUCCESS: Max frequency configuration done
331 * - ERROR: Max frequency configuration not done
333 ErrorStatus
LL_PLL_ConfigSystemClock_HSE(uint32_t HSEFrequency
, uint32_t HSEBypass
,
334 LL_UTILS_PLLInitTypeDef
*UTILS_PLLInitStruct
, LL_UTILS_ClkInitTypeDef
*UTILS_ClkInitStruct
)
336 ErrorStatus status
= SUCCESS
;
337 uint32_t pllfreq
= 0U;
339 /* Check the parameters */
340 assert_param(IS_LL_UTILS_HSE_FREQUENCY(HSEFrequency
));
341 assert_param(IS_LL_UTILS_HSE_BYPASS(HSEBypass
));
343 /* Check if one of the PLL is enabled */
344 if (UTILS_PLL_IsBusy() == SUCCESS
)
346 /* Check PREDIV value */
347 #if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
348 assert_param(IS_LL_UTILS_PREDIV_VALUE(UTILS_PLLInitStruct
->PLLDiv
));
350 assert_param(IS_LL_UTILS_PREDIV_VALUE(UTILS_PLLInitStruct
->Prediv
));
351 #endif /*RCC_PLLSRC_PREDIV1_SUPPORT*/
353 /* Calculate the new PLL output frequency */
354 pllfreq
= UTILS_GetPLLOutputFrequency(HSEFrequency
, UTILS_PLLInitStruct
);
356 /* Enable HSE if not enabled */
357 if (LL_RCC_HSE_IsReady() != 1U)
359 /* Check if need to enable HSE bypass feature or not */
360 if (HSEBypass
== LL_UTILS_HSEBYPASS_ON
)
362 LL_RCC_HSE_EnableBypass();
366 LL_RCC_HSE_DisableBypass();
371 while (LL_RCC_HSE_IsReady() != 1U)
373 /* Wait for HSE ready */
378 #if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
379 LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSE
, UTILS_PLLInitStruct
->PLLMul
, UTILS_PLLInitStruct
->PLLDiv
);
381 LL_RCC_PLL_ConfigDomain_SYS((RCC_CFGR_PLLSRC_HSE_PREDIV
| UTILS_PLLInitStruct
->Prediv
), UTILS_PLLInitStruct
->PLLMul
);
382 #endif /*RCC_PLLSRC_PREDIV1_SUPPORT*/
384 /* Enable PLL and switch system clock to PLL */
385 status
= UTILS_EnablePLLAndSwitchSystem(pllfreq
, UTILS_ClkInitStruct
);
389 /* Current PLL configuration cannot be modified */
404 /** @addtogroup UTILS_LL_Private_Functions
408 * @brief Update number of Flash wait states in line with new frequency and current
410 * @param Frequency SYSCLK frequency
411 * @retval An ErrorStatus enumeration value:
412 * - SUCCESS: Latency has been modified
413 * - ERROR: Latency cannot be modified
415 #if defined(FLASH_ACR_LATENCY)
416 static ErrorStatus
UTILS_SetFlashLatency(uint32_t Frequency
)
418 ErrorStatus status
= SUCCESS
;
420 uint32_t latency
= LL_FLASH_LATENCY_0
; /* default value 0WS */
422 /* Frequency cannot be equal to 0 */
429 if (Frequency
> UTILS_LATENCY2_FREQ
)
431 /* 48 < SYSCLK <= 72 => 2WS (3 CPU cycles) */
432 latency
= LL_FLASH_LATENCY_2
;
436 if (Frequency
> UTILS_LATENCY1_FREQ
)
438 /* 24 < SYSCLK <= 48 => 1WS (2 CPU cycles) */
439 latency
= LL_FLASH_LATENCY_1
;
441 /* else SYSCLK < 24MHz default LL_FLASH_LATENCY_0 0WS */
444 LL_FLASH_SetLatency(latency
);
446 /* Check that the new number of wait states is taken into account to access the Flash
447 memory by reading the FLASH_ACR register */
448 if (LL_FLASH_GetLatency() != latency
)
455 #endif /* FLASH_ACR_LATENCY */
458 * @brief Function to check that PLL can be modified
459 * @param PLL_InputFrequency PLL input frequency (in Hz)
460 * @param UTILS_PLLInitStruct pointer to a @ref LL_UTILS_PLLInitTypeDef structure that contains
461 * the configuration information for the PLL.
462 * @retval PLL output frequency (in Hz)
464 static uint32_t UTILS_GetPLLOutputFrequency(uint32_t PLL_InputFrequency
, LL_UTILS_PLLInitTypeDef
*UTILS_PLLInitStruct
)
466 uint32_t pllfreq
= 0U;
468 /* Check the parameters */
469 assert_param(IS_LL_UTILS_PLLMUL_VALUE(UTILS_PLLInitStruct
->PLLMul
));
471 /* Check different PLL parameters according to RM */
472 /* The application software must set correctly the PLL multiplication factor to
473 not exceed @ref UTILS_PLL_OUTPUT_MAX */
474 #if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
475 pllfreq
= __LL_RCC_CALC_PLLCLK_FREQ(PLL_InputFrequency
, UTILS_PLLInitStruct
->PLLMul
, UTILS_PLLInitStruct
->PLLDiv
);
477 pllfreq
= __LL_RCC_CALC_PLLCLK_FREQ(PLL_InputFrequency
/ (UTILS_PLLInitStruct
->Prediv
+ 1U), UTILS_PLLInitStruct
->PLLMul
);
478 #endif /*RCC_PLLSRC_PREDIV1_SUPPORT*/
479 assert_param(IS_LL_UTILS_PLL_FREQUENCY(pllfreq
));
485 * @brief Function to check that PLL can be modified
486 * @retval An ErrorStatus enumeration value:
487 * - SUCCESS: PLL modification can be done
488 * - ERROR: PLL is busy
490 static ErrorStatus
UTILS_PLL_IsBusy(void)
492 ErrorStatus status
= SUCCESS
;
494 /* Check if PLL is busy*/
495 if (LL_RCC_PLL_IsReady() != 0U)
497 /* PLL configuration cannot be modified */
505 * @brief Function to enable PLL and switch system clock to PLL
506 * @param SYSCLK_Frequency SYSCLK frequency
507 * @param UTILS_ClkInitStruct pointer to a @ref LL_UTILS_ClkInitTypeDef structure that contains
508 * the configuration information for the BUS prescalers.
509 * @retval An ErrorStatus enumeration value:
510 * - SUCCESS: No problem to switch system to PLL
511 * - ERROR: Problem to switch system to PLL
513 static ErrorStatus
UTILS_EnablePLLAndSwitchSystem(uint32_t SYSCLK_Frequency
, LL_UTILS_ClkInitTypeDef
*UTILS_ClkInitStruct
)
515 ErrorStatus status
= SUCCESS
;
516 uint32_t sysclk_frequency_current
= 0U;
518 assert_param(IS_LL_UTILS_SYSCLK_DIV(UTILS_ClkInitStruct
->AHBCLKDivider
));
519 assert_param(IS_LL_UTILS_APB1_DIV(UTILS_ClkInitStruct
->APB1CLKDivider
));
520 assert_param(IS_LL_UTILS_APB2_DIV(UTILS_ClkInitStruct
->APB2CLKDivider
));
522 /* Calculate current SYSCLK frequency */
523 sysclk_frequency_current
= (SystemCoreClock
<< AHBPrescTable
[LL_RCC_GetAHBPrescaler() >> RCC_POSITION_HPRE
]);
525 /* Increasing the number of wait states because of higher CPU frequency */
526 if (sysclk_frequency_current
< SYSCLK_Frequency
)
528 /* Set FLASH latency to highest latency */
529 status
= UTILS_SetFlashLatency(SYSCLK_Frequency
);
532 /* Update system clock configuration */
533 if (status
== SUCCESS
)
537 while (LL_RCC_PLL_IsReady() != 1U)
539 /* Wait for PLL ready */
542 /* Sysclk activation on the main PLL */
543 LL_RCC_SetAHBPrescaler(UTILS_ClkInitStruct
->AHBCLKDivider
);
544 LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL
);
545 while (LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL
)
547 /* Wait for system clock switch to PLL */
550 /* Set APB1 & APB2 prescaler*/
551 LL_RCC_SetAPB1Prescaler(UTILS_ClkInitStruct
->APB1CLKDivider
);
552 LL_RCC_SetAPB2Prescaler(UTILS_ClkInitStruct
->APB2CLKDivider
);
555 /* Decreasing the number of wait states because of lower CPU frequency */
556 if (sysclk_frequency_current
> SYSCLK_Frequency
)
558 /* Set FLASH latency to lowest latency */
559 status
= UTILS_SetFlashLatency(SYSCLK_Frequency
);
562 /* Update SystemCoreClock variable */
563 if (status
== SUCCESS
)
565 LL_SetSystemCoreClock(__LL_RCC_CALC_HCLK_FREQ(SYSCLK_Frequency
, UTILS_ClkInitStruct
->AHBCLKDivider
));
583 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/