Merge pull request #11189 from klutvott123/move-telemetry-displayport-init
[betaflight.git] / lib / main / STM32F1 / Drivers / STM32F1xx_HAL_Driver / Src / stm32f1xx_ll_utils.c
blob03741a94e1d9cb15663ccb83a32f788dbf8b7497
1 /**
2 ******************************************************************************
3 * @file stm32f1xx_ll_utils.c
4 * @author MCD Application Team
5 * @version V1.1.1
6 * @date 12-May-2017
7 * @brief UTILS LL module driver.
8 ******************************************************************************
9 * @attention
11 * <h2><center>&copy; 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 /* Includes ------------------------------------------------------------------*/
38 #include "stm32f1xx_ll_rcc.h"
39 #include "stm32f1xx_ll_utils.h"
40 #include "stm32f1xx_ll_system.h"
41 #ifdef USE_FULL_ASSERT
42 #include "stm32_assert.h"
43 #else
44 #define assert_param(expr) ((void)0U)
45 #endif
47 /** @addtogroup STM32F1xx_LL_Driver
48 * @{
51 /** @addtogroup UTILS_LL
52 * @{
55 /* Private types -------------------------------------------------------------*/
56 /* Private variables ---------------------------------------------------------*/
57 /* Private constants ---------------------------------------------------------*/
58 /** @addtogroup UTILS_LL_Private_Constants
59 * @{
62 /* Defines used for PLL range */
63 #define UTILS_PLL_OUTPUT_MAX RCC_MAX_FREQUENCY /*!< Frequency max for PLL output, in Hz */
65 /* Defines used for HSE range */
66 #define UTILS_HSE_FREQUENCY_MIN RCC_HSE_MIN /*!< Frequency min for HSE frequency, in Hz */
67 #define UTILS_HSE_FREQUENCY_MAX RCC_HSE_MAX /*!< Frequency max for HSE frequency, in Hz */
69 /* Defines used for FLASH latency according to HCLK Frequency */
70 #if defined(FLASH_ACR_LATENCY)
71 #define UTILS_LATENCY1_FREQ 24000000U /*!< SYSCLK frequency to set FLASH latency 1 */
72 #define UTILS_LATENCY2_FREQ 48000000U /*!< SYSCLK frequency to set FLASH latency 2 */
73 #else
74 /*!< No Latency Configuration in this device */
75 #endif
76 /**
77 * @}
79 /* Private macros ------------------------------------------------------------*/
80 /** @addtogroup UTILS_LL_Private_Macros
81 * @{
83 #define IS_LL_UTILS_SYSCLK_DIV(__VALUE__) (((__VALUE__) == LL_RCC_SYSCLK_DIV_1) \
84 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_2) \
85 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_4) \
86 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_8) \
87 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_16) \
88 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_64) \
89 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_128) \
90 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_256) \
91 || ((__VALUE__) == LL_RCC_SYSCLK_DIV_512))
93 #define IS_LL_UTILS_APB1_DIV(__VALUE__) (((__VALUE__) == LL_RCC_APB1_DIV_1) \
94 || ((__VALUE__) == LL_RCC_APB1_DIV_2) \
95 || ((__VALUE__) == LL_RCC_APB1_DIV_4) \
96 || ((__VALUE__) == LL_RCC_APB1_DIV_8) \
97 || ((__VALUE__) == LL_RCC_APB1_DIV_16))
99 #define IS_LL_UTILS_APB2_DIV(__VALUE__) (((__VALUE__) == LL_RCC_APB2_DIV_1) \
100 || ((__VALUE__) == LL_RCC_APB2_DIV_2) \
101 || ((__VALUE__) == LL_RCC_APB2_DIV_4) \
102 || ((__VALUE__) == LL_RCC_APB2_DIV_8) \
103 || ((__VALUE__) == LL_RCC_APB2_DIV_16))
105 #if defined(RCC_CFGR_PLLMULL6_5)
106 #define IS_LL_UTILS_PLLMUL_VALUE(__VALUE__) (((__VALUE__) == LL_RCC_PLL_MUL_4) \
107 || ((__VALUE__) == LL_RCC_PLL_MUL_5) \
108 || ((__VALUE__) == LL_RCC_PLL_MUL_6) \
109 || ((__VALUE__) == LL_RCC_PLL_MUL_7) \
110 || ((__VALUE__) == LL_RCC_PLL_MUL_8) \
111 || ((__VALUE__) == LL_RCC_PLL_MUL_9) \
112 || ((__VALUE__) == LL_RCC_PLL_MUL_6_5))
113 #else
114 #define IS_LL_UTILS_PLLMUL_VALUE(__VALUE__) (((__VALUE__) == LL_RCC_PLL_MUL_2) \
115 || ((__VALUE__) == LL_RCC_PLL_MUL_3) \
116 || ((__VALUE__) == LL_RCC_PLL_MUL_4) \
117 || ((__VALUE__) == LL_RCC_PLL_MUL_5) \
118 || ((__VALUE__) == LL_RCC_PLL_MUL_6) \
119 || ((__VALUE__) == LL_RCC_PLL_MUL_7) \
120 || ((__VALUE__) == LL_RCC_PLL_MUL_8) \
121 || ((__VALUE__) == LL_RCC_PLL_MUL_9) \
122 || ((__VALUE__) == LL_RCC_PLL_MUL_10) \
123 || ((__VALUE__) == LL_RCC_PLL_MUL_11) \
124 || ((__VALUE__) == LL_RCC_PLL_MUL_12) \
125 || ((__VALUE__) == LL_RCC_PLL_MUL_13) \
126 || ((__VALUE__) == LL_RCC_PLL_MUL_14) \
127 || ((__VALUE__) == LL_RCC_PLL_MUL_15) \
128 || ((__VALUE__) == LL_RCC_PLL_MUL_16))
129 #endif /* RCC_CFGR_PLLMULL6_5 */
131 #if defined(RCC_CFGR2_PREDIV1)
132 #define IS_LL_UTILS_PREDIV_VALUE(__VALUE__) (((__VALUE__) == LL_RCC_PREDIV_DIV_1) || ((__VALUE__) == LL_RCC_PREDIV_DIV_2) || \
133 ((__VALUE__) == LL_RCC_PREDIV_DIV_3) || ((__VALUE__) == LL_RCC_PREDIV_DIV_4) || \
134 ((__VALUE__) == LL_RCC_PREDIV_DIV_5) || ((__VALUE__) == LL_RCC_PREDIV_DIV_6) || \
135 ((__VALUE__) == LL_RCC_PREDIV_DIV_7) || ((__VALUE__) == LL_RCC_PREDIV_DIV_8) || \
136 ((__VALUE__) == LL_RCC_PREDIV_DIV_9) || ((__VALUE__) == LL_RCC_PREDIV_DIV_10) || \
137 ((__VALUE__) == LL_RCC_PREDIV_DIV_11) || ((__VALUE__) == LL_RCC_PREDIV_DIV_12) || \
138 ((__VALUE__) == LL_RCC_PREDIV_DIV_13) || ((__VALUE__) == LL_RCC_PREDIV_DIV_14) || \
139 ((__VALUE__) == LL_RCC_PREDIV_DIV_15) || ((__VALUE__) == LL_RCC_PREDIV_DIV_16))
140 #else
141 #define IS_LL_UTILS_PREDIV_VALUE(__VALUE__) (((__VALUE__) == LL_RCC_PREDIV_DIV_1) || ((__VALUE__) == LL_RCC_PREDIV_DIV_2))
142 #endif /*RCC_PREDIV1_DIV_2_16_SUPPORT*/
144 #define IS_LL_UTILS_PLL_FREQUENCY(__VALUE__) ((__VALUE__) <= UTILS_PLL_OUTPUT_MAX)
147 #define IS_LL_UTILS_HSE_BYPASS(__STATE__) (((__STATE__) == LL_UTILS_HSEBYPASS_ON) \
148 || ((__STATE__) == LL_UTILS_HSEBYPASS_OFF))
150 #define IS_LL_UTILS_HSE_FREQUENCY(__FREQUENCY__) (((__FREQUENCY__) >= UTILS_HSE_FREQUENCY_MIN) && ((__FREQUENCY__) <= UTILS_HSE_FREQUENCY_MAX))
152 * @}
154 /* Private function prototypes -----------------------------------------------*/
155 /** @defgroup UTILS_LL_Private_Functions UTILS Private functions
156 * @{
158 static uint32_t UTILS_GetPLLOutputFrequency(uint32_t PLL_InputFrequency,
159 LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct);
160 #if defined(FLASH_ACR_LATENCY)
161 static ErrorStatus UTILS_SetFlashLatency(uint32_t Frequency);
162 #endif /* FLASH_ACR_LATENCY */
163 static ErrorStatus UTILS_EnablePLLAndSwitchSystem(uint32_t SYSCLK_Frequency, LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct);
164 static ErrorStatus UTILS_PLL_IsBusy(void);
166 * @}
169 /* Exported functions --------------------------------------------------------*/
170 /** @addtogroup UTILS_LL_Exported_Functions
171 * @{
174 /** @addtogroup UTILS_LL_EF_DELAY
175 * @{
179 * @brief This function configures the Cortex-M SysTick source to have 1ms time base.
180 * @note When a RTOS is used, it is recommended to avoid changing the Systick
181 * configuration by calling this function, for a delay use rather osDelay RTOS service.
182 * @param HCLKFrequency HCLK frequency in Hz
183 * @note HCLK frequency can be calculated thanks to RCC helper macro or function @ref LL_RCC_GetSystemClocksFreq
184 * @retval None
186 void LL_Init1msTick(uint32_t HCLKFrequency)
188 /* Use frequency provided in argument */
189 LL_InitTick(HCLKFrequency, 1000U);
193 * @brief This function provides accurate delay (in milliseconds) based
194 * on SysTick counter flag
195 * @note When a RTOS is used, it is recommended to avoid using blocking delay
196 * and use rather osDelay service.
197 * @note To respect 1ms timebase, user should call @ref LL_Init1msTick function which
198 * will configure Systick to 1ms
199 * @param Delay specifies the delay time length, in milliseconds.
200 * @retval None
202 void LL_mDelay(uint32_t Delay)
204 __IO uint32_t tmp = SysTick->CTRL; /* Clear the COUNTFLAG first */
205 /* Add this code to indicate that local variable is not used */
206 ((void)tmp);
208 /* Add a period to guaranty minimum wait */
209 if (Delay < LL_MAX_DELAY)
211 Delay++;
214 while (Delay)
216 if ((SysTick->CTRL & SysTick_CTRL_COUNTFLAG_Msk) != 0U)
218 Delay--;
224 * @}
227 /** @addtogroup UTILS_EF_SYSTEM
228 * @brief System Configuration functions
230 @verbatim
231 ===============================================================================
232 ##### System Configuration functions #####
233 ===============================================================================
234 [..]
235 System, AHB and APB buses clocks configuration
237 (+) The maximum frequency of the SYSCLK, HCLK, PCLK1 and PCLK2 is RCC_MAX_FREQUENCY Hz.
238 @endverbatim
239 @internal
240 Depending on the SYSCLK frequency, the flash latency should be adapted accordingly:
241 (++) +-----------------------------------------------+
242 (++) | Latency | SYSCLK clock frequency (MHz) |
243 (++) |---------------|-------------------------------|
244 (++) |0WS(1CPU cycle)| 0 < SYSCLK <= 24 |
245 (++) |---------------|-------------------------------|
246 (++) |1WS(2CPU cycle)| 24 < SYSCLK <= 48 |
247 (++) |---------------|-------------------------------|
248 (++) |2WS(3CPU cycle)| 48 < SYSCLK <= 72 |
249 (++) +-----------------------------------------------+
250 @endinternal
251 * @{
255 * @brief This function sets directly SystemCoreClock CMSIS variable.
256 * @note Variable can be calculated also through SystemCoreClockUpdate function.
257 * @param HCLKFrequency HCLK frequency in Hz (can be calculated thanks to RCC helper macro)
258 * @retval None
260 void LL_SetSystemCoreClock(uint32_t HCLKFrequency)
262 /* HCLK clock frequency */
263 SystemCoreClock = HCLKFrequency;
267 * @brief This function configures system clock with HSI as clock source of the PLL
268 * @note The application need to ensure that PLL is disabled.
269 * @note Function is based on the following formula:
270 * - PLL output frequency = ((HSI frequency / PREDIV) * PLLMUL)
271 * - PREDIV: Set to 2 for few devices
272 * - PLLMUL: The application software must set correctly the PLL multiplication factor to
273 * not exceed 72MHz
274 * @note FLASH latency can be modified through this function.
275 * @param UTILS_PLLInitStruct pointer to a @ref LL_UTILS_PLLInitTypeDef structure that contains
276 * the configuration information for the PLL.
277 * @param UTILS_ClkInitStruct pointer to a @ref LL_UTILS_ClkInitTypeDef structure that contains
278 * the configuration information for the BUS prescalers.
279 * @retval An ErrorStatus enumeration value:
280 * - SUCCESS: Max frequency configuration done
281 * - ERROR: Max frequency configuration not done
283 ErrorStatus LL_PLL_ConfigSystemClock_HSI(LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct,
284 LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct)
286 ErrorStatus status = SUCCESS;
287 uint32_t pllfreq = 0U;
289 /* Check if one of the PLL is enabled */
290 if (UTILS_PLL_IsBusy() == SUCCESS)
292 #if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
293 /* Check PREDIV value */
294 assert_param(IS_LL_UTILS_PREDIV_VALUE(UTILS_PLLInitStruct->PLLDiv));
295 #else
296 /* Force PREDIV value to 2 */
297 UTILS_PLLInitStruct->Prediv = LL_RCC_PREDIV_DIV_2;
298 #endif /*RCC_PLLSRC_PREDIV1_SUPPORT*/
299 /* Calculate the new PLL output frequency */
300 pllfreq = UTILS_GetPLLOutputFrequency(HSI_VALUE, UTILS_PLLInitStruct);
302 /* Enable HSI if not enabled */
303 if (LL_RCC_HSI_IsReady() != 1U)
305 LL_RCC_HSI_Enable();
306 while (LL_RCC_HSI_IsReady() != 1U)
308 /* Wait for HSI ready */
312 /* Configure PLL */
313 LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSI_DIV_2, UTILS_PLLInitStruct->PLLMul);
315 /* Enable PLL and switch system clock to PLL */
316 status = UTILS_EnablePLLAndSwitchSystem(pllfreq, UTILS_ClkInitStruct);
318 else
320 /* Current PLL configuration cannot be modified */
321 status = ERROR;
324 return status;
328 * @brief This function configures system clock with HSE as clock source of the PLL
329 * @note The application need to ensure that PLL is disabled.
330 * @note Function is based on the following formula:
331 * - PLL output frequency = ((HSI frequency / PREDIV) * PLLMUL)
332 * - PREDIV: Set to 2 for few devices
333 * - PLLMUL: The application software must set correctly the PLL multiplication factor to
334 * not exceed @ref UTILS_PLL_OUTPUT_MAX
335 * @note FLASH latency can be modified through this function.
336 * @param HSEFrequency Value between Min_Data = RCC_HSE_MIN and Max_Data = RCC_HSE_MAX
337 * @param HSEBypass This parameter can be one of the following values:
338 * @arg @ref LL_UTILS_HSEBYPASS_ON
339 * @arg @ref LL_UTILS_HSEBYPASS_OFF
340 * @param UTILS_PLLInitStruct pointer to a @ref LL_UTILS_PLLInitTypeDef structure that contains
341 * the configuration information for the PLL.
342 * @param UTILS_ClkInitStruct pointer to a @ref LL_UTILS_ClkInitTypeDef structure that contains
343 * the configuration information for the BUS prescalers.
344 * @retval An ErrorStatus enumeration value:
345 * - SUCCESS: Max frequency configuration done
346 * - ERROR: Max frequency configuration not done
348 ErrorStatus LL_PLL_ConfigSystemClock_HSE(uint32_t HSEFrequency, uint32_t HSEBypass,
349 LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct, LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct)
351 ErrorStatus status = SUCCESS;
352 uint32_t pllfreq = 0U;
354 /* Check the parameters */
355 assert_param(IS_LL_UTILS_HSE_FREQUENCY(HSEFrequency));
356 assert_param(IS_LL_UTILS_HSE_BYPASS(HSEBypass));
358 /* Check if one of the PLL is enabled */
359 if (UTILS_PLL_IsBusy() == SUCCESS)
361 assert_param(IS_LL_UTILS_PREDIV_VALUE(UTILS_PLLInitStruct->Prediv));
363 /* Calculate the new PLL output frequency */
364 pllfreq = UTILS_GetPLLOutputFrequency(HSEFrequency, UTILS_PLLInitStruct);
366 /* Enable HSE if not enabled */
367 if (LL_RCC_HSE_IsReady() != 1U)
369 /* Check if need to enable HSE bypass feature or not */
370 if (HSEBypass == LL_UTILS_HSEBYPASS_ON)
372 LL_RCC_HSE_EnableBypass();
374 else
376 LL_RCC_HSE_DisableBypass();
379 /* Enable HSE */
380 LL_RCC_HSE_Enable();
381 while (LL_RCC_HSE_IsReady() != 1U)
383 /* Wait for HSE ready */
387 /* Configure PLL */
388 LL_RCC_PLL_ConfigDomain_SYS((RCC_CFGR_PLLSRC | UTILS_PLLInitStruct->Prediv), UTILS_PLLInitStruct->PLLMul);
390 /* Enable PLL and switch system clock to PLL */
391 status = UTILS_EnablePLLAndSwitchSystem(pllfreq, UTILS_ClkInitStruct);
393 else
395 /* Current PLL configuration cannot be modified */
396 status = ERROR;
399 return status;
403 * @}
407 * @}
410 /** @addtogroup UTILS_LL_Private_Functions
411 * @{
414 * @brief Update number of Flash wait states in line with new frequency and current
415 voltage range.
416 * @param Frequency SYSCLK frequency
417 * @retval An ErrorStatus enumeration value:
418 * - SUCCESS: Latency has been modified
419 * - ERROR: Latency cannot be modified
421 #if defined(FLASH_ACR_LATENCY)
422 static ErrorStatus UTILS_SetFlashLatency(uint32_t Frequency)
424 ErrorStatus status = SUCCESS;
426 uint32_t latency = LL_FLASH_LATENCY_0; /* default value 0WS */
428 /* Frequency cannot be equal to 0 */
429 if (Frequency == 0U)
431 status = ERROR;
433 else
435 if (Frequency > UTILS_LATENCY2_FREQ)
437 /* 48 < SYSCLK <= 72 => 2WS (3 CPU cycles) */
438 latency = LL_FLASH_LATENCY_2;
440 else
442 if (Frequency > UTILS_LATENCY1_FREQ)
444 /* 24 < SYSCLK <= 48 => 1WS (2 CPU cycles) */
445 latency = LL_FLASH_LATENCY_1;
447 /* else SYSCLK < 24MHz default LL_FLASH_LATENCY_0 0WS */
450 LL_FLASH_SetLatency(latency);
452 /* Check that the new number of wait states is taken into account to access the Flash
453 memory by reading the FLASH_ACR register */
454 if (LL_FLASH_GetLatency() != latency)
456 status = ERROR;
459 return status;
461 #endif /* FLASH_ACR_LATENCY */
464 * @brief Function to check that PLL can be modified
465 * @param PLL_InputFrequency PLL input frequency (in Hz)
466 * @param UTILS_PLLInitStruct pointer to a @ref LL_UTILS_PLLInitTypeDef structure that contains
467 * the configuration information for the PLL.
468 * @retval PLL output frequency (in Hz)
470 static uint32_t UTILS_GetPLLOutputFrequency(uint32_t PLL_InputFrequency, LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct)
472 uint32_t pllfreq = 0U;
474 /* Check the parameters */
475 assert_param(IS_LL_UTILS_PLLMUL_VALUE(UTILS_PLLInitStruct->PLLMul));
477 /* Check different PLL parameters according to RM */
478 #if defined (RCC_CFGR2_PREDIV1)
479 pllfreq = __LL_RCC_CALC_PLLCLK_FREQ(PLL_InputFrequency / (UTILS_PLLInitStruct->Prediv + 1U), UTILS_PLLInitStruct->PLLMul);
480 #elif defined(RCC_CFGR2_PREDIV1SRC)
481 pllfreq = __LL_RCC_CALC_PLLCLK_FREQ(PLL_InputFrequency, UTILS_PLLInitStruct->PLLMul, UTILS_PLLInitStruct->PLLDiv);
482 #else
483 pllfreq = __LL_RCC_CALC_PLLCLK_FREQ(PLL_InputFrequency / ((UTILS_PLLInitStruct->Prediv >> RCC_CFGR_PLLXTPRE_Pos) + 1U), UTILS_PLLInitStruct->PLLMul);
484 #endif /*RCC_CFGR2_PREDIV1SRC*/
485 assert_param(IS_LL_UTILS_PLL_FREQUENCY(pllfreq));
487 return pllfreq;
491 * @brief Function to check that PLL can be modified
492 * @retval An ErrorStatus enumeration value:
493 * - SUCCESS: PLL modification can be done
494 * - ERROR: PLL is busy
496 static ErrorStatus UTILS_PLL_IsBusy(void)
498 ErrorStatus status = SUCCESS;
500 /* Check if PLL is busy*/
501 if (LL_RCC_PLL_IsReady() != 0U)
503 /* PLL configuration cannot be modified */
504 status = ERROR;
506 #if defined(RCC_PLL2_SUPPORT)
507 /* Check if PLL2 is busy*/
508 if (LL_RCC_PLL2_IsReady() != 0U)
510 /* PLL2 configuration cannot be modified */
511 status = ERROR;
513 #endif /* RCC_PLL2_SUPPORT */
515 #if defined(RCC_PLLI2S_SUPPORT)
516 /* Check if PLLI2S is busy*/
517 if (LL_RCC_PLLI2S_IsReady() != 0U)
519 /* PLLI2S configuration cannot be modified */
520 status = ERROR;
522 #endif /* RCC_PLLI2S_SUPPORT */
524 return status;
528 * @brief Function to enable PLL and switch system clock to PLL
529 * @param SYSCLK_Frequency SYSCLK frequency
530 * @param UTILS_ClkInitStruct pointer to a @ref LL_UTILS_ClkInitTypeDef structure that contains
531 * the configuration information for the BUS prescalers.
532 * @retval An ErrorStatus enumeration value:
533 * - SUCCESS: No problem to switch system to PLL
534 * - ERROR: Problem to switch system to PLL
536 static ErrorStatus UTILS_EnablePLLAndSwitchSystem(uint32_t SYSCLK_Frequency, LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct)
538 ErrorStatus status = SUCCESS;
539 #if defined(FLASH_ACR_LATENCY)
540 uint32_t sysclk_frequency_current = 0U;
541 #endif /* FLASH_ACR_LATENCY */
543 assert_param(IS_LL_UTILS_SYSCLK_DIV(UTILS_ClkInitStruct->AHBCLKDivider));
544 assert_param(IS_LL_UTILS_APB1_DIV(UTILS_ClkInitStruct->APB1CLKDivider));
545 assert_param(IS_LL_UTILS_APB2_DIV(UTILS_ClkInitStruct->APB2CLKDivider));
547 #if defined(FLASH_ACR_LATENCY)
548 /* Calculate current SYSCLK frequency */
549 sysclk_frequency_current = (SystemCoreClock << AHBPrescTable[LL_RCC_GetAHBPrescaler() >> RCC_CFGR_HPRE_Pos]);
550 #endif /* FLASH_ACR_LATENCY */
552 /* Increasing the number of wait states because of higher CPU frequency */
553 #if defined (FLASH_ACR_LATENCY)
554 if (sysclk_frequency_current < SYSCLK_Frequency)
556 /* Set FLASH latency to highest latency */
557 status = UTILS_SetFlashLatency(SYSCLK_Frequency);
559 #endif /* FLASH_ACR_LATENCY */
561 /* Update system clock configuration */
562 if (status == SUCCESS)
564 #if defined(RCC_PLL2_SUPPORT)
565 /* Enable PLL2 */
566 LL_RCC_PLL2_Enable();
567 while (LL_RCC_PLL2_IsReady() != 1U)
569 /* Wait for PLL2 ready */
572 #endif /* RCC_PLL2_SUPPORT */
573 /* Enable PLL */
574 LL_RCC_PLL_Enable();
575 while (LL_RCC_PLL_IsReady() != 1U)
577 /* Wait for PLL ready */
580 /* Sysclk activation on the main PLL */
581 LL_RCC_SetAHBPrescaler(UTILS_ClkInitStruct->AHBCLKDivider);
582 LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL);
583 while (LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL)
585 /* Wait for system clock switch to PLL */
588 /* Set APB1 & APB2 prescaler*/
589 LL_RCC_SetAPB1Prescaler(UTILS_ClkInitStruct->APB1CLKDivider);
590 LL_RCC_SetAPB2Prescaler(UTILS_ClkInitStruct->APB2CLKDivider);
593 /* Decreasing the number of wait states because of lower CPU frequency */
594 #if defined (FLASH_ACR_LATENCY)
595 if (sysclk_frequency_current > SYSCLK_Frequency)
597 /* Set FLASH latency to lowest latency */
598 status = UTILS_SetFlashLatency(SYSCLK_Frequency);
600 #endif /* FLASH_ACR_LATENCY */
602 /* Update SystemCoreClock variable */
603 if (status == SUCCESS)
605 LL_SetSystemCoreClock(__LL_RCC_CALC_HCLK_FREQ(SYSCLK_Frequency, UTILS_ClkInitStruct->AHBCLKDivider));
608 return status;
612 * @}
616 * @}
620 * @}
623 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/