TUKS MCU Introductory course / TUKS-COURSE-THERMOMETER

Fork of TUKS-COURSE-TIMER by TUKS MCU Introductory course

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