STM32L486xx HAL User Manual
stm32l4xx_hal_rcc.c
Go to the documentation of this file.
00001 /**
00002   ******************************************************************************
00003   * @file    stm32l4xx_hal_rcc.c
00004   * @author  MCD Application Team
00005   * @brief   RCC HAL module driver.
00006   *          This file provides firmware functions to manage the following
00007   *          functionalities of the Reset and Clock Control (RCC) peripheral:
00008   *           + Initialization and de-initialization functions
00009   *           + Peripheral Control functions
00010   *
00011   @verbatim
00012   ==============================================================================
00013                       ##### RCC specific features #####
00014   ==============================================================================
00015     [..]
00016       After reset the device is running from Multiple Speed Internal oscillator
00017       (4 MHz) with Flash 0 wait state. Flash prefetch buffer, D-Cache
00018       and I-Cache are disabled, and all peripherals are off except internal
00019       SRAM, Flash and JTAG.
00020 
00021       (+) There is no prescaler on High speed (AHBs) and Low speed (APBs) busses:
00022           all peripherals mapped on these busses are running at MSI speed.
00023       (+) The clock for all peripherals is switched off, except the SRAM and FLASH.
00024       (+) All GPIOs are in analog mode, except the JTAG pins which
00025           are assigned to be used for debug purpose.
00026 
00027     [..]
00028       Once the device started from reset, the user application has to:
00029       (+) Configure the clock source to be used to drive the System clock
00030           (if the application needs higher frequency/performance)
00031       (+) Configure the System clock frequency and Flash settings
00032       (+) Configure the AHB and APB busses prescalers
00033       (+) Enable the clock for the peripheral(s) to be used
00034       (+) Configure the clock source(s) for peripherals which clocks are not
00035           derived from the System clock (SAIx, RTC, ADC, USB OTG FS/SDMMC1/RNG)
00036 
00037   @endverbatim
00038   ******************************************************************************
00039   * @attention
00040   *
00041   * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
00042   *
00043   * Redistribution and use in source and binary forms, with or without modification,
00044   * are permitted provided that the following conditions are met:
00045   *   1. Redistributions of source code must retain the above copyright notice,
00046   *      this list of conditions and the following disclaimer.
00047   *   2. Redistributions in binary form must reproduce the above copyright notice,
00048   *      this list of conditions and the following disclaimer in the documentation
00049   *      and/or other materials provided with the distribution.
00050   *   3. Neither the name of STMicroelectronics nor the names of its contributors
00051   *      may be used to endorse or promote products derived from this software
00052   *      without specific prior written permission.
00053   *
00054   * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00055   * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00056   * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00057   * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
00058   * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00059   * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00060   * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00061   * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
00062   * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00063   * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00064   *
00065   ******************************************************************************
00066   */
00067 
00068 /* Includes ------------------------------------------------------------------*/
00069 #include "stm32l4xx_hal.h"
00070 
00071 /** @addtogroup STM32L4xx_HAL_Driver
00072   * @{
00073   */
00074 
00075 /** @defgroup RCC RCC
00076   * @brief RCC HAL module driver
00077   * @{
00078   */
00079 
00080 #ifdef HAL_RCC_MODULE_ENABLED
00081 
00082 /* Private typedef -----------------------------------------------------------*/
00083 /* Private define ------------------------------------------------------------*/
00084 /** @defgroup RCC_Private_Constants RCC Private Constants
00085  * @{
00086  */
00087 #define HSE_TIMEOUT_VALUE          HSE_STARTUP_TIMEOUT
00088 #define HSI_TIMEOUT_VALUE          2U    /* 2 ms (minimum Tick + 1) */
00089 #define MSI_TIMEOUT_VALUE          2U    /* 2 ms (minimum Tick + 1) */
00090 #define LSI_TIMEOUT_VALUE          2U    /* 2 ms (minimum Tick + 1) */
00091 #define HSI48_TIMEOUT_VALUE        2U    /* 2 ms (minimum Tick + 1) */
00092 #define PLL_TIMEOUT_VALUE          2U    /* 2 ms (minimum Tick + 1) */
00093 #define CLOCKSWITCH_TIMEOUT_VALUE  5000U /* 5 s    */
00094 /**
00095   * @}
00096   */
00097 
00098 /* Private macro -------------------------------------------------------------*/
00099 /** @defgroup RCC_Private_Macros RCC Private Macros
00100   * @{
00101   */
00102 #define __MCO1_CLK_ENABLE()   __HAL_RCC_GPIOA_CLK_ENABLE()
00103 #define MCO1_GPIO_PORT        GPIOA
00104 #define MCO1_PIN              GPIO_PIN_8
00105 
00106 #define RCC_PLL_OSCSOURCE_CONFIG(__HAL_RCC_PLLSOURCE__) \
00107             (MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, (__HAL_RCC_PLLSOURCE__)))
00108 /**
00109   * @}
00110   */
00111 
00112 /* Private variables ---------------------------------------------------------*/
00113 
00114 /* Private function prototypes -----------------------------------------------*/
00115 /** @defgroup RCC_Private_Functions RCC Private Functions
00116   * @{
00117   */
00118 static HAL_StatusTypeDef RCC_SetFlashLatencyFromMSIRange(uint32_t msirange);
00119 #if defined(STM32L4R5xx) || defined(STM32L4R7xx) || defined(STM32L4R9xx) || defined(STM32L4S5xx) || defined(STM32L4S7xx) || defined(STM32L4S9xx)
00120 static uint32_t          RCC_GetSysClockFreqFromPLLSource(void);
00121 #endif
00122 /**
00123   * @}
00124   */
00125 
00126 /* Exported functions --------------------------------------------------------*/
00127 
00128 /** @defgroup RCC_Exported_Functions RCC Exported Functions
00129   * @{
00130   */
00131 
00132 /** @defgroup RCC_Exported_Functions_Group1 Initialization and de-initialization functions
00133   *  @brief    Initialization and Configuration functions
00134   *
00135   @verbatim
00136  ===============================================================================
00137            ##### Initialization and de-initialization functions #####
00138  ===============================================================================
00139     [..]
00140       This section provides functions allowing to configure the internal and external oscillators
00141       (HSE, HSI, LSE, MSI, LSI, PLL, CSS and MCO) and the System busses clocks (SYSCLK, AHB, APB1
00142        and APB2).
00143 
00144     [..] Internal/external clock and PLL configuration
00145          (+) HSI (high-speed internal): 16 MHz factory-trimmed RC used directly or through
00146              the PLL as System clock source.
00147 
00148          (+) MSI (Mutiple Speed Internal): Its frequency is software trimmable from 100KHZ to 48MHZ.
00149              It can be used to generate the clock for the USB OTG FS (48 MHz).
00150              The number of flash wait states is automatically adjusted when MSI range is updated with
00151              HAL_RCC_OscConfig() and the MSI is used as System clock source.
00152 
00153          (+) LSI (low-speed internal): 32 KHz low consumption RC used as IWDG and/or RTC
00154              clock source.
00155 
00156          (+) HSE (high-speed external): 4 to 48 MHz crystal oscillator used directly or
00157              through the PLL as System clock source. Can be used also optionally as RTC clock source.
00158 
00159          (+) LSE (low-speed external): 32.768 KHz oscillator used optionally as RTC clock source.
00160 
00161          (+) PLL (clocked by HSI, HSE or MSI) providing up to three independent output clocks:
00162            (++) The first output is used to generate the high speed system clock (up to 80MHz).
00163            (++) The second output is used to generate the clock for the USB OTG FS (48 MHz),
00164                 the random analog generator (<=48 MHz) and the SDMMC1 (<= 48 MHz).
00165            (++) The third output is used to generate an accurate clock to achieve
00166                 high-quality audio performance on SAI interface.
00167 
00168          (+) PLLSAI1 (clocked by HSI, HSE or MSI) providing up to three independent output clocks:
00169            (++) The first output is used to generate SAR ADC1 clock.
00170            (++) The second output is used to generate the clock for the USB OTG FS (48 MHz),
00171                 the random analog generator (<=48 MHz) and the SDMMC1 (<= 48 MHz).
00172            (++) The Third output is used to generate an accurate clock to achieve
00173                 high-quality audio performance on SAI interface.
00174 
00175          (+) PLLSAI2 (clocked by HSI , HSE or MSI) providing up to two independent output clocks:
00176            (++) The first output is used to generate SAR ADC2 clock.
00177            (++) The second  output is used to generate an accurate clock to achieve
00178                 high-quality audio performance on SAI interface.
00179 
00180          (+) CSS (Clock security system): once enabled, if a HSE clock failure occurs
00181             (HSE used directly or through PLL as System clock source), the System clock
00182              is automatically switched to HSI and an interrupt is generated if enabled.
00183              The interrupt is linked to the Cortex-M4 NMI (Non-Maskable Interrupt)
00184              exception vector.
00185 
00186          (+) MCO (microcontroller clock output): used to output MSI, LSI, HSI, LSE, HSE or
00187              main PLL clock (through a configurable prescaler) on PA8 pin.
00188 
00189     [..] System, AHB and APB busses clocks configuration
00190          (+) Several clock sources can be used to drive the System clock (SYSCLK): MSI, HSI,
00191              HSE and main PLL.
00192              The AHB clock (HCLK) is derived from System clock through configurable
00193              prescaler and used to clock the CPU, memory and peripherals mapped
00194              on AHB bus (DMA, GPIO...). APB1 (PCLK1) and APB2 (PCLK2) clocks are derived
00195              from AHB clock through configurable prescalers and used to clock
00196              the peripherals mapped on these busses. You can use
00197              "HAL_RCC_GetSysClockFreq()" function to retrieve the frequencies of these clocks.
00198 
00199          -@- All the peripheral clocks are derived from the System clock (SYSCLK) except:
00200 
00201            (+@) SAI: the SAI clock can be derived either from a specific PLL (PLLSAI1) or (PLLSAI2) or
00202                 from an external clock mapped on the SAI_CKIN pin.
00203                 You have to use HAL_RCCEx_PeriphCLKConfig() function to configure this clock.
00204            (+@) RTC: the RTC clock can be derived either from the LSI, LSE or HSE clock
00205                 divided by 2 to 31.
00206                 You have to use __HAL_RCC_RTC_ENABLE() and HAL_RCCEx_PeriphCLKConfig() function
00207                 to configure this clock.
00208            (+@) USB OTG FS, SDMMC1 and RNG: USB OTG FS requires a frequency equal to 48 MHz
00209                 to work correctly, while the SDMMC1 and RNG peripherals require a frequency
00210                 equal or lower than to 48 MHz. This clock is derived of the main PLL or PLLSAI1
00211                 through PLLQ divider. You have to enable the peripheral clock and use
00212                 HAL_RCCEx_PeriphCLKConfig() function to configure this clock.
00213            (+@) IWDG clock which is always the LSI clock.
00214 
00215 
00216          (+) The maximum frequency of the SYSCLK, HCLK, PCLK1 and PCLK2 is 80 MHz.
00217              The clock source frequency should be adapted depending on the device voltage range
00218              as listed in the Reference Manual "Clock source frequency versus voltage scaling" chapter.
00219 
00220   @endverbatim
00221 
00222            Table 1. HCLK clock frequency for STM32L4Rx/STM32L4Sx devices
00223            +--------------------------------------------------------+
00224            | Latency         |     HCLK clock frequency (MHz)       |
00225            |                 |--------------------------------------|
00226            |                 |  voltage range 1  | voltage range 2  |
00227            |                 |       1.2 V       |     1.0 V        |
00228            |-----------------|-------------------|------------------|
00229            |0WS(1 CPU cycles)|   0 < HCLK <= 20  |  0 < HCLK <= 8   |
00230            |-----------------|-------------------|------------------|
00231            |1WS(2 CPU cycles)|  20 < HCLK <= 40  |  8 < HCLK <= 16  |
00232            |-----------------|-------------------|------------------|
00233            |2WS(3 CPU cycles)|  40 < HCLK <= 60  | 16 < HCLK <= 26  |
00234            |-----------------|-------------------|------------------|
00235            |3WS(4 CPU cycles)|  60 < HCLK <= 80  | 16 < HCLK <= 26  |
00236            |-----------------|-------------------|------------------|
00237            |4WS(5 CPU cycles)|  80 < HCLK <= 100 | 16 < HCLK <= 26  |
00238            |-----------------|-------------------|------------------|
00239            |5WS(6 CPU cycles)| 100 < HCLK <= 120 | 16 < HCLK <= 26  |
00240            +--------------------------------------------------------+
00241 
00242            Table 2. HCLK clock frequency for other STM32L4 devices
00243            +-------------------------------------------------------+
00244            | Latency         |    HCLK clock frequency (MHz)       |
00245            |                 |-------------------------------------|
00246            |                 | voltage range 1  | voltage range 2  |
00247            |                 |      1.2 V       |     1.0 V        |
00248            |-----------------|------------------|------------------|
00249            |0WS(1 CPU cycles)|  0 < HCLK <= 16  |  0 < HCLK <= 6   |
00250            |-----------------|------------------|------------------|
00251            |1WS(2 CPU cycles)| 16 < HCLK <= 32  |  6 < HCLK <= 12  |
00252            |-----------------|------------------|------------------|
00253            |2WS(3 CPU cycles)| 32 < HCLK <= 48  | 12 < HCLK <= 18  |
00254            |-----------------|------------------|------------------|
00255            |3WS(4 CPU cycles)| 48 < HCLK <= 64  | 18 < HCLK <= 26  |
00256            |-----------------|------------------|------------------|
00257            |4WS(5 CPU cycles)| 64 < HCLK <= 80  | 18 < HCLK <= 26  |
00258            +-------------------------------------------------------+
00259   * @{
00260   */
00261 
00262 /**
00263   * @brief  Reset the RCC clock configuration to the default reset state.
00264   * @note   The default reset state of the clock configuration is given below:
00265   *            - MSI ON and used as system clock source
00266   *            - HSE, HSI, PLL, PLLSAI1 and PLLISAI2 OFF
00267   *            - AHB, APB1 and APB2 prescaler set to 1.
00268   *            - CSS, MCO1 OFF
00269   *            - All interrupts disabled
00270   *            - All interrupt and reset flags cleared
00271   * @note   This function doesn't modify the configuration of the
00272   *            - Peripheral clocks
00273   *            - LSI, LSE and RTC clocks
00274   * @retval HAL status
00275   */
00276 HAL_StatusTypeDef HAL_RCC_DeInit(void)
00277 {
00278   uint32_t tickstart = 0;
00279 
00280   /* Set MSION bit */
00281   SET_BIT(RCC->CR, RCC_CR_MSION);
00282 
00283   /* Insure MSIRDY bit is set before writing default MSIRANGE value */
00284   /* Get start tick */
00285   tickstart = HAL_GetTick();
00286 
00287   /* Wait till MSI is ready */
00288   while(READ_BIT(RCC->CR, RCC_CR_MSIRDY) == RESET)
00289   {
00290     if((HAL_GetTick() - tickstart) > MSI_TIMEOUT_VALUE)
00291     {
00292       return HAL_TIMEOUT;
00293     }
00294   }
00295 
00296   /* Set MSIRANGE default value */
00297   MODIFY_REG(RCC->CR, RCC_CR_MSIRANGE, RCC_MSIRANGE_6);
00298 
00299   /* Reset CFGR register (MSI is selected as system clock source) */
00300   CLEAR_REG(RCC->CFGR);
00301 
00302   /* Update the SystemCoreClock global variable for MSI as system clock source */
00303   SystemCoreClock = MSI_VALUE;
00304 
00305   /* Configure the source of time base considering new system clock settings  */
00306   if(HAL_InitTick(TICK_INT_PRIORITY) != HAL_OK)
00307   {
00308     return HAL_ERROR;
00309   }
00310 
00311   /* Insure MSI selected as system clock source */
00312   /* Get start tick */
00313   tickstart = HAL_GetTick();
00314 
00315   /* Wait till system clock source is ready */
00316   while(READ_BIT(RCC->CFGR, RCC_CFGR_SWS) != RCC_CFGR_SWS_MSI)
00317   {
00318     if((HAL_GetTick() - tickstart) > CLOCKSWITCH_TIMEOUT_VALUE)
00319     {
00320       return HAL_TIMEOUT;
00321     }
00322   }
00323 
00324   /* Reset HSION, HSIKERON, HSIASFS, HSEON, HSECSSON, PLLON, PLLSAIxON bits */
00325 #if defined(RCC_PLLSAI2_SUPPORT)
00326 
00327   CLEAR_BIT(RCC->CR, RCC_CR_HSEON | RCC_CR_HSION | RCC_CR_HSIKERON| RCC_CR_HSIASFS | RCC_CR_PLLON | RCC_CR_PLLSAI1ON | RCC_CR_PLLSAI2ON);
00328 
00329 #else
00330 
00331   CLEAR_BIT(RCC->CR, RCC_CR_HSEON | RCC_CR_HSION | RCC_CR_HSIKERON| RCC_CR_HSIASFS | RCC_CR_PLLON | RCC_CR_PLLSAI1ON);
00332 
00333 #endif /* RCC_PLLSAI2_SUPPORT */
00334 
00335   /* Insure PLLRDY, PLLSAI1RDY and PLLSAI2RDY (if present) are reset */
00336   /* Get start tick */
00337   tickstart = HAL_GetTick();
00338 
00339 #if defined(RCC_PLLSAI2_SUPPORT)
00340 
00341   while(READ_BIT(RCC->CR, RCC_CR_PLLRDY | RCC_CR_PLLSAI1RDY | RCC_CR_PLLSAI2RDY) != 0U)
00342 
00343 #else
00344 
00345   while(READ_BIT(RCC->CR, RCC_CR_PLLRDY | RCC_CR_PLLSAI1RDY) != 0U)
00346 
00347 #endif
00348   {
00349     if((HAL_GetTick() - tickstart) > PLL_TIMEOUT_VALUE)
00350     {
00351       return HAL_TIMEOUT;
00352     }
00353   }
00354 
00355   /* Reset PLLCFGR register */
00356   CLEAR_REG(RCC->PLLCFGR);
00357   SET_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLN_4 );
00358 
00359   /* Reset PLLSAI1CFGR register */
00360   CLEAR_REG(RCC->PLLSAI1CFGR);
00361   SET_BIT(RCC->PLLSAI1CFGR,  RCC_PLLSAI1CFGR_PLLSAI1N_4 );
00362 
00363 #if defined(RCC_PLLSAI2_SUPPORT)
00364 
00365   /* Reset PLLSAI2CFGR register */
00366   CLEAR_REG(RCC->PLLSAI2CFGR);
00367   SET_BIT(RCC->PLLSAI2CFGR,  RCC_PLLSAI2CFGR_PLLSAI2N_4 );
00368 
00369 #endif /* RCC_PLLSAI2_SUPPORT */
00370 
00371   /* Reset HSEBYP bit */
00372   CLEAR_BIT(RCC->CR, RCC_CR_HSEBYP);
00373 
00374   /* Disable all interrupts */
00375   CLEAR_REG(RCC->CIER);
00376 
00377   /* Clear all interrupt flags */
00378   WRITE_REG(RCC->CICR, 0xFFFFFFFFU);
00379 
00380   /* Clear all reset flags */
00381   SET_BIT(RCC->CSR, RCC_CSR_RMVF);
00382 
00383   return HAL_OK;
00384 }
00385 
00386 /**
00387   * @brief  Initialize the RCC Oscillators according to the specified parameters in the
00388   *         RCC_OscInitTypeDef.
00389   * @param  RCC_OscInitStruct  pointer to an RCC_OscInitTypeDef structure that
00390   *         contains the configuration information for the RCC Oscillators.
00391   * @note   The PLL is not disabled when used as system clock.
00392   * @note   Transitions LSE Bypass to LSE On and LSE On to LSE Bypass are not
00393   *         supported by this macro. User should request a transition to LSE Off
00394   *         first and then LSE On or LSE Bypass.
00395   * @note   Transition HSE Bypass to HSE On and HSE On to HSE Bypass are not
00396   *         supported by this macro. User should request a transition to HSE Off
00397   *         first and then HSE On or HSE Bypass.
00398   * @retval HAL status
00399   */
00400 HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef  *RCC_OscInitStruct)
00401 {
00402   uint32_t tickstart;
00403 
00404   /* Check Null pointer */
00405   if(RCC_OscInitStruct == NULL)
00406   {
00407     return HAL_ERROR;
00408   }
00409 
00410   /* Check the parameters */
00411   assert_param(IS_RCC_OSCILLATORTYPE(RCC_OscInitStruct->OscillatorType));
00412 
00413   /*----------------------------- MSI Configuration --------------------------*/
00414   if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_MSI) == RCC_OSCILLATORTYPE_MSI)
00415   {
00416     /* Check the parameters */
00417     assert_param(IS_RCC_MSI(RCC_OscInitStruct->MSIState));
00418     assert_param(IS_RCC_MSICALIBRATION_VALUE(RCC_OscInitStruct->MSICalibrationValue));
00419     assert_param(IS_RCC_MSI_CLOCK_RANGE(RCC_OscInitStruct->MSIClockRange));
00420 
00421     /* When the MSI is used as system clock it will not be disabled */
00422     if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_MSI) )
00423     {
00424       if((READ_BIT(RCC->CR, RCC_CR_MSIRDY) != RESET) && (RCC_OscInitStruct->MSIState == RCC_MSI_OFF))
00425       {
00426         return HAL_ERROR;
00427       }
00428 
00429        /* Otherwise, just the calibration and MSI range change are allowed */
00430       else
00431       {
00432         /* To correctly read data from FLASH memory, the number of wait states (LATENCY)
00433            must be correctly programmed according to the frequency of the CPU clock
00434            (HCLK) and the supply voltage of the device. */
00435         if(RCC_OscInitStruct->MSIClockRange > __HAL_RCC_GET_MSI_RANGE())
00436         {
00437           /* First increase number of wait states update if necessary */
00438           if(RCC_SetFlashLatencyFromMSIRange(RCC_OscInitStruct->MSIClockRange) != HAL_OK)
00439           {
00440             return HAL_ERROR;
00441           }
00442 
00443           /* Selects the Multiple Speed oscillator (MSI) clock range .*/
00444           __HAL_RCC_MSI_RANGE_CONFIG(RCC_OscInitStruct->MSIClockRange);
00445           /* Adjusts the Multiple Speed oscillator (MSI) calibration value.*/
00446           __HAL_RCC_MSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->MSICalibrationValue);
00447         }
00448         else
00449         {
00450           /* Else, keep current flash latency while decreasing applies */
00451           /* Selects the Multiple Speed oscillator (MSI) clock range .*/
00452           __HAL_RCC_MSI_RANGE_CONFIG(RCC_OscInitStruct->MSIClockRange);
00453           /* Adjusts the Multiple Speed oscillator (MSI) calibration value.*/
00454           __HAL_RCC_MSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->MSICalibrationValue);
00455 
00456           /* Decrease number of wait states update if necessary */
00457           if(RCC_SetFlashLatencyFromMSIRange(RCC_OscInitStruct->MSIClockRange) != HAL_OK)
00458           {
00459             return HAL_ERROR;
00460           }
00461         }
00462 
00463         /* Update the SystemCoreClock global variable */
00464         SystemCoreClock = HAL_RCC_GetSysClockFreq() >> AHBPrescTable[READ_BIT(RCC->CFGR, RCC_CFGR_HPRE) >> RCC_CFGR_HPRE_Pos];
00465 
00466         /* Configure the source of time base considering new system clocks settings*/
00467         HAL_InitTick (TICK_INT_PRIORITY);
00468       }
00469     }
00470     else
00471     {
00472       /* Check the MSI State */
00473       if(RCC_OscInitStruct->MSIState != RCC_MSI_OFF)
00474       {
00475         /* Enable the Internal High Speed oscillator (MSI). */
00476         __HAL_RCC_MSI_ENABLE();
00477 
00478         /* Get timeout */
00479         tickstart = HAL_GetTick();
00480 
00481         /* Wait till MSI is ready */
00482         while(READ_BIT(RCC->CR, RCC_CR_MSIRDY) == RESET)
00483         {
00484           if((HAL_GetTick() - tickstart) > MSI_TIMEOUT_VALUE)
00485           {
00486             return HAL_TIMEOUT;
00487           }
00488         }
00489          /* Selects the Multiple Speed oscillator (MSI) clock range .*/
00490         __HAL_RCC_MSI_RANGE_CONFIG(RCC_OscInitStruct->MSIClockRange);
00491          /* Adjusts the Multiple Speed oscillator (MSI) calibration value.*/
00492         __HAL_RCC_MSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->MSICalibrationValue);
00493 
00494       }
00495       else
00496       {
00497         /* Disable the Internal High Speed oscillator (MSI). */
00498         __HAL_RCC_MSI_DISABLE();
00499 
00500         /* Get timeout */
00501         tickstart = HAL_GetTick();
00502 
00503         /* Wait till MSI is ready */
00504         while(READ_BIT(RCC->CR, RCC_CR_MSIRDY) != RESET)
00505         {
00506           if((HAL_GetTick() - tickstart) > MSI_TIMEOUT_VALUE)
00507           {
00508             return HAL_TIMEOUT;
00509           }
00510         }
00511       }
00512     }
00513   }
00514   /*------------------------------- HSE Configuration ------------------------*/
00515   if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSE) == RCC_OSCILLATORTYPE_HSE)
00516   {
00517     /* Check the parameters */
00518     assert_param(IS_RCC_HSE(RCC_OscInitStruct->HSEState));
00519 
00520     /* When the HSE is used as system clock or clock source for PLL in these cases it is not allowed to be disabled */
00521     if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSE) ||
00522        ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && (__HAL_RCC_GET_PLL_OSCSOURCE() == RCC_PLLSOURCE_HSE)))
00523     {
00524       if((READ_BIT(RCC->CR, RCC_CR_HSERDY) != RESET) && (RCC_OscInitStruct->HSEState == RCC_HSE_OFF))
00525       {
00526         return HAL_ERROR;
00527       }
00528     }
00529     else
00530     {
00531       /* Set the new HSE configuration ---------------------------------------*/
00532       __HAL_RCC_HSE_CONFIG(RCC_OscInitStruct->HSEState);
00533 
00534       /* Check the HSE State */
00535       if(RCC_OscInitStruct->HSEState != RCC_HSE_OFF)
00536       {
00537         /* Get Start Tick*/
00538         tickstart = HAL_GetTick();
00539 
00540         /* Wait till HSE is ready */
00541         while(READ_BIT(RCC->CR, RCC_CR_HSERDY) == RESET)
00542         {
00543           if((HAL_GetTick() - tickstart) > HSE_TIMEOUT_VALUE)
00544           {
00545             return HAL_TIMEOUT;
00546           }
00547         }
00548       }
00549       else
00550       {
00551         /* Get Start Tick*/
00552         tickstart = HAL_GetTick();
00553 
00554         /* Wait till HSE is disabled */
00555         while(READ_BIT(RCC->CR, RCC_CR_HSERDY) != RESET)
00556         {
00557           if((HAL_GetTick() - tickstart) > HSE_TIMEOUT_VALUE)
00558           {
00559             return HAL_TIMEOUT;
00560           }
00561         }
00562       }
00563     }
00564   }
00565   /*----------------------------- HSI Configuration --------------------------*/
00566   if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI) == RCC_OSCILLATORTYPE_HSI)
00567   {
00568     /* Check the parameters */
00569     assert_param(IS_RCC_HSI(RCC_OscInitStruct->HSIState));
00570     assert_param(IS_RCC_HSI_CALIBRATION_VALUE(RCC_OscInitStruct->HSICalibrationValue));
00571 
00572     /* Check if HSI is used as system clock or as PLL source when PLL is selected as system clock */
00573     if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSI) ||
00574        ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && (__HAL_RCC_GET_PLL_OSCSOURCE() == RCC_PLLSOURCE_HSI)))
00575     {
00576       /* When HSI is used as system clock it will not be disabled */
00577       if((READ_BIT(RCC->CR, RCC_CR_HSIRDY) != RESET) && (RCC_OscInitStruct->HSIState == RCC_HSI_OFF))
00578       {
00579         return HAL_ERROR;
00580       }
00581       /* Otherwise, just the calibration is allowed */
00582       else
00583       {
00584         /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/
00585         __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue);
00586       }
00587     }
00588     else
00589     {
00590       /* Check the HSI State */
00591       if(RCC_OscInitStruct->HSIState != RCC_HSI_OFF)
00592       {
00593         /* Enable the Internal High Speed oscillator (HSI). */
00594         __HAL_RCC_HSI_ENABLE();
00595 
00596         /* Get Start Tick*/
00597         tickstart = HAL_GetTick();
00598 
00599         /* Wait till HSI is ready */
00600         while(READ_BIT(RCC->CR, RCC_CR_HSIRDY) == RESET)
00601         {
00602           if((HAL_GetTick() - tickstart) > HSI_TIMEOUT_VALUE)
00603           {
00604             return HAL_TIMEOUT;
00605           }
00606         }
00607 
00608         /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/
00609         __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue);
00610       }
00611       else
00612       {
00613         /* Disable the Internal High Speed oscillator (HSI). */
00614         __HAL_RCC_HSI_DISABLE();
00615 
00616         /* Get Start Tick*/
00617         tickstart = HAL_GetTick();
00618 
00619         /* Wait till HSI is disabled */
00620         while(READ_BIT(RCC->CR, RCC_CR_HSIRDY) != RESET)
00621         {
00622           if((HAL_GetTick() - tickstart) > HSI_TIMEOUT_VALUE)
00623           {
00624             return HAL_TIMEOUT;
00625           }
00626         }
00627       }
00628     }
00629   }
00630   /*------------------------------ LSI Configuration -------------------------*/
00631   if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSI) == RCC_OSCILLATORTYPE_LSI)
00632   {
00633     /* Check the parameters */
00634     assert_param(IS_RCC_LSI(RCC_OscInitStruct->LSIState));
00635 
00636     /* Check the LSI State */
00637     if(RCC_OscInitStruct->LSIState != RCC_LSI_OFF)
00638     {
00639       /* Enable the Internal Low Speed oscillator (LSI). */
00640       __HAL_RCC_LSI_ENABLE();
00641 
00642       /* Get Start Tick*/
00643       tickstart = HAL_GetTick();
00644 
00645       /* Wait till LSI is ready */
00646       while(READ_BIT(RCC->CSR, RCC_CSR_LSIRDY) == RESET)
00647       {
00648         if((HAL_GetTick() - tickstart) > LSI_TIMEOUT_VALUE)
00649         {
00650           return HAL_TIMEOUT;
00651         }
00652       }
00653     }
00654     else
00655     {
00656       /* Disable the Internal Low Speed oscillator (LSI). */
00657       __HAL_RCC_LSI_DISABLE();
00658 
00659       /* Get Start Tick*/
00660       tickstart = HAL_GetTick();
00661 
00662       /* Wait till LSI is disabled */
00663       while(READ_BIT(RCC->CSR, RCC_CSR_LSIRDY) != RESET)
00664       {
00665         if((HAL_GetTick() - tickstart) > LSI_TIMEOUT_VALUE)
00666         {
00667           return HAL_TIMEOUT;
00668         }
00669       }
00670     }
00671   }
00672   /*------------------------------ LSE Configuration -------------------------*/
00673   if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSE) == RCC_OSCILLATORTYPE_LSE)
00674   {
00675     FlagStatus       pwrclkchanged = RESET;
00676 
00677     /* Check the parameters */
00678     assert_param(IS_RCC_LSE(RCC_OscInitStruct->LSEState));
00679 
00680     /* Update LSE configuration in Backup Domain control register    */
00681     /* Requires to enable write access to Backup Domain of necessary */
00682     if(HAL_IS_BIT_CLR(RCC->APB1ENR1, RCC_APB1ENR1_PWREN))
00683     {
00684       __HAL_RCC_PWR_CLK_ENABLE();
00685       pwrclkchanged = SET;
00686     }
00687 
00688     if(HAL_IS_BIT_CLR(PWR->CR1, PWR_CR1_DBP))
00689     {
00690       /* Enable write access to Backup domain */
00691       SET_BIT(PWR->CR1, PWR_CR1_DBP);
00692 
00693       /* Wait for Backup domain Write protection disable */
00694       tickstart = HAL_GetTick();
00695 
00696       while(HAL_IS_BIT_CLR(PWR->CR1, PWR_CR1_DBP))
00697       {
00698         if((HAL_GetTick() - tickstart) > RCC_DBP_TIMEOUT_VALUE)
00699         {
00700           return HAL_TIMEOUT;
00701         }
00702       }
00703     }
00704 
00705     /* Set the new LSE configuration -----------------------------------------*/
00706     __HAL_RCC_LSE_CONFIG(RCC_OscInitStruct->LSEState);
00707 
00708     /* Check the LSE State */
00709     if(RCC_OscInitStruct->LSEState != RCC_LSE_OFF)
00710     {
00711       /* Get Start Tick*/
00712       tickstart = HAL_GetTick();
00713 
00714       /* Wait till LSE is ready */
00715       while(READ_BIT(RCC->BDCR, RCC_BDCR_LSERDY) == RESET)
00716       {
00717         if((HAL_GetTick() - tickstart) > RCC_LSE_TIMEOUT_VALUE)
00718         {
00719           return HAL_TIMEOUT;
00720         }
00721       }
00722     }
00723     else
00724     {
00725       /* Get Start Tick*/
00726       tickstart = HAL_GetTick();
00727 
00728       /* Wait till LSE is disabled */
00729       while(READ_BIT(RCC->BDCR, RCC_BDCR_LSERDY) != RESET)
00730       {
00731         if((HAL_GetTick() - tickstart) > RCC_LSE_TIMEOUT_VALUE)
00732         {
00733           return HAL_TIMEOUT;
00734         }
00735       }
00736     }
00737 
00738     /* Restore clock configuration if changed */
00739     if(pwrclkchanged == SET)
00740     {
00741       __HAL_RCC_PWR_CLK_DISABLE();
00742     }
00743   }
00744 #if defined(RCC_HSI48_SUPPORT)
00745   /*------------------------------ HSI48 Configuration -----------------------*/
00746   if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI48) == RCC_OSCILLATORTYPE_HSI48)
00747   {
00748     /* Check the parameters */
00749     assert_param(IS_RCC_HSI48(RCC_OscInitStruct->HSI48State));
00750 
00751     /* Check the LSI State */
00752     if(RCC_OscInitStruct->HSI48State != RCC_HSI48_OFF)
00753     {
00754       /* Enable the Internal Low Speed oscillator (HSI48). */
00755       __HAL_RCC_HSI48_ENABLE();
00756 
00757       /* Get Start Tick*/
00758       tickstart = HAL_GetTick();
00759 
00760       /* Wait till HSI48 is ready */
00761       while(READ_BIT(RCC->CRRCR, RCC_CRRCR_HSI48RDY) == RESET)
00762       {
00763         if((HAL_GetTick() - tickstart) > HSI48_TIMEOUT_VALUE)
00764         {
00765           return HAL_TIMEOUT;
00766         }
00767       }
00768     }
00769     else
00770     {
00771       /* Disable the Internal Low Speed oscillator (HSI48). */
00772       __HAL_RCC_HSI48_DISABLE();
00773 
00774       /* Get Start Tick*/
00775       tickstart = HAL_GetTick();
00776 
00777       /* Wait till HSI48 is disabled */
00778       while(READ_BIT(RCC->CRRCR, RCC_CRRCR_HSI48RDY) != RESET)
00779       {
00780         if((HAL_GetTick() - tickstart) > HSI48_TIMEOUT_VALUE)
00781         {
00782           return HAL_TIMEOUT;
00783         }
00784       }
00785     }
00786   }
00787 #endif /* RCC_HSI48_SUPPORT */
00788   /*-------------------------------- PLL Configuration -----------------------*/
00789   /* Check the parameters */
00790   assert_param(IS_RCC_PLL(RCC_OscInitStruct->PLL.PLLState));
00791 
00792   if(RCC_OscInitStruct->PLL.PLLState != RCC_PLL_NONE)
00793   {
00794     /* Check if the PLL is used as system clock or not */
00795     if(__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_CFGR_SWS_PLL)
00796     {
00797       if(RCC_OscInitStruct->PLL.PLLState == RCC_PLL_ON)
00798       {
00799         /* Check the parameters */
00800         assert_param(IS_RCC_PLLSOURCE(RCC_OscInitStruct->PLL.PLLSource));
00801         assert_param(IS_RCC_PLLM_VALUE(RCC_OscInitStruct->PLL.PLLM));
00802         assert_param(IS_RCC_PLLN_VALUE(RCC_OscInitStruct->PLL.PLLN));
00803         assert_param(IS_RCC_PLLP_VALUE(RCC_OscInitStruct->PLL.PLLP));
00804         assert_param(IS_RCC_PLLQ_VALUE(RCC_OscInitStruct->PLL.PLLQ));
00805         assert_param(IS_RCC_PLLR_VALUE(RCC_OscInitStruct->PLL.PLLR));
00806 
00807         /* Disable the main PLL. */
00808         __HAL_RCC_PLL_DISABLE();
00809 
00810         /* Get Start Tick*/
00811         tickstart = HAL_GetTick();
00812 
00813         /* Wait till PLL is ready */
00814         while(READ_BIT(RCC->CR, RCC_CR_PLLRDY) != RESET)
00815         {
00816           if((HAL_GetTick() - tickstart) > PLL_TIMEOUT_VALUE)
00817           {
00818             return HAL_TIMEOUT;
00819           }
00820         }
00821 
00822         /* Configure the main PLL clock source, multiplication and division factors. */
00823         __HAL_RCC_PLL_CONFIG(RCC_OscInitStruct->PLL.PLLSource,
00824                              RCC_OscInitStruct->PLL.PLLM,
00825                              RCC_OscInitStruct->PLL.PLLN,
00826                              RCC_OscInitStruct->PLL.PLLP,
00827                              RCC_OscInitStruct->PLL.PLLQ,
00828                              RCC_OscInitStruct->PLL.PLLR);
00829 
00830         /* Enable the main PLL. */
00831         __HAL_RCC_PLL_ENABLE();
00832 
00833         /* Enable PLL System Clock output. */
00834          __HAL_RCC_PLLCLKOUT_ENABLE(RCC_PLL_SYSCLK);
00835 
00836         /* Get Start Tick*/
00837         tickstart = HAL_GetTick();
00838 
00839         /* Wait till PLL is ready */
00840         while(READ_BIT(RCC->CR, RCC_CR_PLLRDY) == RESET)
00841         {
00842           if((HAL_GetTick() - tickstart) > PLL_TIMEOUT_VALUE)
00843           {
00844             return HAL_TIMEOUT;
00845           }
00846         }
00847       }
00848       else
00849       {
00850         /* Disable the main PLL. */
00851         __HAL_RCC_PLL_DISABLE();
00852 
00853         /* Disable all PLL outputs to save power if no PLLs on */
00854         if((READ_BIT(RCC->CR, RCC_CR_PLLSAI1RDY) == RESET)
00855 #if defined(RCC_PLLSAI2_SUPPORT)
00856            &&
00857            (READ_BIT(RCC->CR, RCC_CR_PLLSAI2RDY) == RESET)
00858 #endif /* RCC_PLLSAI2_SUPPORT */
00859           )
00860         {
00861           MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, RCC_PLLSOURCE_NONE);
00862         }
00863 
00864 #if defined(RCC_PLLSAI2_SUPPORT)
00865         __HAL_RCC_PLLCLKOUT_DISABLE(RCC_PLL_SYSCLK | RCC_PLL_48M1CLK | RCC_PLL_SAI3CLK);
00866 #else
00867         __HAL_RCC_PLLCLKOUT_DISABLE(RCC_PLL_SYSCLK | RCC_PLL_48M1CLK | RCC_PLL_SAI2CLK);
00868 #endif /* RCC_PLLSAI2_SUPPORT */
00869 
00870         /* Get Start Tick*/
00871         tickstart = HAL_GetTick();
00872 
00873         /* Wait till PLL is disabled */
00874         while(READ_BIT(RCC->CR, RCC_CR_PLLRDY) != RESET)
00875         {
00876           if((HAL_GetTick() - tickstart) > PLL_TIMEOUT_VALUE)
00877           {
00878             return HAL_TIMEOUT;
00879           }
00880         }
00881       }
00882     }
00883     else
00884     {
00885       return HAL_ERROR;
00886     }
00887   }
00888   return HAL_OK;
00889 }
00890 
00891 /**
00892   * @brief  Initialize the CPU, AHB and APB busses clocks according to the specified
00893   *         parameters in the RCC_ClkInitStruct.
00894   * @param  RCC_ClkInitStruct  pointer to an RCC_OscInitTypeDef structure that
00895   *         contains the configuration information for the RCC peripheral.
00896   * @param  FLatency  FLASH Latency
00897   *          This parameter can be one of the following values:
00898   *            @arg FLASH_LATENCY_0   FLASH 0 Latency cycle
00899   *            @arg FLASH_LATENCY_1   FLASH 1 Latency cycle
00900   *            @arg FLASH_LATENCY_2   FLASH 2 Latency cycles
00901   *            @arg FLASH_LATENCY_3   FLASH 3 Latency cycles
00902   *            @arg FLASH_LATENCY_4   FLASH 4 Latency cycles
00903   @if STM32L4S9xx
00904   *            @arg FLASH_LATENCY_5   FLASH 5 Latency cycles
00905   *            @arg FLASH_LATENCY_6   FLASH 6 Latency cycles
00906   *            @arg FLASH_LATENCY_7   FLASH 7 Latency cycles
00907   *            @arg FLASH_LATENCY_8   FLASH 8 Latency cycles
00908   *            @arg FLASH_LATENCY_9   FLASH 9 Latency cycles
00909   *            @arg FLASH_LATENCY_10  FLASH 10 Latency cycles
00910   *            @arg FLASH_LATENCY_11  FLASH 11 Latency cycles
00911   *            @arg FLASH_LATENCY_12  FLASH 12 Latency cycles
00912   *            @arg FLASH_LATENCY_13  FLASH 13 Latency cycles
00913   *            @arg FLASH_LATENCY_14  FLASH 14 Latency cycles
00914   *            @arg FLASH_LATENCY_15  FLASH 15 Latency cycles
00915   @endif
00916   *
00917   * @note   The SystemCoreClock CMSIS variable is used to store System Clock Frequency
00918   *         and updated by HAL_RCC_GetHCLKFreq() function called within this function
00919   *
00920   * @note   The MSI is used by default as system clock source after
00921   *         startup from Reset, wake-up from STANDBY mode. After restart from Reset,
00922   *         the MSI frequency is set to its default value 4 MHz.
00923   *
00924   * @note   The HSI can be selected as system clock source after
00925   *         from STOP modes or in case of failure of the HSE used directly or indirectly
00926   *         as system clock (if the Clock Security System CSS is enabled).
00927   *
00928   * @note   A switch from one clock source to another occurs only if the target
00929   *         clock source is ready (clock stable after startup delay or PLL locked).
00930   *         If a clock source which is not yet ready is selected, the switch will
00931   *         occur when the clock source is ready.
00932   *
00933   * @note   You can use HAL_RCC_GetClockConfig() function to know which clock is
00934   *         currently used as system clock source.
00935   *
00936   * @note   Depending on the device voltage range, the software has to set correctly
00937   *         HPRE[3:0] bits to ensure that HCLK not exceed the maximum allowed frequency
00938   *         (for more details refer to section above "Initialization/de-initialization functions")
00939   * @retval None
00940   */
00941 HAL_StatusTypeDef HAL_RCC_ClockConfig(RCC_ClkInitTypeDef  *RCC_ClkInitStruct, uint32_t FLatency)
00942 {
00943   uint32_t tickstart;
00944 #if defined(STM32L4R5xx) || defined(STM32L4R7xx) || defined(STM32L4R9xx) || defined(STM32L4S5xx) || defined(STM32L4S7xx) || defined(STM32L4S9xx)
00945   uint32_t pllfreq = 0;
00946   uint32_t hpre = RCC_SYSCLK_DIV1;
00947 #endif
00948 
00949   /* Check Null pointer */
00950   if(RCC_ClkInitStruct == NULL)
00951   {
00952     return HAL_ERROR;
00953   }
00954 
00955   /* Check the parameters */
00956   assert_param(IS_RCC_CLOCKTYPE(RCC_ClkInitStruct->ClockType));
00957   assert_param(IS_FLASH_LATENCY(FLatency));
00958 
00959   /* To correctly read data from FLASH memory, the number of wait states (LATENCY)
00960     must be correctly programmed according to the frequency of the CPU clock
00961     (HCLK) and the supply voltage of the device. */
00962 
00963   /* Increasing the number of wait states because of higher CPU frequency */
00964   if(FLatency > __HAL_FLASH_GET_LATENCY())
00965   {
00966     /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */
00967     __HAL_FLASH_SET_LATENCY(FLatency);
00968 
00969     /* Check that the new number of wait states is taken into account to access the Flash
00970     memory by reading the FLASH_ACR register */
00971     if(__HAL_FLASH_GET_LATENCY() != FLatency)
00972     {
00973       return HAL_ERROR;
00974     }
00975   }
00976 
00977   /*------------------------- SYSCLK Configuration ---------------------------*/
00978   if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_SYSCLK) == RCC_CLOCKTYPE_SYSCLK)
00979   {
00980     assert_param(IS_RCC_SYSCLKSOURCE(RCC_ClkInitStruct->SYSCLKSource));
00981 
00982     /* PLL is selected as System Clock Source */
00983     if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_PLLCLK)
00984     {
00985       /* Check the PLL ready flag */
00986       if(READ_BIT(RCC->CR, RCC_CR_PLLRDY) == RESET)
00987       {
00988         return HAL_ERROR;
00989       }
00990 #if defined(STM32L4R5xx) || defined(STM32L4R7xx) || defined(STM32L4R9xx) || defined(STM32L4S5xx) || defined(STM32L4S7xx) || defined(STM32L4S9xx)
00991       /* Undershoot management when selection PLL as SYSCLK source and frequency above 80Mhz */
00992       /* Compute target PLL output frequency */
00993       pllfreq = RCC_GetSysClockFreqFromPLLSource();
00994 
00995       /* Intermediate step with HCLK prescaler 2 necessary before to go over 80Mhz */
00996       if((pllfreq > 80000000U) &&
00997          (((((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_HCLK) == RCC_CLOCKTYPE_HCLK) && (RCC_ClkInitStruct->AHBCLKDivider == RCC_SYSCLK_DIV1))
00998           ||
00999           ((READ_BIT(RCC->CFGR, RCC_CFGR_HPRE) == RCC_SYSCLK_DIV1))))
01000       {
01001         MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, RCC_SYSCLK_DIV2);
01002         hpre = RCC_SYSCLK_DIV2;
01003       }
01004 #endif
01005     }
01006     else
01007     {
01008       /* HSE is selected as System Clock Source */
01009       if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_HSE)
01010       {
01011         /* Check the HSE ready flag */
01012         if(READ_BIT(RCC->CR, RCC_CR_HSERDY) == RESET)
01013         {
01014           return HAL_ERROR;
01015         }
01016       }
01017       /* MSI is selected as System Clock Source */
01018       else if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_MSI)
01019       {
01020         /* Check the MSI ready flag */
01021         if(READ_BIT(RCC->CR, RCC_CR_MSIRDY) == RESET)
01022         {
01023           return HAL_ERROR;
01024         }
01025       }
01026       /* HSI is selected as System Clock Source */
01027       else
01028       {
01029         /* Check the HSI ready flag */
01030         if(READ_BIT(RCC->CR, RCC_CR_HSIRDY) == RESET)
01031         {
01032           return HAL_ERROR;
01033         }
01034       }
01035 #if defined(STM32L4R5xx) || defined(STM32L4R7xx) || defined(STM32L4R9xx) || defined(STM32L4S5xx) || defined(STM32L4S7xx) || defined(STM32L4S9xx)
01036       /* Overshoot management when going down from PLL as SYSCLK source and frequency above 80Mhz */
01037       pllfreq = HAL_RCC_GetSysClockFreq();
01038 
01039       /* Intermediate step with HCLK prescaler 2 necessary before to go under 80Mhz */
01040       if(pllfreq > 80000000U)
01041       {
01042         MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, RCC_SYSCLK_DIV2);
01043         hpre = RCC_SYSCLK_DIV2;
01044       }
01045 #endif
01046 
01047     }
01048 
01049     MODIFY_REG(RCC->CFGR, RCC_CFGR_SW, RCC_ClkInitStruct->SYSCLKSource);
01050 
01051     /* Get Start Tick*/
01052     tickstart = HAL_GetTick();
01053 
01054     while(__HAL_RCC_GET_SYSCLK_SOURCE() != (RCC_ClkInitStruct->SYSCLKSource << RCC_CFGR_SWS_Pos))
01055     {
01056       if((HAL_GetTick() - tickstart) > CLOCKSWITCH_TIMEOUT_VALUE)
01057       {
01058         return HAL_TIMEOUT;
01059       }
01060     }
01061   }
01062 
01063   /*-------------------------- HCLK Configuration --------------------------*/
01064   if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_HCLK) == RCC_CLOCKTYPE_HCLK)
01065   {
01066     assert_param(IS_RCC_HCLK(RCC_ClkInitStruct->AHBCLKDivider));
01067     MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, RCC_ClkInitStruct->AHBCLKDivider);
01068   }
01069 #if defined(STM32L4R5xx) || defined(STM32L4R7xx) || defined(STM32L4R9xx) || defined(STM32L4S5xx) || defined(STM32L4S7xx) || defined(STM32L4S9xx)
01070   else
01071   {
01072     /* Is intermediate HCLK prescaler 2 applied internally, complete with HCLK prescaler 1 */
01073     if(hpre == RCC_SYSCLK_DIV2)
01074     {
01075       MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, RCC_SYSCLK_DIV1);
01076     }
01077   }
01078 #endif
01079 
01080   /* Decreasing the number of wait states because of lower CPU frequency */
01081   if(FLatency < __HAL_FLASH_GET_LATENCY())
01082   {
01083     /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */
01084     __HAL_FLASH_SET_LATENCY(FLatency);
01085 
01086     /* Check that the new number of wait states is taken into account to access the Flash
01087     memory by reading the FLASH_ACR register */
01088     if(__HAL_FLASH_GET_LATENCY() != FLatency)
01089     {
01090       return HAL_ERROR;
01091     }
01092   }
01093 
01094   /*-------------------------- PCLK1 Configuration ---------------------------*/
01095   if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1)
01096   {
01097     assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB1CLKDivider));
01098     MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, RCC_ClkInitStruct->APB1CLKDivider);
01099   }
01100 
01101   /*-------------------------- PCLK2 Configuration ---------------------------*/
01102   if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2)
01103   {
01104     assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB2CLKDivider));
01105     MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, ((RCC_ClkInitStruct->APB2CLKDivider) << 3U));
01106   }
01107 
01108   /* Update the SystemCoreClock global variable */
01109   SystemCoreClock = HAL_RCC_GetSysClockFreq() >> AHBPrescTable[READ_BIT(RCC->CFGR, RCC_CFGR_HPRE) >> RCC_CFGR_HPRE_Pos];
01110 
01111   /* Configure the source of time base considering new system clocks settings*/
01112   HAL_InitTick (TICK_INT_PRIORITY);
01113 
01114   return HAL_OK;
01115 }
01116 
01117 /**
01118   * @}
01119   */
01120 
01121 /** @defgroup RCC_Exported_Functions_Group2 Peripheral Control functions
01122  *  @brief   RCC clocks control functions
01123  *
01124 @verbatim
01125  ===============================================================================
01126                       ##### Peripheral Control functions #####
01127  ===============================================================================
01128     [..]
01129     This subsection provides a set of functions allowing to:
01130 
01131     (+) Ouput clock to MCO pin.
01132     (+) Retrieve current clock frequencies.
01133     (+) Enable the Clock Security System.
01134 
01135 @endverbatim
01136   * @{
01137   */
01138 
01139 /**
01140   * @brief  Select the clock source to output on MCO pin(PA8).
01141   * @note   PA8 should be configured in alternate function mode.
01142   * @param  RCC_MCOx  specifies the output direction for the clock source.
01143   *          For STM32L4xx family this parameter can have only one value:
01144   *            @arg @ref RCC_MCO1  Clock source to output on MCO1 pin(PA8).
01145   * @param  RCC_MCOSource  specifies the clock source to output.
01146   *          This parameter can be one of the following values:
01147   *            @arg @ref RCC_MCO1SOURCE_NOCLOCK  MCO output disabled, no clock on MCO
01148   *            @arg @ref RCC_MCO1SOURCE_SYSCLK  system  clock selected as MCO source
01149   *            @arg @ref RCC_MCO1SOURCE_MSI  MSI clock selected as MCO source
01150   *            @arg @ref RCC_MCO1SOURCE_HSI  HSI clock selected as MCO source
01151   *            @arg @ref RCC_MCO1SOURCE_HSE  HSE clock selected as MCO sourcee
01152   *            @arg @ref RCC_MCO1SOURCE_PLLCLK  main PLL clock selected as MCO source
01153   *            @arg @ref RCC_MCO1SOURCE_LSI  LSI clock selected as MCO source
01154   *            @arg @ref RCC_MCO1SOURCE_LSE  LSE clock selected as MCO source
01155   @if STM32L443xx
01156   *            @arg @ref RCC_MCO1SOURCE_HSI48  HSI48 clock selected as MCO source for devices with HSI48
01157   @endif
01158   * @param  RCC_MCODiv  specifies the MCO prescaler.
01159   *          This parameter can be one of the following values:
01160   *            @arg @ref RCC_MCODIV_1  no division applied to MCO clock
01161   *            @arg @ref RCC_MCODIV_2  division by 2 applied to MCO clock
01162   *            @arg @ref RCC_MCODIV_4  division by 4 applied to MCO clock
01163   *            @arg @ref RCC_MCODIV_8  division by 8 applied to MCO clock
01164   *            @arg @ref RCC_MCODIV_16  division by 16 applied to MCO clock
01165   * @retval None
01166   */
01167 void HAL_RCC_MCOConfig( uint32_t RCC_MCOx, uint32_t RCC_MCOSource, uint32_t RCC_MCODiv)
01168 {
01169   GPIO_InitTypeDef GPIO_InitStruct;
01170 
01171   /* Check the parameters */
01172   assert_param(IS_RCC_MCO(RCC_MCOx));
01173   assert_param(IS_RCC_MCODIV(RCC_MCODiv));
01174   assert_param(IS_RCC_MCO1SOURCE(RCC_MCOSource));
01175 
01176   /* Prevent unused argument(s) compilation warning if no assert_param check */
01177   UNUSED(RCC_MCOx);
01178 
01179   /* MCO Clock Enable */
01180   __MCO1_CLK_ENABLE();
01181 
01182   /* Configue the MCO1 pin in alternate function mode */
01183   GPIO_InitStruct.Pin = MCO1_PIN;
01184   GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
01185   GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
01186   GPIO_InitStruct.Pull = GPIO_NOPULL;
01187   GPIO_InitStruct.Alternate = GPIO_AF0_MCO;
01188   HAL_GPIO_Init(MCO1_GPIO_PORT, &GPIO_InitStruct);
01189 
01190   /* Mask MCOSEL[] and MCOPRE[] bits then set MCO1 clock source and prescaler */
01191   MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCOSEL | RCC_CFGR_MCOPRE), (RCC_MCOSource | RCC_MCODiv ));
01192 }
01193 
01194 /**
01195   * @brief  Return the SYSCLK frequency.
01196   *
01197   * @note   The system frequency computed by this function is not the real
01198   *         frequency in the chip. It is calculated based on the predefined
01199   *         constant and the selected clock source:
01200   * @note     If SYSCLK source is MSI, function returns values based on MSI
01201   *             Value as defined by the MSI range.
01202   * @note     If SYSCLK source is HSI, function returns values based on HSI_VALUE(*)
01203   * @note     If SYSCLK source is HSE, function returns values based on HSE_VALUE(**)
01204   * @note     If SYSCLK source is PLL, function returns values based on HSE_VALUE(**),
01205   *           HSI_VALUE(*) or MSI Value multiplied/divided by the PLL factors.
01206   * @note     (*) HSI_VALUE is a constant defined in stm32l4xx_hal_conf.h file (default value
01207   *               16 MHz) but the real value may vary depending on the variations
01208   *               in voltage and temperature.
01209   * @note     (**) HSE_VALUE is a constant defined in stm32l4xx_hal_conf.h file (default value
01210   *                8 MHz), user has to ensure that HSE_VALUE is same as the real
01211   *                frequency of the crystal used. Otherwise, this function may
01212   *                have wrong result.
01213   *
01214   * @note   The result of this function could be not correct when using fractional
01215   *         value for HSE crystal.
01216   *
01217   * @note   This function can be used by the user application to compute the
01218   *         baudrate for the communication peripherals or configure other parameters.
01219   *
01220   * @note   Each time SYSCLK changes, this function must be called to update the
01221   *         right SYSCLK value. Otherwise, any configuration based on this function will be incorrect.
01222   *
01223   *
01224   * @retval SYSCLK frequency
01225   */
01226 uint32_t HAL_RCC_GetSysClockFreq(void)
01227 {
01228   uint32_t msirange = 0U, pllvco = 0U, pllsource = 0U, pllr = 2U, pllm = 2U;
01229   uint32_t sysclockfreq = 0U;
01230 
01231   if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_MSI) ||
01232      ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && (__HAL_RCC_GET_PLL_OSCSOURCE() == RCC_PLLSOURCE_MSI)))
01233   {
01234     /* MSI or PLL with MSI source used as system clock source */
01235 
01236     /* Get SYSCLK source */
01237     if(READ_BIT(RCC->CR, RCC_CR_MSIRGSEL) == RESET)
01238     { /* MSISRANGE from RCC_CSR applies */
01239       msirange = READ_BIT(RCC->CSR, RCC_CSR_MSISRANGE) >> RCC_CSR_MSISRANGE_Pos;
01240     }
01241     else
01242     { /* MSIRANGE from RCC_CR applies */
01243       msirange = READ_BIT(RCC->CR, RCC_CR_MSIRANGE) >> RCC_CR_MSIRANGE_Pos;
01244     }
01245     /*MSI frequency range in HZ*/
01246     msirange = MSIRangeTable[msirange];
01247 
01248     if(__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_MSI)
01249     {
01250       /* MSI used as system clock source */
01251       sysclockfreq = msirange;
01252     }
01253   }
01254   else if(__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSI)
01255   {
01256     /* HSI used as system clock source */
01257     sysclockfreq = HSI_VALUE;
01258   }
01259   else if(__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSE)
01260   {
01261     /* HSE used as system clock source */
01262     sysclockfreq = HSE_VALUE;
01263   }
01264 
01265   if(__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL)
01266   {
01267     /* PLL used as system clock  source */
01268 
01269     /* PLL_VCO = (HSE_VALUE or HSI_VALUE or MSI_VALUE/ PLLM) * PLLN
01270     SYSCLK = PLL_VCO / PLLR
01271     */
01272     pllsource = READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC);
01273     pllm = (READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLM) >> RCC_PLLCFGR_PLLM_Pos) + 1U ;
01274 
01275     switch (pllsource)
01276     {
01277     case RCC_PLLSOURCE_HSI:  /* HSI used as PLL clock source */
01278       pllvco = (HSI_VALUE / pllm) * (READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos);
01279       break;
01280 
01281     case RCC_PLLSOURCE_HSE:  /* HSE used as PLL clock source */
01282       pllvco = (HSE_VALUE / pllm) * (READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos);
01283       break;
01284 
01285     case RCC_PLLSOURCE_MSI:  /* MSI used as PLL clock source */
01286     default:
01287       pllvco = (msirange / pllm) * (READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos);
01288       break;
01289     }
01290     pllr = ((READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLR) >> RCC_PLLCFGR_PLLR_Pos) + 1U ) * 2U;
01291     sysclockfreq = pllvco/pllr;
01292   }
01293 
01294   return sysclockfreq;
01295 }
01296 
01297 /**
01298   * @brief  Return the HCLK frequency.
01299   * @note   Each time HCLK changes, this function must be called to update the
01300   *         right HCLK value. Otherwise, any configuration based on this function will be incorrect.
01301   *
01302   * @note   The SystemCoreClock CMSIS variable is used to store System Clock Frequency.
01303   * @retval HCLK frequency in Hz
01304   */
01305 uint32_t HAL_RCC_GetHCLKFreq(void)
01306 {
01307   return SystemCoreClock;
01308 }
01309 
01310 /**
01311   * @brief  Return the PCLK1 frequency.
01312   * @note   Each time PCLK1 changes, this function must be called to update the
01313   *         right PCLK1 value. Otherwise, any configuration based on this function will be incorrect.
01314   * @retval PCLK1 frequency in Hz
01315   */
01316 uint32_t HAL_RCC_GetPCLK1Freq(void)
01317 {
01318   /* Get HCLK source and Compute PCLK1 frequency ---------------------------*/
01319   return (HAL_RCC_GetHCLKFreq() >> APBPrescTable[READ_BIT(RCC->CFGR, RCC_CFGR_PPRE1) >> RCC_CFGR_PPRE1_Pos]);
01320 }
01321 
01322 /**
01323   * @brief  Return the PCLK2 frequency.
01324   * @note   Each time PCLK2 changes, this function must be called to update the
01325   *         right PCLK2 value. Otherwise, any configuration based on this function will be incorrect.
01326   * @retval PCLK2 frequency in Hz
01327   */
01328 uint32_t HAL_RCC_GetPCLK2Freq(void)
01329 {
01330   /* Get HCLK source and Compute PCLK2 frequency ---------------------------*/
01331   return (HAL_RCC_GetHCLKFreq()>> APBPrescTable[READ_BIT(RCC->CFGR, RCC_CFGR_PPRE2) >> RCC_CFGR_PPRE2_Pos]);
01332 }
01333 
01334 /**
01335   * @brief  Configure the RCC_OscInitStruct according to the internal
01336   *         RCC configuration registers.
01337   * @param  RCC_OscInitStruct  pointer to an RCC_OscInitTypeDef structure that
01338   *         will be configured.
01339   * @retval None
01340   */
01341 void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef  *RCC_OscInitStruct)
01342 {
01343   /* Check the parameters */
01344   assert_param(RCC_OscInitStruct != NULL);
01345 
01346   /* Set all possible values for the Oscillator type parameter ---------------*/
01347 #if defined(RCC_HSI48_SUPPORT)
01348   RCC_OscInitStruct->OscillatorType = RCC_OSCILLATORTYPE_HSE | RCC_OSCILLATORTYPE_HSI | RCC_OSCILLATORTYPE_MSI | \
01349                                       RCC_OSCILLATORTYPE_LSE | RCC_OSCILLATORTYPE_LSI | RCC_OSCILLATORTYPE_HSI48;
01350 #else
01351   RCC_OscInitStruct->OscillatorType = RCC_OSCILLATORTYPE_HSE | RCC_OSCILLATORTYPE_HSI | RCC_OSCILLATORTYPE_MSI | \
01352                                       RCC_OSCILLATORTYPE_LSE | RCC_OSCILLATORTYPE_LSI;
01353 #endif /* RCC_HSI48_SUPPORT */
01354 
01355   /* Get the HSE configuration -----------------------------------------------*/
01356   if(READ_BIT(RCC->CR, RCC_CR_HSEBYP) == RCC_CR_HSEBYP)
01357   {
01358     RCC_OscInitStruct->HSEState = RCC_HSE_BYPASS;
01359   }
01360   else if(READ_BIT(RCC->CR, RCC_CR_HSEON) == RCC_CR_HSEON)
01361   {
01362     RCC_OscInitStruct->HSEState = RCC_HSE_ON;
01363   }
01364   else
01365   {
01366     RCC_OscInitStruct->HSEState = RCC_HSE_OFF;
01367   }
01368 
01369    /* Get the MSI configuration -----------------------------------------------*/
01370   if(READ_BIT(RCC->CR, RCC_CR_MSION) == RCC_CR_MSION)
01371   {
01372     RCC_OscInitStruct->MSIState = RCC_MSI_ON;
01373   }
01374   else
01375   {
01376     RCC_OscInitStruct->MSIState = RCC_MSI_OFF;
01377   }
01378 
01379   RCC_OscInitStruct->MSICalibrationValue = READ_BIT(RCC->ICSCR, RCC_ICSCR_MSITRIM) >> RCC_ICSCR_MSITRIM_Pos;
01380   RCC_OscInitStruct->MSIClockRange = READ_BIT(RCC->CR, RCC_CR_MSIRANGE);
01381 
01382   /* Get the HSI configuration -----------------------------------------------*/
01383   if(READ_BIT(RCC->CR, RCC_CR_HSION) == RCC_CR_HSION)
01384   {
01385     RCC_OscInitStruct->HSIState = RCC_HSI_ON;
01386   }
01387   else
01388   {
01389     RCC_OscInitStruct->HSIState = RCC_HSI_OFF;
01390   }
01391 
01392   RCC_OscInitStruct->HSICalibrationValue = READ_BIT(RCC->ICSCR, RCC_ICSCR_HSITRIM) >> RCC_ICSCR_HSITRIM_Pos;
01393 
01394   /* Get the LSE configuration -----------------------------------------------*/
01395   if(READ_BIT(RCC->BDCR, RCC_BDCR_LSEBYP) == RCC_BDCR_LSEBYP)
01396   {
01397     RCC_OscInitStruct->LSEState = RCC_LSE_BYPASS;
01398   }
01399   else if(READ_BIT(RCC->BDCR, RCC_BDCR_LSEON) == RCC_BDCR_LSEON)
01400   {
01401     RCC_OscInitStruct->LSEState = RCC_LSE_ON;
01402   }
01403   else
01404   {
01405     RCC_OscInitStruct->LSEState = RCC_LSE_OFF;
01406   }
01407 
01408   /* Get the LSI configuration -----------------------------------------------*/
01409   if(READ_BIT(RCC->CSR, RCC_CSR_LSION) == RCC_CSR_LSION)
01410   {
01411     RCC_OscInitStruct->LSIState = RCC_LSI_ON;
01412   }
01413   else
01414   {
01415     RCC_OscInitStruct->LSIState = RCC_LSI_OFF;
01416   }
01417 
01418 #if defined(RCC_HSI48_SUPPORT)
01419   /* Get the HSI48 configuration ---------------------------------------------*/
01420   if(READ_BIT(RCC->CRRCR, RCC_CRRCR_HSI48ON) == RCC_CRRCR_HSI48ON)
01421   {
01422     RCC_OscInitStruct->HSI48State = RCC_HSI48_ON;
01423   }
01424   else
01425   {
01426     RCC_OscInitStruct->HSI48State = RCC_HSI48_OFF;
01427   }
01428 #else
01429   RCC_OscInitStruct->HSI48State = RCC_HSI48_OFF;
01430 #endif /* RCC_HSI48_SUPPORT */
01431 
01432   /* Get the PLL configuration -----------------------------------------------*/
01433   if(READ_BIT(RCC->CR, RCC_CR_PLLON) == RCC_CR_PLLON)
01434   {
01435     RCC_OscInitStruct->PLL.PLLState = RCC_PLL_ON;
01436   }
01437   else
01438   {
01439     RCC_OscInitStruct->PLL.PLLState = RCC_PLL_OFF;
01440   }
01441   RCC_OscInitStruct->PLL.PLLSource = READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC);
01442   RCC_OscInitStruct->PLL.PLLM = (READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLM) >> RCC_PLLCFGR_PLLM_Pos) + 1U;
01443   RCC_OscInitStruct->PLL.PLLN = READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos;
01444   RCC_OscInitStruct->PLL.PLLQ = (((READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLQ) >> RCC_PLLCFGR_PLLQ_Pos) + 1U) << 1U);
01445   RCC_OscInitStruct->PLL.PLLR = (((READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLR) >> RCC_PLLCFGR_PLLR_Pos) + 1U) << 1U);
01446 #if defined(RCC_PLLP_DIV_2_31_SUPPORT)
01447   RCC_OscInitStruct->PLL.PLLP = READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLPDIV) >> RCC_PLLCFGR_PLLPDIV_Pos;
01448 #else
01449   if(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLP) != RESET)
01450   {
01451     RCC_OscInitStruct->PLL.PLLP = RCC_PLLP_DIV17;
01452   }
01453   else
01454   {
01455     RCC_OscInitStruct->PLL.PLLP = RCC_PLLP_DIV7;
01456   }
01457 #endif /* RCC_PLLP_DIV_2_31_SUPPORT */
01458 }
01459 
01460 /**
01461   * @brief  Configure the RCC_ClkInitStruct according to the internal
01462   *         RCC configuration registers.
01463   * @param  RCC_ClkInitStruct  pointer to an RCC_ClkInitTypeDef structure that
01464   *         will be configured.
01465   * @param  pFLatency  Pointer on the Flash Latency.
01466   * @retval None
01467   */
01468 void HAL_RCC_GetClockConfig(RCC_ClkInitTypeDef  *RCC_ClkInitStruct, uint32_t *pFLatency)
01469 {
01470   /* Check the parameters */
01471   assert_param(RCC_ClkInitStruct != NULL);
01472   assert_param(pFLatency != NULL);
01473 
01474   /* Set all possible values for the Clock type parameter --------------------*/
01475   RCC_ClkInitStruct->ClockType = RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
01476 
01477   /* Get the SYSCLK configuration --------------------------------------------*/
01478   RCC_ClkInitStruct->SYSCLKSource = READ_BIT(RCC->CFGR, RCC_CFGR_SW);
01479 
01480   /* Get the HCLK configuration ----------------------------------------------*/
01481   RCC_ClkInitStruct->AHBCLKDivider = READ_BIT(RCC->CFGR, RCC_CFGR_HPRE);
01482 
01483   /* Get the APB1 configuration ----------------------------------------------*/
01484   RCC_ClkInitStruct->APB1CLKDivider = READ_BIT(RCC->CFGR, RCC_CFGR_PPRE1);
01485 
01486   /* Get the APB2 configuration ----------------------------------------------*/
01487   RCC_ClkInitStruct->APB2CLKDivider = (READ_BIT(RCC->CFGR, RCC_CFGR_PPRE2) >> 3U);
01488 
01489   /* Get the Flash Wait State (Latency) configuration ------------------------*/
01490   *pFLatency = __HAL_FLASH_GET_LATENCY();
01491 }
01492 
01493 /**
01494   * @brief  Enable the Clock Security System.
01495   * @note   If a failure is detected on the HSE oscillator clock, this oscillator
01496   *         is automatically disabled and an interrupt is generated to inform the
01497   *         software about the failure (Clock Security System Interrupt, CSSI),
01498   *         allowing the MCU to perform rescue operations. The CSSI is linked to
01499   *         the Cortex-M4 NMI (Non-Maskable Interrupt) exception vector.
01500   * @note   The Clock Security System can only be cleared by reset.
01501   * @retval None
01502   */
01503 void HAL_RCC_EnableCSS(void)
01504 {
01505   SET_BIT(RCC->CR, RCC_CR_CSSON) ;
01506 }
01507 
01508 /**
01509   * @brief Handle the RCC Clock Security System interrupt request.
01510   * @note This API should be called under the NMI_Handler().
01511   * @retval None
01512   */
01513 void HAL_RCC_NMI_IRQHandler(void)
01514 {
01515   /* Check RCC CSSF interrupt flag  */
01516   if(__HAL_RCC_GET_IT(RCC_IT_CSS))
01517   {
01518     /* RCC Clock Security System interrupt user callback */
01519     HAL_RCC_CSSCallback();
01520 
01521     /* Clear RCC CSS pending bit */
01522     __HAL_RCC_CLEAR_IT(RCC_IT_CSS);
01523   }
01524 }
01525 
01526 /**
01527   * @brief  RCC Clock Security System interrupt callback.
01528   * @retval none
01529   */
01530 __weak void HAL_RCC_CSSCallback(void)
01531 {
01532   /* NOTE : This function should not be modified, when the callback is needed,
01533             the HAL_RCC_CSSCallback should be implemented in the user file
01534    */
01535 }
01536 
01537 /**
01538   * @}
01539   */
01540 
01541 /**
01542   * @}
01543   */
01544 
01545 /* Private function prototypes -----------------------------------------------*/
01546 /** @addtogroup RCC_Private_Functions
01547   * @{
01548   */
01549 /**
01550   * @brief  Update number of Flash wait states in line with MSI range and current
01551             voltage range.
01552   * @param  msirange  MSI range value from RCC_MSIRANGE_0 to RCC_MSIRANGE_11
01553   * @retval HAL status
01554   */
01555 static HAL_StatusTypeDef RCC_SetFlashLatencyFromMSIRange(uint32_t msirange)
01556 {
01557   uint32_t vos = 0;
01558   uint32_t latency = FLASH_LATENCY_0;  /* default value 0WS */
01559 
01560   if(__HAL_RCC_PWR_IS_CLK_ENABLED())
01561   {
01562     vos = HAL_PWREx_GetVoltageRange();
01563   }
01564   else
01565   {
01566     __HAL_RCC_PWR_CLK_ENABLE();
01567     vos = HAL_PWREx_GetVoltageRange();
01568     __HAL_RCC_PWR_CLK_DISABLE();
01569   }
01570 
01571   if(vos == PWR_REGULATOR_VOLTAGE_SCALE1)
01572   {
01573     if(msirange > RCC_MSIRANGE_8)
01574     {
01575       /* MSI > 16Mhz */
01576       if(msirange > RCC_MSIRANGE_10)
01577       {
01578         /* MSI 48Mhz */
01579         latency = FLASH_LATENCY_2; /* 2WS */
01580       }
01581       else
01582       {
01583         /* MSI 24Mhz or 32Mhz */
01584         latency = FLASH_LATENCY_1; /* 1WS */
01585       }
01586     }
01587     /* else MSI <= 16Mhz default FLASH_LATENCY_0 0WS */
01588   }
01589   else
01590   {
01591 #if defined(STM32L4R5xx) || defined(STM32L4R7xx) || defined(STM32L4R9xx) || defined(STM32L4S5xx) || defined(STM32L4S7xx) || defined(STM32L4S9xx)
01592     if(msirange >= RCC_MSIRANGE_8)
01593     {
01594       /* MSI >= 16Mhz */
01595       latency = FLASH_LATENCY_2; /* 2WS */
01596     }
01597     else
01598     {
01599       if(msirange == RCC_MSIRANGE_7)
01600       {
01601         /* MSI 8Mhz */
01602         latency = FLASH_LATENCY_1; /* 1WS */
01603       }
01604       /* else MSI < 8Mhz default FLASH_LATENCY_0 0WS */
01605     }
01606 #else
01607     if(msirange > RCC_MSIRANGE_8)
01608     {
01609       /* MSI > 16Mhz */
01610       latency = FLASH_LATENCY_3; /* 3WS */
01611     }
01612     else
01613     {
01614       if(msirange == RCC_MSIRANGE_8)
01615       {
01616         /* MSI 16Mhz */
01617         latency = FLASH_LATENCY_2; /* 2WS */
01618       }
01619       else if(msirange == RCC_MSIRANGE_7)
01620       {
01621         /* MSI 8Mhz */
01622         latency = FLASH_LATENCY_1; /* 1WS */
01623       }
01624       /* else MSI < 8Mhz default FLASH_LATENCY_0 0WS */
01625     }
01626 #endif
01627   }
01628 
01629   __HAL_FLASH_SET_LATENCY(latency);
01630 
01631   /* Check that the new number of wait states is taken into account to access the Flash
01632      memory by reading the FLASH_ACR register */
01633   if(__HAL_FLASH_GET_LATENCY() != latency)
01634   {
01635     return HAL_ERROR;
01636   }
01637 
01638   return HAL_OK;
01639 }
01640 
01641 #if defined(STM32L4R5xx) || defined(STM32L4R7xx) || defined(STM32L4R9xx) || defined(STM32L4S5xx) || defined(STM32L4S7xx) || defined(STM32L4S9xx)
01642 /**
01643   * @brief  Compute SYSCLK frequency based on PLL SYSCLK source.
01644   * @retval SYSCLK frequency
01645   */
01646 static uint32_t RCC_GetSysClockFreqFromPLLSource(void)
01647 {
01648   uint32_t msirange = 0U, pllvco = 0U, pllsource = 0U, pllr = 2U, pllm = 2U;
01649   uint32_t sysclockfreq = 0U;
01650 
01651   if(__HAL_RCC_GET_PLL_OSCSOURCE() == RCC_PLLSOURCE_MSI)
01652   {
01653     /* Get MSI range source */
01654     if(READ_BIT(RCC->CR, RCC_CR_MSIRGSEL) == RESET)
01655     { /* MSISRANGE from RCC_CSR applies */
01656       msirange = READ_BIT(RCC->CSR, RCC_CSR_MSISRANGE) >> RCC_CSR_MSISRANGE_Pos;
01657     }
01658     else
01659     { /* MSIRANGE from RCC_CR applies */
01660       msirange = READ_BIT(RCC->CR, RCC_CR_MSIRANGE) >> RCC_CR_MSIRANGE_Pos;
01661     }
01662     /*MSI frequency range in HZ*/
01663     msirange = MSIRangeTable[msirange];
01664   }
01665 
01666   /* PLL_VCO = (HSE_VALUE or HSI_VALUE or MSI_VALUE/ PLLM) * PLLN
01667      SYSCLK = PLL_VCO / PLLR
01668    */
01669   pllsource = READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC);
01670   pllm = (READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLM) >> RCC_PLLCFGR_PLLM_Pos) + 1U ;
01671 
01672   switch (pllsource)
01673   {
01674   case RCC_PLLSOURCE_HSI:  /* HSI used as PLL clock source */
01675     pllvco = (HSI_VALUE / pllm) * (READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos);
01676     break;
01677 
01678   case RCC_PLLSOURCE_HSE:  /* HSE used as PLL clock source */
01679     pllvco = (HSE_VALUE / pllm) * (READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos);
01680     break;
01681 
01682   case RCC_PLLSOURCE_MSI:  /* MSI used as PLL clock source */
01683   default:
01684     pllvco = (msirange / pllm) * (READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos);
01685     break;
01686   }
01687 
01688   pllr = ((READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLR) >> RCC_PLLCFGR_PLLR_Pos) + 1U ) * 2U;
01689   sysclockfreq = pllvco/pllr;
01690 
01691   return sysclockfreq;
01692 }
01693 #endif /* STM32L4R5xx || STM32L4R7xx || STM32L4R9xx || STM32L4S5xx || STM32L4S7xx || STM32L4S9xx */
01694 
01695 /**
01696   * @}
01697   */
01698 
01699 #endif /* HAL_RCC_MODULE_ENABLED */
01700 /**
01701   * @}
01702   */
01703 
01704 /**
01705   * @}
01706   */
01707 
01708 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/