Hal Drivers for L4

Dependents:   BSP OneHopeOnePrayer FINAL_AUDIO_RECORD AudioDemo

Fork of STM32L4xx_HAL_Driver by Senior Design: Sound Monitor

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers stm32l4xx_hal_rcc.c Source File

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