Merge pull request #10558 from iNavFlight/MrD_Correct-comments-on-OSD-symbols
[inav.git] / lib / main / STM32F7 / Drivers / STM32F7xx_HAL_Driver / Src / stm32f7xx_hal_rcc.c
bloba161b2664f6f90084503796f5e12b4257b0d59c0
1 /**
2 ******************************************************************************
3 * @file stm32f7xx_hal_rcc.c
4 * @author MCD Application Team
5 * @version V1.2.2
6 * @date 14-April-2017
7 * @brief RCC HAL module driver.
8 * This file provides firmware functions to manage the following
9 * functionalities of the Reset and Clock Control (RCC) peripheral:
10 * + Initialization and de-initialization functions
11 * + Peripheral Control functions
13 @verbatim
14 ==============================================================================
15 ##### RCC specific features #####
16 ==============================================================================
17 [..]
18 After reset the device is running from Internal High Speed oscillator
19 (HSI 16MHz) with Flash 0 wait state, Flash prefetch buffer, D-Cache
20 and I-Cache are disabled, and all peripherals are off except internal
21 SRAM, Flash and JTAG.
22 (+) There is no prescaler on High speed (AHB) and Low speed (APB) busses;
23 all peripherals mapped on these busses are running at HSI speed.
24 (+) The clock for all peripherals is switched off, except the SRAM and FLASH.
25 (+) All GPIOs are in input floating state, except the JTAG pins which
26 are assigned to be used for debug purpose.
28 [..]
29 Once the device started from reset, the user application has to:
30 (+) Configure the clock source to be used to drive the System clock
31 (if the application needs higher frequency/performance)
32 (+) Configure the System clock frequency and Flash settings
33 (+) Configure the AHB and APB busses prescalers
34 (+) Enable the clock for the peripheral(s) to be used
35 (+) Configure the clock source(s) for peripherals which clocks are not
36 derived from the System clock (I2S, RTC, ADC, USB OTG FS/SDIO/RNG)
38 ##### RCC Limitations #####
39 ==============================================================================
40 [..]
41 A delay between an RCC peripheral clock enable and the effective peripheral
42 enabling should be taken into account in order to manage the peripheral read/write
43 from/to registers.
44 (+) This delay depends on the peripheral mapping.
45 (+) If peripheral is mapped on AHB: the delay is 2 AHB clock cycle
46 after the clock enable bit is set on the hardware register
47 (+) If peripheral is mapped on APB: the delay is 2 APB clock cycle
48 after the clock enable bit is set on the hardware register
50 [..]
51 Implemented Workaround:
52 (+) For AHB & APB peripherals, a dummy read to the peripheral register has been
53 inserted in each __HAL_RCC_PPP_CLK_ENABLE() macro.
55 @endverbatim
56 ******************************************************************************
57 * @attention
59 * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
61 * Redistribution and use in source and binary forms, with or without modification,
62 * are permitted provided that the following conditions are met:
63 * 1. Redistributions of source code must retain the above copyright notice,
64 * this list of conditions and the following disclaimer.
65 * 2. Redistributions in binary form must reproduce the above copyright notice,
66 * this list of conditions and the following disclaimer in the documentation
67 * and/or other materials provided with the distribution.
68 * 3. Neither the name of STMicroelectronics nor the names of its contributors
69 * may be used to endorse or promote products derived from this software
70 * without specific prior written permission.
72 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
73 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
74 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
75 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
76 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
77 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
78 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
79 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
80 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
81 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
83 ******************************************************************************
84 */
86 /* Includes ------------------------------------------------------------------*/
87 #include "stm32f7xx_hal.h"
89 /** @addtogroup STM32F7xx_HAL_Driver
90 * @{
93 /** @defgroup RCC RCC
94 * @brief RCC HAL module driver
95 * @{
98 #ifdef HAL_RCC_MODULE_ENABLED
100 /* Private typedef -----------------------------------------------------------*/
101 /* Private define ------------------------------------------------------------*/
102 /* Private macro -------------------------------------------------------------*/
103 /** @defgroup RCC_Private_Macros RCC Private Macros
104 * @{
107 #define MCO1_CLK_ENABLE() __HAL_RCC_GPIOA_CLK_ENABLE()
108 #define MCO1_GPIO_PORT GPIOA
109 #define MCO1_PIN GPIO_PIN_8
111 #define MCO2_CLK_ENABLE() __HAL_RCC_GPIOC_CLK_ENABLE()
112 #define MCO2_GPIO_PORT GPIOC
113 #define MCO2_PIN GPIO_PIN_9
116 * @}
118 /* Private variables ---------------------------------------------------------*/
119 /** @defgroup RCC_Private_Variables RCC Private Variables
120 * @{
124 * @}
127 /* Private function prototypes -----------------------------------------------*/
128 /* Exported functions ---------------------------------------------------------*/
130 /** @defgroup RCC_Exported_Functions RCC Exported Functions
131 * @{
134 /** @defgroup RCC_Exported_Functions_Group1 Initialization and de-initialization functions
135 * @brief Initialization and Configuration functions
137 @verbatim
138 ===============================================================================
139 ##### Initialization and de-initialization functions #####
140 ===============================================================================
141 [..]
142 This section provides functions allowing to configure the internal/external oscillators
143 (HSE, HSI, LSE, LSI, PLL, CSS and MCO) and the System buses clocks (SYSCLK, AHB, APB1
144 and APB2).
146 [..] Internal/external clock and PLL configuration
147 (#) HSI (high-speed internal), 16 MHz factory-trimmed RC used directly or through
148 the PLL as System clock source.
150 (#) LSI (low-speed internal), 32 KHz low consumption RC used as IWDG and/or RTC
151 clock source.
153 (#) HSE (high-speed external), 4 to 26 MHz crystal oscillator used directly or
154 through the PLL as System clock source. Can be used also as RTC clock source.
156 (#) LSE (low-speed external), 32 KHz oscillator used as RTC clock source.
158 (#) PLL (clocked by HSI or HSE), featuring two different output clocks:
159 (++) The first output is used to generate the high speed system clock (up to 216 MHz)
160 (++) The second output is used to generate the clock for the USB OTG FS (48 MHz),
161 the random analog generator (<=48 MHz) and the SDIO (<= 48 MHz).
163 (#) CSS (Clock security system), once enable using the function HAL_RCC_EnableCSS()
164 and if a HSE clock failure occurs(HSE used directly or through PLL as System
165 clock source), the System clock is automatically switched to HSI and an interrupt
166 is generated if enabled. The interrupt is linked to the Cortex-M7 NMI
167 (Non-Maskable Interrupt) exception vector.
169 (#) MCO1 (microcontroller clock output), used to output HSI, LSE, HSE or PLL
170 clock (through a configurable prescaler) on PA8 pin.
172 (#) MCO2 (microcontroller clock output), used to output HSE, PLL, SYSCLK or PLLI2S
173 clock (through a configurable prescaler) on PC9 pin.
175 [..] System, AHB and APB busses clocks configuration
176 (#) Several clock sources can be used to drive the System clock (SYSCLK): HSI,
177 HSE and PLL.
178 The AHB clock (HCLK) is derived from System clock through configurable
179 prescaler and used to clock the CPU, memory and peripherals mapped
180 on AHB bus (DMA, GPIO...). APB1 (PCLK1) and APB2 (PCLK2) clocks are derived
181 from AHB clock through configurable prescalers and used to clock
182 the peripherals mapped on these busses. You can use
183 "HAL_RCC_GetSysClockFreq()" function to retrieve the frequencies of these clocks.
185 -@- All the peripheral clocks are derived from the System clock (SYSCLK) except:
186 (+@) I2S: the I2S clock can be derived either from a specific PLL (PLLI2S) or
187 from an external clock mapped on the I2S_CKIN pin.
188 You have to use __HAL_RCC_PLLI2S_CONFIG() macro to configure this clock.
189 (+@) SAI: the SAI clock can be derived either from a specific PLL (PLLI2S) or (PLLSAI) or
190 from an external clock mapped on the I2S_CKIN pin.
191 You have to use __HAL_RCC_PLLI2S_CONFIG() macro to configure this clock.
192 (+@) RTC: the RTC clock can be derived either from the LSI, LSE or HSE clock
193 divided by 2 to 31. You have to use __HAL_RCC_RTC_CONFIG() and __HAL_RCC_RTC_ENABLE()
194 macros to configure this clock.
195 (+@) USB OTG FS, SDIO and RTC: USB OTG FS require a frequency equal to 48 MHz
196 to work correctly, while the SDIO require a frequency equal or lower than
197 to 48. This clock is derived of the main PLL through PLLQ divider.
198 (+@) IWDG clock which is always the LSI clock.
199 @endverbatim
200 * @{
204 * @brief Resets the RCC clock configuration to the default reset state.
205 * @note The default reset state of the clock configuration is given below:
206 * - HSI ON and used as system clock source
207 * - HSE, PLL and PLLI2S OFF
208 * - AHB, APB1 and APB2 prescaler set to 1.
209 * - CSS, MCO1 and MCO2 OFF
210 * - All interrupts disabled
211 * @note This function doesn't modify the configuration of the
212 * - Peripheral clocks
213 * - LSI, LSE and RTC clocks
214 * @retval None
216 void HAL_RCC_DeInit(void)
218 /* Set HSION bit */
219 SET_BIT(RCC->CR, RCC_CR_HSION | RCC_CR_HSITRIM_4);
221 /* Reset CFGR register */
222 CLEAR_REG(RCC->CFGR);
224 /* Reset HSEON, CSSON, PLLON, PLLI2S */
225 CLEAR_BIT(RCC->CR, RCC_CR_HSEON | RCC_CR_CSSON | RCC_CR_PLLON| RCC_CR_PLLI2SON);
227 /* Reset PLLCFGR register */
228 CLEAR_REG(RCC->PLLCFGR);
229 SET_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLQ_2 | ((uint32_t)0x20000000U));
231 /* Reset PLLI2SCFGR register */
232 CLEAR_REG(RCC->PLLI2SCFGR);
233 SET_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN_6 | RCC_PLLI2SCFGR_PLLI2SN_7 | RCC_PLLI2SCFGR_PLLI2SR_1);
235 /* Reset HSEBYP bit */
236 CLEAR_BIT(RCC->CR, RCC_CR_HSEBYP);
238 /* Disable all interrupts */
239 CLEAR_REG(RCC->CIR);
241 /* Update the SystemCoreClock global variable */
242 SystemCoreClock = HSI_VALUE;
246 * @brief Initializes the RCC Oscillators according to the specified parameters in the
247 * RCC_OscInitTypeDef.
248 * @param RCC_OscInitStruct: pointer to an RCC_OscInitTypeDef structure that
249 * contains the configuration information for the RCC Oscillators.
250 * @note The PLL is not disabled when used as system clock.
251 * @note Transitions LSE Bypass to LSE On and LSE On to LSE Bypass are not
252 * supported by this function. User should request a transition to LSE Off
253 * first and then LSE On or LSE Bypass.
254 * @note Transition HSE Bypass to HSE On and HSE On to HSE Bypass are not
255 * supported by this function. User should request a transition to HSE Off
256 * first and then HSE On or HSE Bypass.
257 * @retval HAL status
259 HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct)
261 uint32_t tickstart = 0;
262 FlagStatus pwrclkchanged = RESET;
264 /* Check the parameters */
265 assert_param(IS_RCC_OSCILLATORTYPE(RCC_OscInitStruct->OscillatorType));
267 /*------------------------------- HSE Configuration ------------------------*/
268 if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSE) == RCC_OSCILLATORTYPE_HSE)
270 /* Check the parameters */
271 assert_param(IS_RCC_HSE(RCC_OscInitStruct->HSEState));
272 /* When the HSE is used as system clock or clock source for PLL, It can not be disabled */
273 if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_HSE)
274 || ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_PLLCLK) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE)))
276 if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) && (RCC_OscInitStruct->HSEState == RCC_HSE_OFF))
278 return HAL_ERROR;
281 else
283 /* Set the new HSE configuration ---------------------------------------*/
284 __HAL_RCC_HSE_CONFIG(RCC_OscInitStruct->HSEState);
286 /* Check the HSE State */
287 if(RCC_OscInitStruct->HSEState != RCC_HSE_OFF)
289 /* Get Start Tick*/
290 tickstart = HAL_GetTick();
292 /* Wait till HSE is ready */
293 while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET)
295 if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE)
297 return HAL_TIMEOUT;
301 else
303 /* Get Start Tick*/
304 tickstart = HAL_GetTick();
306 /* Wait till HSE is bypassed or disabled */
307 while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET)
309 if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE)
311 return HAL_TIMEOUT;
317 /*----------------------------- HSI Configuration --------------------------*/
318 if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI) == RCC_OSCILLATORTYPE_HSI)
320 /* Check the parameters */
321 assert_param(IS_RCC_HSI(RCC_OscInitStruct->HSIState));
322 assert_param(IS_RCC_CALIBRATION_VALUE(RCC_OscInitStruct->HSICalibrationValue));
324 /* Check if HSI is used as system clock or as PLL source when PLL is selected as system clock */
325 if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_HSI)
326 || ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_PLLCLK) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI)))
328 /* When HSI is used as system clock it will not disabled */
329 if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) && (RCC_OscInitStruct->HSIState != RCC_HSI_ON))
331 return HAL_ERROR;
333 /* Otherwise, just the calibration is allowed */
334 else
336 /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/
337 __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue);
340 else
342 /* Check the HSI State */
343 if((RCC_OscInitStruct->HSIState)!= RCC_HSI_OFF)
345 /* Enable the Internal High Speed oscillator (HSI). */
346 __HAL_RCC_HSI_ENABLE();
348 /* Get Start Tick*/
349 tickstart = HAL_GetTick();
351 /* Wait till HSI is ready */
352 while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET)
354 if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE)
356 return HAL_TIMEOUT;
360 /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/
361 __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue);
363 else
365 /* Disable the Internal High Speed oscillator (HSI). */
366 __HAL_RCC_HSI_DISABLE();
368 /* Get Start Tick*/
369 tickstart = HAL_GetTick();
371 /* Wait till HSI is ready */
372 while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET)
374 if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE)
376 return HAL_TIMEOUT;
382 /*------------------------------ LSI Configuration -------------------------*/
383 if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSI) == RCC_OSCILLATORTYPE_LSI)
385 /* Check the parameters */
386 assert_param(IS_RCC_LSI(RCC_OscInitStruct->LSIState));
388 /* Check the LSI State */
389 if((RCC_OscInitStruct->LSIState)!= RCC_LSI_OFF)
391 /* Enable the Internal Low Speed oscillator (LSI). */
392 __HAL_RCC_LSI_ENABLE();
394 /* Get Start Tick*/
395 tickstart = HAL_GetTick();
397 /* Wait till LSI is ready */
398 while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) == RESET)
400 if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE)
402 return HAL_TIMEOUT;
406 else
408 /* Disable the Internal Low Speed oscillator (LSI). */
409 __HAL_RCC_LSI_DISABLE();
411 /* Get Start Tick*/
412 tickstart = HAL_GetTick();
414 /* Wait till LSI is ready */
415 while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) != RESET)
417 if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE)
419 return HAL_TIMEOUT;
424 /*------------------------------ LSE Configuration -------------------------*/
425 if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSE) == RCC_OSCILLATORTYPE_LSE)
427 /* Check the parameters */
428 assert_param(IS_RCC_LSE(RCC_OscInitStruct->LSEState));
430 /* Update LSE configuration in Backup Domain control register */
431 /* Requires to enable write access to Backup Domain of necessary */
432 if(__HAL_RCC_PWR_IS_CLK_DISABLED())
434 /* Enable Power Clock*/
435 __HAL_RCC_PWR_CLK_ENABLE();
436 pwrclkchanged = SET;
439 if(HAL_IS_BIT_CLR(PWR->CR1, PWR_CR1_DBP))
441 /* Enable write access to Backup domain */
442 PWR->CR1 |= PWR_CR1_DBP;
444 /* Wait for Backup domain Write protection disable */
445 tickstart = HAL_GetTick();
447 while(HAL_IS_BIT_CLR(PWR->CR1, PWR_CR1_DBP))
449 if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE)
451 return HAL_TIMEOUT;
456 /* Set the new LSE configuration -----------------------------------------*/
457 __HAL_RCC_LSE_CONFIG(RCC_OscInitStruct->LSEState);
458 /* Check the LSE State */
459 if((RCC_OscInitStruct->LSEState) != RCC_LSE_OFF)
461 /* Get Start Tick*/
462 tickstart = HAL_GetTick();
464 /* Wait till LSE is ready */
465 while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET)
467 if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE)
469 return HAL_TIMEOUT;
473 else
475 /* Get Start Tick*/
476 tickstart = HAL_GetTick();
478 /* Wait till LSE is ready */
479 while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) != RESET)
481 if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE)
483 return HAL_TIMEOUT;
488 /* Restore clock configuration if changed */
489 if(pwrclkchanged == SET)
491 __HAL_RCC_PWR_CLK_DISABLE();
494 /*-------------------------------- PLL Configuration -----------------------*/
495 /* Check the parameters */
496 assert_param(IS_RCC_PLL(RCC_OscInitStruct->PLL.PLLState));
497 if ((RCC_OscInitStruct->PLL.PLLState) != RCC_PLL_NONE)
499 /* Check if the PLL is used as system clock or not */
500 if(__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_SYSCLKSOURCE_STATUS_PLLCLK)
502 if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_ON)
504 /* Check the parameters */
505 assert_param(IS_RCC_PLLSOURCE(RCC_OscInitStruct->PLL.PLLSource));
506 assert_param(IS_RCC_PLLM_VALUE(RCC_OscInitStruct->PLL.PLLM));
507 assert_param(IS_RCC_PLLN_VALUE(RCC_OscInitStruct->PLL.PLLN));
508 assert_param(IS_RCC_PLLP_VALUE(RCC_OscInitStruct->PLL.PLLP));
509 assert_param(IS_RCC_PLLQ_VALUE(RCC_OscInitStruct->PLL.PLLQ));
510 #if defined (RCC_PLLCFGR_PLLR)
511 assert_param(IS_RCC_PLLR_VALUE(RCC_OscInitStruct->PLL.PLLR));
512 #endif
514 /* Disable the main PLL. */
515 __HAL_RCC_PLL_DISABLE();
517 /* Get Start Tick*/
518 tickstart = HAL_GetTick();
520 /* Wait till PLL is ready */
521 while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET)
523 if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE)
525 return HAL_TIMEOUT;
529 /* Configure the main PLL clock source, multiplication and division factors. */
530 #if defined (RCC_PLLCFGR_PLLR)
531 __HAL_RCC_PLL_CONFIG(RCC_OscInitStruct->PLL.PLLSource,
532 RCC_OscInitStruct->PLL.PLLM,
533 RCC_OscInitStruct->PLL.PLLN,
534 RCC_OscInitStruct->PLL.PLLP,
535 RCC_OscInitStruct->PLL.PLLQ,
536 RCC_OscInitStruct->PLL.PLLR);
537 #else
538 __HAL_RCC_PLL_CONFIG(RCC_OscInitStruct->PLL.PLLSource,
539 RCC_OscInitStruct->PLL.PLLM,
540 RCC_OscInitStruct->PLL.PLLN,
541 RCC_OscInitStruct->PLL.PLLP,
542 RCC_OscInitStruct->PLL.PLLQ);
543 #endif
545 /* Enable the main PLL. */
546 __HAL_RCC_PLL_ENABLE();
548 /* Get Start Tick*/
549 tickstart = HAL_GetTick();
551 /* Wait till PLL is ready */
552 while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET)
554 if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE)
556 return HAL_TIMEOUT;
560 else
562 /* Disable the main PLL. */
563 __HAL_RCC_PLL_DISABLE();
565 /* Get Start Tick*/
566 tickstart = HAL_GetTick();
568 /* Wait till PLL is ready */
569 while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET)
571 if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE)
573 return HAL_TIMEOUT;
578 else
580 return HAL_ERROR;
583 return HAL_OK;
587 * @brief Initializes the CPU, AHB and APB busses clocks according to the specified
588 * parameters in the RCC_ClkInitStruct.
589 * @param RCC_ClkInitStruct: pointer to an RCC_OscInitTypeDef structure that
590 * contains the configuration information for the RCC peripheral.
591 * @param FLatency: FLASH Latency, this parameter depend on device selected
593 * @note The SystemCoreClock CMSIS variable is used to store System Clock Frequency
594 * and updated by HAL_RCC_GetHCLKFreq() function called within this function
596 * @note The HSI is used (enabled by hardware) as system clock source after
597 * startup from Reset, wake-up from STOP and STANDBY mode, or in case
598 * of failure of the HSE used directly or indirectly as system clock
599 * (if the Clock Security System CSS is enabled).
601 * @note A switch from one clock source to another occurs only if the target
602 * clock source is ready (clock stable after startup delay or PLL locked).
603 * If a clock source which is not yet ready is selected, the switch will
604 * occur when the clock source will be ready.
605 * You can use HAL_RCC_GetClockConfig() function to know which clock is
606 * currently used as system clock source.
607 * @note Depending on the device voltage range, the software has to set correctly
608 * HPRE[3:0] bits to ensure that HCLK not exceed the maximum allowed frequency
609 * (for more details refer to section above "Initialization/de-initialization functions")
610 * @retval None
612 HAL_StatusTypeDef HAL_RCC_ClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t FLatency)
614 uint32_t tickstart = 0;
616 /* Check the parameters */
617 assert_param(IS_RCC_CLOCKTYPE(RCC_ClkInitStruct->ClockType));
618 assert_param(IS_FLASH_LATENCY(FLatency));
620 /* To correctly read data from FLASH memory, the number of wait states (LATENCY)
621 must be correctly programmed according to the frequency of the CPU clock
622 (HCLK) and the supply voltage of the device. */
624 /* Increasing the CPU frequency */
625 if(FLatency > (FLASH->ACR & FLASH_ACR_LATENCY))
627 /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */
628 __HAL_FLASH_SET_LATENCY(FLatency);
630 /* Check that the new number of wait states is taken into account to access the Flash
631 memory by reading the FLASH_ACR register */
632 if((FLASH->ACR & FLASH_ACR_LATENCY) != FLatency)
634 return HAL_ERROR;
638 /*-------------------------- HCLK Configuration --------------------------*/
639 if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_HCLK) == RCC_CLOCKTYPE_HCLK)
641 assert_param(IS_RCC_HCLK(RCC_ClkInitStruct->AHBCLKDivider));
642 MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, RCC_ClkInitStruct->AHBCLKDivider);
645 /*------------------------- SYSCLK Configuration ---------------------------*/
646 if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_SYSCLK) == RCC_CLOCKTYPE_SYSCLK)
648 assert_param(IS_RCC_SYSCLKSOURCE(RCC_ClkInitStruct->SYSCLKSource));
650 /* HSE is selected as System Clock Source */
651 if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_HSE)
653 /* Check the HSE ready flag */
654 if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET)
656 return HAL_ERROR;
659 /* PLL is selected as System Clock Source */
660 else if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_PLLCLK)
662 /* Check the PLL ready flag */
663 if(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET)
665 return HAL_ERROR;
668 /* HSI is selected as System Clock Source */
669 else
671 /* Check the HSI ready flag */
672 if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET)
674 return HAL_ERROR;
678 __HAL_RCC_SYSCLK_CONFIG(RCC_ClkInitStruct->SYSCLKSource);
679 /* Get Start Tick*/
680 tickstart = HAL_GetTick();
682 if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_HSE)
684 while (__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_SYSCLKSOURCE_STATUS_HSE)
686 if((HAL_GetTick() - tickstart ) > CLOCKSWITCH_TIMEOUT_VALUE)
688 return HAL_TIMEOUT;
692 else if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_PLLCLK)
694 while (__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_SYSCLKSOURCE_STATUS_PLLCLK)
696 if((HAL_GetTick() - tickstart ) > CLOCKSWITCH_TIMEOUT_VALUE)
698 return HAL_TIMEOUT;
702 else
704 while(__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_SYSCLKSOURCE_STATUS_HSI)
706 if((HAL_GetTick() - tickstart ) > CLOCKSWITCH_TIMEOUT_VALUE)
708 return HAL_TIMEOUT;
714 /* Decreasing the number of wait states because of lower CPU frequency */
715 if(FLatency < (FLASH->ACR & FLASH_ACR_LATENCY))
717 /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */
718 __HAL_FLASH_SET_LATENCY(FLatency);
720 /* Check that the new number of wait states is taken into account to access the Flash
721 memory by reading the FLASH_ACR register */
722 if((FLASH->ACR & FLASH_ACR_LATENCY) != FLatency)
724 return HAL_ERROR;
728 /*-------------------------- PCLK1 Configuration ---------------------------*/
729 if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1)
731 assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB1CLKDivider));
732 MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, RCC_ClkInitStruct->APB1CLKDivider);
735 /*-------------------------- PCLK2 Configuration ---------------------------*/
736 if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2)
738 assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB2CLKDivider));
739 MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, ((RCC_ClkInitStruct->APB2CLKDivider) << 3));
742 /* Update the SystemCoreClock global variable */
743 SystemCoreClock = HAL_RCC_GetSysClockFreq() >> AHBPrescTable[(RCC->CFGR & RCC_CFGR_HPRE)>> POSITION_VAL(RCC_CFGR_HPRE)];
745 /* Configure the source of time base considering new system clocks settings*/
746 HAL_InitTick (TICK_INT_PRIORITY);
748 return HAL_OK;
752 * @}
755 /** @defgroup RCC_Exported_Functions_Group2 Peripheral Control functions
756 * @brief RCC clocks control functions
758 @verbatim
759 ===============================================================================
760 ##### Peripheral Control functions #####
761 ===============================================================================
762 [..]
763 This subsection provides a set of functions allowing to control the RCC Clocks
764 frequencies.
766 @endverbatim
767 * @{
771 * @brief Selects the clock source to output on MCO1 pin(PA8) or on MCO2 pin(PC9).
772 * @note PA8/PC9 should be configured in alternate function mode.
773 * @param RCC_MCOx: specifies the output direction for the clock source.
774 * This parameter can be one of the following values:
775 * @arg RCC_MCO1: Clock source to output on MCO1 pin(PA8).
776 * @arg RCC_MCO2: Clock source to output on MCO2 pin(PC9).
777 * @param RCC_MCOSource: specifies the clock source to output.
778 * This parameter can be one of the following values:
779 * @arg RCC_MCO1SOURCE_HSI: HSI clock selected as MCO1 source
780 * @arg RCC_MCO1SOURCE_LSE: LSE clock selected as MCO1 source
781 * @arg RCC_MCO1SOURCE_HSE: HSE clock selected as MCO1 source
782 * @arg RCC_MCO1SOURCE_PLLCLK: main PLL clock selected as MCO1 source
783 * @arg RCC_MCO2SOURCE_SYSCLK: System clock (SYSCLK) selected as MCO2 source
784 * @arg RCC_MCO2SOURCE_PLLI2SCLK: PLLI2S clock selected as MCO2 source
785 * @arg RCC_MCO2SOURCE_HSE: HSE clock selected as MCO2 source
786 * @arg RCC_MCO2SOURCE_PLLCLK: main PLL clock selected as MCO2 source
787 * @param RCC_MCODiv: specifies the MCOx prescaler.
788 * This parameter can be one of the following values:
789 * @arg RCC_MCODIV_1: no division applied to MCOx clock
790 * @arg RCC_MCODIV_2: division by 2 applied to MCOx clock
791 * @arg RCC_MCODIV_3: division by 3 applied to MCOx clock
792 * @arg RCC_MCODIV_4: division by 4 applied to MCOx clock
793 * @arg RCC_MCODIV_5: division by 5 applied to MCOx clock
794 * @retval None
796 void HAL_RCC_MCOConfig(uint32_t RCC_MCOx, uint32_t RCC_MCOSource, uint32_t RCC_MCODiv)
798 GPIO_InitTypeDef GPIO_InitStruct;
799 /* Check the parameters */
800 assert_param(IS_RCC_MCO(RCC_MCOx));
801 assert_param(IS_RCC_MCODIV(RCC_MCODiv));
802 /* RCC_MCO1 */
803 if(RCC_MCOx == RCC_MCO1)
805 assert_param(IS_RCC_MCO1SOURCE(RCC_MCOSource));
807 /* MCO1 Clock Enable */
808 MCO1_CLK_ENABLE();
810 /* Configure the MCO1 pin in alternate function mode */
811 GPIO_InitStruct.Pin = MCO1_PIN;
812 GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
813 GPIO_InitStruct.Speed = GPIO_SPEED_HIGH;
814 GPIO_InitStruct.Pull = GPIO_NOPULL;
815 GPIO_InitStruct.Alternate = GPIO_AF0_MCO;
816 HAL_GPIO_Init(MCO1_GPIO_PORT, &GPIO_InitStruct);
818 /* Mask MCO1 and MCO1PRE[2:0] bits then Select MCO1 clock source and prescaler */
819 MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO1 | RCC_CFGR_MCO1PRE), (RCC_MCOSource | RCC_MCODiv));
821 else
823 assert_param(IS_RCC_MCO2SOURCE(RCC_MCOSource));
825 /* MCO2 Clock Enable */
826 MCO2_CLK_ENABLE();
828 /* Configure the MCO2 pin in alternate function mode */
829 GPIO_InitStruct.Pin = MCO2_PIN;
830 GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
831 GPIO_InitStruct.Speed = GPIO_SPEED_HIGH;
832 GPIO_InitStruct.Pull = GPIO_NOPULL;
833 GPIO_InitStruct.Alternate = GPIO_AF0_MCO;
834 HAL_GPIO_Init(MCO2_GPIO_PORT, &GPIO_InitStruct);
836 /* Mask MCO2 and MCO2PRE[2:0] bits then Select MCO2 clock source and prescaler */
837 MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO2 | RCC_CFGR_MCO2PRE), (RCC_MCOSource | (RCC_MCODiv << 3)));
842 * @brief Enables the Clock Security System.
843 * @note If a failure is detected on the HSE oscillator clock, this oscillator
844 * is automatically disabled and an interrupt is generated to inform the
845 * software about the failure (Clock Security System Interrupt, CSSI),
846 * allowing the MCU to perform rescue operations. The CSSI is linked to
847 * the Cortex-M7 NMI (Non-Maskable Interrupt) exception vector.
848 * @retval None
850 void HAL_RCC_EnableCSS(void)
852 SET_BIT(RCC->CR, RCC_CR_CSSON);
856 * @brief Disables the Clock Security System.
857 * @retval None
859 void HAL_RCC_DisableCSS(void)
861 CLEAR_BIT(RCC->CR, RCC_CR_CSSON);
865 * @brief Returns the SYSCLK frequency
867 * @note The system frequency computed by this function is not the real
868 * frequency in the chip. It is calculated based on the predefined
869 * constant and the selected clock source:
870 * @note If SYSCLK source is HSI, function returns values based on HSI_VALUE(*)
871 * @note If SYSCLK source is HSE, function returns values based on HSE_VALUE(**)
872 * @note If SYSCLK source is PLL, function returns values based on HSE_VALUE(**)
873 * or HSI_VALUE(*) multiplied/divided by the PLL factors.
874 * @note (*) HSI_VALUE is a constant defined in stm32f7xx_hal_conf.h file (default value
875 * 16 MHz) but the real value may vary depending on the variations
876 * in voltage and temperature.
877 * @note (**) HSE_VALUE is a constant defined in stm32f7xx_hal_conf.h file (default value
878 * 25 MHz), user has to ensure that HSE_VALUE is same as the real
879 * frequency of the crystal used. Otherwise, this function may
880 * have wrong result.
882 * @note The result of this function could be not correct when using fractional
883 * value for HSE crystal.
885 * @note This function can be used by the user application to compute the
886 * baudrate for the communication peripherals or configure other parameters.
888 * @note Each time SYSCLK changes, this function must be called to update the
889 * right SYSCLK value. Otherwise, any configuration based on this function will be incorrect.
892 * @retval SYSCLK frequency
894 uint32_t HAL_RCC_GetSysClockFreq(void)
896 uint32_t pllm = 0, pllvco = 0, pllp = 0;
897 uint32_t sysclockfreq = 0;
899 /* Get SYSCLK source -------------------------------------------------------*/
900 switch (RCC->CFGR & RCC_CFGR_SWS)
902 case RCC_SYSCLKSOURCE_STATUS_HSI: /* HSI used as system clock source */
904 sysclockfreq = HSI_VALUE;
905 break;
907 case RCC_SYSCLKSOURCE_STATUS_HSE: /* HSE used as system clock source */
909 sysclockfreq = HSE_VALUE;
910 break;
912 case RCC_SYSCLKSOURCE_STATUS_PLLCLK: /* PLL used as system clock source */
914 /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN
915 SYSCLK = PLL_VCO / PLLP */
916 pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
917 if (__HAL_RCC_GET_PLL_OSCSOURCE() != RCC_PLLCFGR_PLLSRC_HSI)
919 /* HSE used as PLL clock source */
920 pllvco = ((HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> POSITION_VAL(RCC_PLLCFGR_PLLN)));
922 else
924 /* HSI used as PLL clock source */
925 pllvco = ((HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> POSITION_VAL(RCC_PLLCFGR_PLLN)));
927 pllp = ((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >> POSITION_VAL(RCC_PLLCFGR_PLLP)) + 1 ) *2);
929 sysclockfreq = pllvco/pllp;
930 break;
932 default:
934 sysclockfreq = HSI_VALUE;
935 break;
938 return sysclockfreq;
942 * @brief Returns the HCLK frequency
943 * @note Each time HCLK changes, this function must be called to update the
944 * right HCLK value. Otherwise, any configuration based on this function will be incorrect.
945 * @note The SystemCoreClock CMSIS variable is used to store System Clock Frequency.
946 * @retval HCLK frequency
948 uint32_t HAL_RCC_GetHCLKFreq(void)
950 return SystemCoreClock;
954 * @brief Returns the PCLK1 frequency
955 * @note Each time PCLK1 changes, this function must be called to update the
956 * right PCLK1 value. Otherwise, any configuration based on this function will be incorrect.
957 * @retval PCLK1 frequency
959 uint32_t HAL_RCC_GetPCLK1Freq(void)
961 /* Get HCLK source and Compute PCLK1 frequency ---------------------------*/
962 return (HAL_RCC_GetHCLKFreq() >> APBPrescTable[(RCC->CFGR & RCC_CFGR_PPRE1)>> POSITION_VAL(RCC_CFGR_PPRE1)]);
966 * @brief Returns the PCLK2 frequency
967 * @note Each time PCLK2 changes, this function must be called to update the
968 * right PCLK2 value. Otherwise, any configuration based on this function will be incorrect.
969 * @retval PCLK2 frequency
971 uint32_t HAL_RCC_GetPCLK2Freq(void)
973 /* Get HCLK source and Compute PCLK2 frequency ---------------------------*/
974 return (HAL_RCC_GetHCLKFreq()>> APBPrescTable[(RCC->CFGR & RCC_CFGR_PPRE2)>> POSITION_VAL(RCC_CFGR_PPRE2)]);
978 * @brief Configures the RCC_OscInitStruct according to the internal
979 * RCC configuration registers.
980 * @param RCC_OscInitStruct: pointer to an RCC_OscInitTypeDef structure that
981 * will be configured.
982 * @retval None
984 void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct)
986 /* Set all possible values for the Oscillator type parameter ---------------*/
987 RCC_OscInitStruct->OscillatorType = RCC_OSCILLATORTYPE_HSE | RCC_OSCILLATORTYPE_HSI | RCC_OSCILLATORTYPE_LSE | RCC_OSCILLATORTYPE_LSI;
989 /* Get the HSE configuration -----------------------------------------------*/
990 if((RCC->CR &RCC_CR_HSEBYP) == RCC_CR_HSEBYP)
992 RCC_OscInitStruct->HSEState = RCC_HSE_BYPASS;
994 else if((RCC->CR &RCC_CR_HSEON) == RCC_CR_HSEON)
996 RCC_OscInitStruct->HSEState = RCC_HSE_ON;
998 else
1000 RCC_OscInitStruct->HSEState = RCC_HSE_OFF;
1003 /* Get the HSI configuration -----------------------------------------------*/
1004 if((RCC->CR &RCC_CR_HSION) == RCC_CR_HSION)
1006 RCC_OscInitStruct->HSIState = RCC_HSI_ON;
1008 else
1010 RCC_OscInitStruct->HSIState = RCC_HSI_OFF;
1013 RCC_OscInitStruct->HSICalibrationValue = (uint32_t)((RCC->CR &RCC_CR_HSITRIM) >> POSITION_VAL(RCC_CR_HSITRIM));
1015 /* Get the LSE configuration -----------------------------------------------*/
1016 if((RCC->BDCR &RCC_BDCR_LSEBYP) == RCC_BDCR_LSEBYP)
1018 RCC_OscInitStruct->LSEState = RCC_LSE_BYPASS;
1020 else if((RCC->BDCR &RCC_BDCR_LSEON) == RCC_BDCR_LSEON)
1022 RCC_OscInitStruct->LSEState = RCC_LSE_ON;
1024 else
1026 RCC_OscInitStruct->LSEState = RCC_LSE_OFF;
1029 /* Get the LSI configuration -----------------------------------------------*/
1030 if((RCC->CSR &RCC_CSR_LSION) == RCC_CSR_LSION)
1032 RCC_OscInitStruct->LSIState = RCC_LSI_ON;
1034 else
1036 RCC_OscInitStruct->LSIState = RCC_LSI_OFF;
1039 /* Get the PLL configuration -----------------------------------------------*/
1040 if((RCC->CR &RCC_CR_PLLON) == RCC_CR_PLLON)
1042 RCC_OscInitStruct->PLL.PLLState = RCC_PLL_ON;
1044 else
1046 RCC_OscInitStruct->PLL.PLLState = RCC_PLL_OFF;
1048 RCC_OscInitStruct->PLL.PLLSource = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC);
1049 RCC_OscInitStruct->PLL.PLLM = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM);
1050 RCC_OscInitStruct->PLL.PLLN = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> POSITION_VAL(RCC_PLLCFGR_PLLN));
1051 RCC_OscInitStruct->PLL.PLLP = (uint32_t)((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) + RCC_PLLCFGR_PLLP_0) << 1) >> POSITION_VAL(RCC_PLLCFGR_PLLP));
1052 RCC_OscInitStruct->PLL.PLLQ = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLQ) >> POSITION_VAL(RCC_PLLCFGR_PLLQ));
1056 * @brief Configures the RCC_ClkInitStruct according to the internal
1057 * RCC configuration registers.
1058 * @param RCC_ClkInitStruct: pointer to an RCC_ClkInitTypeDef structure that
1059 * will be configured.
1060 * @param pFLatency: Pointer on the Flash Latency.
1061 * @retval None
1063 void HAL_RCC_GetClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t *pFLatency)
1065 /* Set all possible values for the Clock type parameter --------------------*/
1066 RCC_ClkInitStruct->ClockType = RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
1068 /* Get the SYSCLK configuration --------------------------------------------*/
1069 RCC_ClkInitStruct->SYSCLKSource = (uint32_t)(RCC->CFGR & RCC_CFGR_SW);
1071 /* Get the HCLK configuration ----------------------------------------------*/
1072 RCC_ClkInitStruct->AHBCLKDivider = (uint32_t)(RCC->CFGR & RCC_CFGR_HPRE);
1074 /* Get the APB1 configuration ----------------------------------------------*/
1075 RCC_ClkInitStruct->APB1CLKDivider = (uint32_t)(RCC->CFGR & RCC_CFGR_PPRE1);
1077 /* Get the APB2 configuration ----------------------------------------------*/
1078 RCC_ClkInitStruct->APB2CLKDivider = (uint32_t)((RCC->CFGR & RCC_CFGR_PPRE2) >> 3);
1080 /* Get the Flash Wait State (Latency) configuration ------------------------*/
1081 *pFLatency = (uint32_t)(FLASH->ACR & FLASH_ACR_LATENCY);
1085 * @brief This function handles the RCC CSS interrupt request.
1086 * @note This API should be called under the NMI_Handler().
1087 * @retval None
1089 void HAL_RCC_NMI_IRQHandler(void)
1091 /* Check RCC CSSF flag */
1092 if(__HAL_RCC_GET_IT(RCC_IT_CSS))
1094 /* RCC Clock Security System interrupt user callback */
1095 HAL_RCC_CSSCallback();
1097 /* Clear RCC CSS pending bit */
1098 __HAL_RCC_CLEAR_IT(RCC_IT_CSS);
1103 * @brief RCC Clock Security System interrupt callback
1104 * @retval None
1106 __weak void HAL_RCC_CSSCallback(void)
1108 /* NOTE : This function Should not be modified, when the callback is needed,
1109 the HAL_RCC_CSSCallback could be implemented in the user file
1114 * @}
1118 * @}
1121 #endif /* HAL_RCC_MODULE_ENABLED */
1123 * @}
1127 * @}
1130 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/