Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependents: Space_Invaders_Demo neopixels gpio_test_stm32f3_discovery gpio_test_systimer ... more
stm32f30x_rcc.c
00001 /** 00002 ****************************************************************************** 00003 * @file stm32f30x_rcc.c 00004 * @author MCD Application Team 00005 * @version V1.2.3 00006 * @date 10-July-2015 00007 * @brief This file provides firmware functions to manage the following 00008 * functionalities of the Reset and clock control (RCC) peripheral: 00009 * + Internal/external clocks, PLL, CSS and MCO configuration 00010 * + System, AHB and APB busses clocks configuration 00011 * + Peripheral clocks configuration 00012 * + Interrupts and flags management 00013 * 00014 @verbatim 00015 00016 =============================================================================== 00017 ##### RCC specific features ##### 00018 =============================================================================== 00019 [..] After reset the device is running from HSI (8 MHz) with Flash 0 WS, 00020 all peripherals are off except internal SRAM, Flash and SWD. 00021 (+) There is no prescaler on High speed (AHB) and Low speed (APB) busses; 00022 all peripherals mapped on these busses are running at HSI speed. 00023 (+) The clock for all peripherals is switched off, except the SRAM and FLASH. 00024 (+) All GPIOs are in input floating state, except the SWD pins which 00025 are assigned to be used for debug purpose. 00026 [..] Once the device starts from reset, the user application has to: 00027 (+) Configure the clock source to be used to drive the System clock 00028 (if the application needs higher frequency/performance). 00029 (+) Configure the System clock frequency and Flash settings. 00030 (+) Configure the AHB and APB busses prescalers. 00031 (+) Enable the clock for the peripheral(s) to be used. 00032 (+) Configure the clock source(s) for peripherals which clocks are not 00033 derived from the System clock (ADC, TIM, I2C, USART, RTC and IWDG). 00034 00035 @endverbatim 00036 00037 ****************************************************************************** 00038 * @attention 00039 * 00040 * <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2> 00041 * 00042 * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); 00043 * You may not use this file except in compliance with the License. 00044 * You may obtain a copy of the License at: 00045 * 00046 * http://www.st.com/software_license_agreement_liberty_v2 00047 * 00048 * Unless required by applicable law or agreed to in writing, software 00049 * distributed under the License is distributed on an "AS IS" BASIS, 00050 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 00051 * See the License for the specific language governing permissions and 00052 * limitations under the License. 00053 * 00054 ****************************************************************************** 00055 */ 00056 00057 /* Includes ------------------------------------------------------------------*/ 00058 #include "stm32f30x_rcc.h" 00059 00060 /** @addtogroup STM32F30x_StdPeriph_Driver 00061 * @{ 00062 */ 00063 00064 /** @defgroup RCC 00065 * @brief RCC driver modules 00066 * @{ 00067 */ 00068 00069 /* Private typedef -----------------------------------------------------------*/ 00070 /* Private define ------------------------------------------------------------*/ 00071 /* ------------ RCC registers bit address in the alias region ----------- */ 00072 #define RCC_OFFSET (RCC_BASE - PERIPH_BASE) 00073 00074 /* --- CR Register ---*/ 00075 00076 /* Alias word address of HSION bit */ 00077 #define CR_OFFSET (RCC_OFFSET + 0x00) 00078 #define HSION_BitNumber 0x00 00079 #define CR_HSION_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (HSION_BitNumber * 4)) 00080 00081 /* Alias word address of PLLON bit */ 00082 #define PLLON_BitNumber 0x18 00083 #define CR_PLLON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLON_BitNumber * 4)) 00084 00085 /* Alias word address of CSSON bit */ 00086 #define CSSON_BitNumber 0x13 00087 #define CR_CSSON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (CSSON_BitNumber * 4)) 00088 00089 /* --- CFGR Register ---*/ 00090 /* Alias word address of USBPRE bit */ 00091 #define CFGR_OFFSET (RCC_OFFSET + 0x04) 00092 #define USBPRE_BitNumber 0x16 00093 #define CFGR_USBPRE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (USBPRE_BitNumber * 4)) 00094 /* Alias word address of I2SSRC bit */ 00095 #define I2SSRC_BitNumber 0x17 00096 #define CFGR_I2SSRC_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (I2SSRC_BitNumber * 4)) 00097 00098 /* --- BDCR Register ---*/ 00099 00100 /* Alias word address of RTCEN bit */ 00101 #define BDCR_OFFSET (RCC_OFFSET + 0x20) 00102 #define RTCEN_BitNumber 0x0F 00103 #define BDCR_RTCEN_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (RTCEN_BitNumber * 4)) 00104 00105 /* Alias word address of BDRST bit */ 00106 #define BDRST_BitNumber 0x10 00107 #define BDCR_BDRST_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (BDRST_BitNumber * 4)) 00108 00109 /* --- CSR Register ---*/ 00110 00111 /* Alias word address of LSION bit */ 00112 #define CSR_OFFSET (RCC_OFFSET + 0x24) 00113 #define LSION_BitNumber 0x00 00114 #define CSR_LSION_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (LSION_BitNumber * 4)) 00115 00116 /* ---------------------- RCC registers bit mask ------------------------ */ 00117 /* RCC Flag Mask */ 00118 #define FLAG_MASK ((uint8_t)0x1F) 00119 00120 /* CFGR register byte 3 (Bits[31:23]) base address */ 00121 #define CFGR_BYTE3_ADDRESS ((uint32_t)0x40021007) 00122 00123 /* CIR register byte 2 (Bits[15:8]) base address */ 00124 #define CIR_BYTE2_ADDRESS ((uint32_t)0x40021009) 00125 00126 /* CIR register byte 3 (Bits[23:16]) base address */ 00127 #define CIR_BYTE3_ADDRESS ((uint32_t)0x4002100A) 00128 00129 /* CR register byte 2 (Bits[23:16]) base address */ 00130 #define CR_BYTE2_ADDRESS ((uint32_t)0x40021002) 00131 00132 /* Private macro -------------------------------------------------------------*/ 00133 /* Private variables ---------------------------------------------------------*/ 00134 static __I uint8_t APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9}; 00135 static __I uint16_t ADCPrescTable[16] = {1, 2, 4, 6, 8, 10, 12, 16, 32, 64, 128, 256, 0, 0, 0, 0 }; 00136 00137 /* Private function prototypes -----------------------------------------------*/ 00138 /* Private functions ---------------------------------------------------------*/ 00139 00140 /** @defgroup RCC_Private_Functions 00141 * @{ 00142 */ 00143 00144 /** @defgroup RCC_Group1 Internal and external clocks, PLL, CSS and MCO configuration functions 00145 * @brief Internal and external clocks, PLL, CSS and MCO configuration functions 00146 * 00147 @verbatim 00148 =============================================================================== 00149 ##### Internal-external clocks, PLL, CSS and MCO configuration functions ##### 00150 =============================================================================== 00151 [..] This section provides functions allowing to configure the internal/external 00152 clocks, PLL, CSS and MCO. 00153 (#) HSI (high-speed internal), 8 MHz factory-trimmed RC used directly 00154 or through the PLL as System clock source. 00155 The HSI clock can be used also to clock the USART and I2C peripherals. 00156 (#) LSI (low-speed internal), 40 KHz low consumption RC used as IWDG and/or RTC 00157 clock source. 00158 (#) HSE (high-speed external), 4 to 32 MHz crystal oscillator used directly or 00159 through the PLL as System clock source. Can be used also as RTC clock source. 00160 (#) LSE (low-speed external), 32 KHz oscillator used as RTC clock source. 00161 LSE can be used also to clock the USART peripherals. 00162 (#) PLL (clocked by HSI or HSE), for System clock. 00163 (#) CSS (Clock security system), once enabled and if a HSE clock failure occurs 00164 (HSE used directly or through PLL as System clock source), the System clock 00165 is automatically switched to HSI and an interrupt is generated if enabled. 00166 The interrupt is linked to the Cortex-M4 NMI (Non-Maskable Interrupt) 00167 exception vector. 00168 (#) MCO (microcontroller clock output), used to output SYSCLK, HSI, HSE, LSI, LSE, 00169 PLL clock on PA8 pin. 00170 00171 @endverbatim 00172 * @{ 00173 */ 00174 00175 /** 00176 * @brief Resets the RCC clock configuration to the default reset state. 00177 * @note The default reset state of the clock configuration is given below: 00178 * - HSI ON and used as system clock source 00179 * - HSE, PLL and PLLI2S OFF 00180 * - AHB, APB1 and APB2 prescaler set to 1. 00181 * - CSS and MCO OFF 00182 * - All interrupts disabled 00183 * @note However, This function doesn't modify the configuration of the 00184 * - Peripheral clocks 00185 * - LSI, LSE and RTC clocks 00186 * @param None 00187 * @retval None 00188 */ 00189 void RCC_DeInit(void) 00190 { 00191 /* Set HSION bit */ 00192 RCC->CR |= (uint32_t)0x00000001; 00193 00194 /* Reset SW[1:0], HPRE[3:0], PPRE[2:0] and MCOSEL[2:0] bits */ 00195 RCC->CFGR &= (uint32_t)0xF8FFC000; 00196 00197 /* Reset HSEON, CSSON and PLLON bits */ 00198 RCC->CR &= (uint32_t)0xFEF6FFFF; 00199 00200 /* Reset HSEBYP bit */ 00201 RCC->CR &= (uint32_t)0xFFFBFFFF; 00202 00203 /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */ 00204 RCC->CFGR &= (uint32_t)0xFF80FFFF; 00205 00206 /* Reset PREDIV1[3:0] and ADCPRE[13:4] bits */ 00207 RCC->CFGR2 &= (uint32_t)0xFFFFC000; 00208 00209 /* Reset USARTSW[1:0], I2CSW and TIMSW bits */ 00210 RCC->CFGR3 &= (uint32_t)0xF00ECCC; 00211 00212 /* Disable all interrupts */ 00213 RCC->CIR = 0x00000000; 00214 } 00215 00216 /** 00217 * @brief Configures the External High Speed oscillator (HSE). 00218 * @note After enabling the HSE (RCC_HSE_ON or RCC_HSE_Bypass), the application 00219 * software should wait on HSERDY flag to be set indicating that HSE clock 00220 * is stable and can be used to clock the PLL and/or system clock. 00221 * @note HSE state can not be changed if it is used directly or through the 00222 * PLL as system clock. In this case, you have to select another source 00223 * of the system clock then change the HSE state (ex. disable it). 00224 * @note The HSE is stopped by hardware when entering STOP and STANDBY modes. 00225 * @note This function resets the CSSON bit, so if the Clock security system(CSS) 00226 * was previously enabled you have to enable it again after calling this 00227 * function. 00228 * @param RCC_HSE: specifies the new state of the HSE. 00229 * This parameter can be one of the following values: 00230 * @arg RCC_HSE_OFF: turn OFF the HSE oscillator, HSERDY flag goes low after 00231 * 6 HSE oscillator clock cycles. 00232 * @arg RCC_HSE_ON: turn ON the HSE oscillator 00233 * @arg RCC_HSE_Bypass: HSE oscillator bypassed with external clock 00234 * @retval None 00235 */ 00236 void RCC_HSEConfig(uint8_t RCC_HSE) 00237 { 00238 /* Check the parameters */ 00239 assert_param(IS_RCC_HSE(RCC_HSE)); 00240 00241 /* Reset HSEON and HSEBYP bits before configuring the HSE ------------------*/ 00242 *(__IO uint8_t *) CR_BYTE2_ADDRESS = RCC_HSE_OFF; 00243 00244 /* Set the new HSE configuration -------------------------------------------*/ 00245 *(__IO uint8_t *) CR_BYTE2_ADDRESS = RCC_HSE; 00246 00247 } 00248 00249 /** 00250 * @brief Waits for HSE start-up. 00251 * @note This function waits on HSERDY flag to be set and return SUCCESS if 00252 * this flag is set, otherwise returns ERROR if the timeout is reached 00253 * and this flag is not set. The timeout value is defined by the constant 00254 * HSE_STARTUP_TIMEOUT in stm32f30x.h file. You can tailor it depending 00255 * on the HSE crystal used in your application. 00256 * @param None 00257 * @retval An ErrorStatus enumeration value: 00258 * - SUCCESS: HSE oscillator is stable and ready to use 00259 * - ERROR: HSE oscillator not yet ready 00260 */ 00261 ErrorStatus RCC_WaitForHSEStartUp(void) 00262 { 00263 __IO uint32_t StartUpCounter = 0; 00264 ErrorStatus status = ERROR; 00265 FlagStatus HSEStatus = RESET; 00266 00267 /* Wait till HSE is ready and if timeout is reached exit */ 00268 do 00269 { 00270 HSEStatus = RCC_GetFlagStatus(RCC_FLAG_HSERDY); 00271 StartUpCounter++; 00272 } while((StartUpCounter != HSE_STARTUP_TIMEOUT) && (HSEStatus == RESET)); 00273 00274 if (RCC_GetFlagStatus(RCC_FLAG_HSERDY) != RESET) 00275 { 00276 status = SUCCESS; 00277 } 00278 else 00279 { 00280 status = ERROR; 00281 } 00282 return (status); 00283 } 00284 00285 /** 00286 * @brief Adjusts the Internal High Speed oscillator (HSI) calibration value. 00287 * @note The calibration is used to compensate for the variations in voltage 00288 * and temperature that influence the frequency of the internal HSI RC. 00289 * Refer to the Application Note AN3300 for more details on how to 00290 * calibrate the HSI. 00291 * @param HSICalibrationValue: specifies the HSI calibration trimming value. 00292 * This parameter must be a number between 0 and 0x1F. 00293 * @retval None 00294 */ 00295 void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue) 00296 { 00297 uint32_t tmpreg = 0; 00298 00299 /* Check the parameters */ 00300 assert_param(IS_RCC_HSI_CALIBRATION_VALUE(HSICalibrationValue)); 00301 00302 tmpreg = RCC->CR; 00303 00304 /* Clear HSITRIM[4:0] bits */ 00305 tmpreg &= ~RCC_CR_HSITRIM; 00306 00307 /* Set the HSITRIM[4:0] bits according to HSICalibrationValue value */ 00308 tmpreg |= (uint32_t)HSICalibrationValue << 3; 00309 00310 /* Store the new value */ 00311 RCC->CR = tmpreg; 00312 } 00313 00314 /** 00315 * @brief Enables or disables the Internal High Speed oscillator (HSI). 00316 * @note After enabling the HSI, the application software should wait on 00317 * HSIRDY flag to be set indicating that HSI clock is stable and can 00318 * be used to clock the PLL and/or system clock. 00319 * @note HSI can not be stopped if it is used directly or through the PLL 00320 * as system clock. In this case, you have to select another source 00321 * of the system clock then stop the HSI. 00322 * @note The HSI is stopped by hardware when entering STOP and STANDBY modes. 00323 * @note When the HSI is stopped, HSIRDY flag goes low after 6 HSI oscillator 00324 * clock cycles. 00325 * @param NewState: new state of the HSI. 00326 * This parameter can be: ENABLE or DISABLE. 00327 * @retval None 00328 */ 00329 void RCC_HSICmd(FunctionalState NewState) 00330 { 00331 /* Check the parameters */ 00332 assert_param(IS_FUNCTIONAL_STATE(NewState)); 00333 00334 *(__IO uint32_t *) CR_HSION_BB = (uint32_t)NewState; 00335 } 00336 00337 /** 00338 * @brief Configures the External Low Speed oscillator (LSE). 00339 * @note As the LSE is in the Backup domain and write access is denied to this 00340 * domain after reset, you have to enable write access using 00341 * PWR_BackupAccessCmd(ENABLE) function before to configure the LSE 00342 * (to be done once after reset). 00343 * @note Care must be taken when using this function to configure LSE mode 00344 * as it clears systematically the LSEON bit before any new configuration. 00345 * @note After enabling the LSE (RCC_LSE_ON or RCC_LSE_Bypass), the application 00346 * software should wait on LSERDY flag to be set indicating that LSE clock 00347 * is stable and can be used to clock the RTC. 00348 * @param RCC_LSE: specifies the new state of the LSE. 00349 * This parameter can be one of the following values: 00350 * @arg RCC_LSE_OFF: turn OFF the LSE oscillator, LSERDY flag goes low after 00351 * 6 LSE oscillator clock cycles. 00352 * @arg RCC_LSE_ON: turn ON the LSE oscillator 00353 * @arg RCC_LSE_Bypass: LSE oscillator bypassed with external clock 00354 * @retval None 00355 */ 00356 void RCC_LSEConfig(uint32_t RCC_LSE) 00357 { 00358 /* Check the parameters */ 00359 assert_param(IS_RCC_LSE(RCC_LSE)); 00360 00361 /* Reset LSEON and LSEBYP bits before configuring the LSE ------------------*/ 00362 /* Reset LSEON bit */ 00363 RCC->BDCR &= ~(RCC_BDCR_LSEON); 00364 00365 /* Reset LSEBYP bit */ 00366 RCC->BDCR &= ~(RCC_BDCR_LSEBYP); 00367 00368 /* Configure LSE */ 00369 RCC->BDCR |= RCC_LSE; 00370 } 00371 00372 /** 00373 * @brief Configures the External Low Speed oscillator (LSE) drive capability. 00374 * @param RCC_LSEDrive: specifies the new state of the LSE drive capability. 00375 * This parameter can be one of the following values: 00376 * @arg RCC_LSEDrive_Low: LSE oscillator low drive capability. 00377 * @arg RCC_LSEDrive_MediumLow: LSE oscillator medium low drive capability. 00378 * @arg RCC_LSEDrive_MediumHigh: LSE oscillator medium high drive capability. 00379 * @arg RCC_LSEDrive_High: LSE oscillator high drive capability. 00380 * @retval None 00381 */ 00382 void RCC_LSEDriveConfig(uint32_t RCC_LSEDrive) 00383 { 00384 /* Check the parameters */ 00385 assert_param(IS_RCC_LSE_DRIVE(RCC_LSEDrive)); 00386 00387 /* Clear LSEDRV[1:0] bits */ 00388 RCC->BDCR &= ~(RCC_BDCR_LSEDRV); 00389 00390 /* Set the LSE Drive */ 00391 RCC->BDCR |= RCC_LSEDrive; 00392 } 00393 00394 /** 00395 * @brief Enables or disables the Internal Low Speed oscillator (LSI). 00396 * @note After enabling the LSI, the application software should wait on 00397 * LSIRDY flag to be set indicating that LSI clock is stable and can 00398 * be used to clock the IWDG and/or the RTC. 00399 * @note LSI can not be disabled if the IWDG is running. 00400 * @note When the LSI is stopped, LSIRDY flag goes low after 6 LSI oscillator 00401 * clock cycles. 00402 * @param NewState: new state of the LSI. 00403 * This parameter can be: ENABLE or DISABLE. 00404 * @retval None 00405 */ 00406 void RCC_LSICmd(FunctionalState NewState) 00407 { 00408 /* Check the parameters */ 00409 assert_param(IS_FUNCTIONAL_STATE(NewState)); 00410 00411 *(__IO uint32_t *) CSR_LSION_BB = (uint32_t)NewState; 00412 } 00413 00414 /** 00415 * @brief Configures the PLL clock source and multiplication factor. 00416 * @note This function must be used only when the PLL is disabled. 00417 * @note The minimum input clock frequency for PLL is 2 MHz (when using HSE as 00418 * PLL source). 00419 * @param RCC_PLLSource: specifies the PLL entry clock source. 00420 * This parameter can be one of the following values: 00421 * @arg RCC_PLLSource_HSI: HSI oscillator clockselected as PLL clock entry 00422 * @arg RCC_PLLSource_HSI_Div2: HSI oscillator clock divided by 2 selected as 00423 * PLL clock entry 00424 * @arg RCC_PLLSource_PREDIV1: PREDIV1 clock selected as PLL clock source 00425 * @param RCC_PLLMul: specifies the PLL multiplication factor, which drive the PLLVCO clock 00426 * This parameter can be RCC_PLLMul_x where x:[2,16] 00427 * 00428 * @retval None 00429 */ 00430 void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul) 00431 { 00432 /* Check the parameters */ 00433 assert_param(IS_RCC_PLL_SOURCE(RCC_PLLSource)); 00434 assert_param(IS_RCC_PLL_MUL(RCC_PLLMul)); 00435 00436 /* Clear PLL Source [16] and Multiplier [21:18] bits */ 00437 RCC->CFGR &= ~(RCC_CFGR_PLLMULL | RCC_CFGR_PLLSRC); 00438 00439 /* Set the PLL Source and Multiplier */ 00440 RCC->CFGR |= (uint32_t)(RCC_PLLSource | RCC_PLLMul); 00441 } 00442 00443 /** 00444 * @brief Enables or disables the PLL. 00445 * @note After enabling the PLL, the application software should wait on 00446 * PLLRDY flag to be set indicating that PLL clock is stable and can 00447 * be used as system clock source. 00448 * @note The PLL can not be disabled if it is used as system clock source 00449 * @note The PLL is disabled by hardware when entering STOP and STANDBY modes. 00450 * @param NewState: new state of the PLL. 00451 * This parameter can be: ENABLE or DISABLE. 00452 * @retval None 00453 */ 00454 void RCC_PLLCmd(FunctionalState NewState) 00455 { 00456 /* Check the parameters */ 00457 assert_param(IS_FUNCTIONAL_STATE(NewState)); 00458 00459 *(__IO uint32_t *) CR_PLLON_BB = (uint32_t)NewState; 00460 } 00461 00462 /** 00463 * @brief Configures the PREDIV1 division factor. 00464 * @note This function must be used only when the PLL is disabled. 00465 * @param RCC_PREDIV1_Div: specifies the PREDIV1 clock division factor. 00466 * This parameter can be RCC_PREDIV1_Divx where x:[1,16] 00467 * @retval None 00468 */ 00469 void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Div) 00470 { 00471 uint32_t tmpreg = 0; 00472 00473 /* Check the parameters */ 00474 assert_param(IS_RCC_PREDIV1(RCC_PREDIV1_Div)); 00475 00476 tmpreg = RCC->CFGR2; 00477 /* Clear PREDIV1[3:0] bits */ 00478 tmpreg &= ~(RCC_CFGR2_PREDIV1); 00479 00480 /* Set the PREDIV1 division factor */ 00481 tmpreg |= RCC_PREDIV1_Div; 00482 00483 /* Store the new value */ 00484 RCC->CFGR2 = tmpreg; 00485 } 00486 00487 /** 00488 * @brief Enables or disables the Clock Security System. 00489 * @note If a failure is detected on the HSE oscillator clock, this oscillator 00490 * is automatically disabled and an interrupt is generated to inform the 00491 * software about the failure (Clock Security System Interrupt, CSSI), 00492 * allowing the MCU to perform rescue operations. The CSSI is linked to 00493 * the Cortex-M4 NMI (Non-Maskable Interrupt) exception vector. 00494 * @param NewState: new state of the Clock Security System. 00495 * This parameter can be: ENABLE or DISABLE. 00496 * @retval None 00497 */ 00498 void RCC_ClockSecuritySystemCmd(FunctionalState NewState) 00499 { 00500 /* Check the parameters */ 00501 assert_param(IS_FUNCTIONAL_STATE(NewState)); 00502 00503 *(__IO uint32_t *) CR_CSSON_BB = (uint32_t)NewState; 00504 } 00505 00506 #ifdef STM32F303xC 00507 /** 00508 * @brief Selects the clock source to output on MCO pin (PA8). 00509 * @note PA8 should be configured in alternate function mode. 00510 * @param RCC_MCOSource: specifies the clock source to output. 00511 * This parameter can be one of the following values: 00512 * @arg RCC_MCOSource_NoClock: No clock selected. 00513 * @arg RCC_MCOSource_LSI: LSI oscillator clock selected. 00514 * @arg RCC_MCOSource_LSE: LSE oscillator clock selected. 00515 * @arg RCC_MCOSource_SYSCLK: System clock selected. 00516 * @arg RCC_MCOSource_HSI: HSI oscillator clock selected. 00517 * @arg RCC_MCOSource_HSE: HSE oscillator clock selected. 00518 * @arg RCC_MCOSource_PLLCLK_Div2: PLL clock divided by 2 selected. 00519 * @retval None 00520 */ 00521 void RCC_MCOConfig(uint8_t RCC_MCOSource) 00522 { 00523 uint32_t tmpreg = 0; 00524 00525 /* Check the parameters */ 00526 assert_param(IS_RCC_MCO_SOURCE(RCC_MCOSource)); 00527 00528 /* Get CFGR value */ 00529 tmpreg = RCC->CFGR; 00530 /* Clear MCO[3:0] bits */ 00531 tmpreg &= ~(RCC_CFGR_MCO | RCC_CFGR_PLLNODIV); 00532 /* Set the RCC_MCOSource */ 00533 tmpreg |= RCC_MCOSource<<24; 00534 /* Store the new value */ 00535 RCC->CFGR = tmpreg; 00536 } 00537 #else 00538 00539 /** 00540 * @brief Selects the clock source to output on MCO pin (PA8) and the corresponding 00541 * prescsaler. 00542 * @note PA8 should be configured in alternate function mode. 00543 * @param RCC_MCOSource: specifies the clock source to output. 00544 * This parameter can be one of the following values: 00545 * @arg RCC_MCOSource_NoClock: No clock selected. 00546 * @arg RCC_MCOSource_LSI: LSI oscillator clock selected. 00547 * @arg RCC_MCOSource_LSE: LSE oscillator clock selected. 00548 * @arg RCC_MCOSource_SYSCLK: System clock selected. 00549 * @arg RCC_MCOSource_HSI: HSI oscillator clock selected. 00550 * @arg RCC_MCOSource_HSE: HSE oscillator clock selected. 00551 * @arg RCC_MCOSource_PLLCLK_Div2: PLL clock divided by 2 selected. 00552 * @arg RCC_MCOSource_PLLCLK: PLL clock selected. 00553 * @param RCC_MCOPrescaler: specifies the prescaler on MCO pin. 00554 * This parameter can be one of the following values: 00555 * @arg RCC_MCOPrescaler_1: MCO clock is divided by 1. 00556 * @arg RCC_MCOPrescaler_2: MCO clock is divided by 2. 00557 * @arg RCC_MCOPrescaler_4: MCO clock is divided by 4. 00558 * @arg RCC_MCOPrescaler_8: MCO clock is divided by 8. 00559 * @arg RCC_MCOPrescaler_16: MCO clock is divided by 16. 00560 * @arg RCC_MCOPrescaler_32: MCO clock is divided by 32. 00561 * @arg RCC_MCOPrescaler_64: MCO clock is divided by 64. 00562 * @arg RCC_MCOPrescaler_128: MCO clock is divided by 128. 00563 * @retval None 00564 */ 00565 void RCC_MCOConfig(uint8_t RCC_MCOSource, uint32_t RCC_MCOPrescaler) 00566 { 00567 uint32_t tmpreg = 0; 00568 00569 /* Check the parameters */ 00570 assert_param(IS_RCC_MCO_SOURCE(RCC_MCOSource)); 00571 assert_param(IS_RCC_MCO_PRESCALER(RCC_MCOPrescaler)); 00572 00573 /* Get CFGR value */ 00574 tmpreg = RCC->CFGR; 00575 /* Clear MCOPRE[2:0] bits */ 00576 tmpreg &= ~(RCC_CFGR_MCO_PRE | RCC_CFGR_MCO | RCC_CFGR_PLLNODIV); 00577 /* Set the RCC_MCOSource and RCC_MCOPrescaler */ 00578 tmpreg |= (RCC_MCOPrescaler | RCC_MCOSource<<24); 00579 /* Store the new value */ 00580 RCC->CFGR = tmpreg; 00581 } 00582 #endif /* STM32F303xC */ 00583 00584 /** 00585 * @} 00586 */ 00587 00588 /** @defgroup RCC_Group2 System AHB, APB1 and APB2 busses clocks configuration functions 00589 * @brief System, AHB and APB busses clocks configuration functions 00590 * 00591 @verbatim 00592 =============================================================================== 00593 ##### System, AHB, APB1 and APB2 busses clocks configuration functions ##### 00594 =============================================================================== 00595 [..] This section provide functions allowing to configure the System, AHB, APB1 and 00596 APB2 busses clocks. 00597 (#) Several clock sources can be used to drive the System clock (SYSCLK): HSI, 00598 HSE and PLL. 00599 The AHB clock (HCLK) is derived from System clock through configurable prescaler 00600 and used to clock the CPU, memory and peripherals mapped on AHB bus (DMA and GPIO). 00601 APB1 (PCLK1) and APB2 (PCLK2) clocks are derived from AHB clock through 00602 configurable prescalers and used to clock the peripherals mapped on these busses. 00603 You can use "RCC_GetClocksFreq()" function to retrieve the frequencies of these clocks. 00604 00605 (#) The maximum frequency of the SYSCLK, HCLK, PCLK1 and PCLK2 is 72 MHz. 00606 Depending on the maximum frequency, the FLASH wait states (WS) should be 00607 adapted accordingly: 00608 +---------------------------------+ 00609 | Wait states | HCLK clock | 00610 | (Latency) | frequency (MHz) | 00611 |-------------- |-----------------| 00612 |0WS(1CPU cycle)| 0 < HCLK <= 24 | 00613 |---------------|-----------------| 00614 |1WS(2CPU cycle)|24 < HCLK <=48 | 00615 |---------------|-----------------| 00616 |2WS(3CPU cycle)|48 < HCLK <= 72 | 00617 +---------------------------------+ 00618 00619 (#) After reset, the System clock source is the HSI (8 MHz) with 0 WS and 00620 prefetch is disabled. 00621 [..] 00622 (@) All the peripheral clocks are derived from the System clock (SYSCLK) 00623 except: 00624 (+@) The FLASH program/erase clock which is always HSI 8MHz clock. 00625 (+@) The USB 48 MHz clock which is derived from the PLL VCO clock. 00626 (+@) The USART clock which can be derived as well from HSI 8MHz, LSI or LSE. 00627 (+@) The I2C clock which can be derived as well from HSI 8MHz clock. 00628 (+@) The ADC clock which is derived from PLL output. 00629 (+@) The RTC clock which is derived from the LSE, LSI or 1 MHz HSE_RTC 00630 (HSE divided by a programmable prescaler). The System clock (SYSCLK) 00631 frequency must be higher or equal to the RTC clock frequency. 00632 (+@) IWDG clock which is always the LSI clock. 00633 [..] It is recommended to use the following software sequences to tune the number 00634 of wait states needed to access the Flash memory with the CPU frequency (HCLK). 00635 (+) Increasing the CPU frequency 00636 (++) Program the Flash Prefetch buffer, using "FLASH_PrefetchBufferCmd(ENABLE)" 00637 function 00638 (++) Check that Flash Prefetch buffer activation is taken into account by 00639 reading FLASH_ACR using the FLASH_GetPrefetchBufferStatus() function 00640 (++) Program Flash WS to 1 or 2, using "FLASH_SetLatency()" function 00641 (++) Check that the new number of WS is taken into account by reading FLASH_ACR 00642 (++) Modify the CPU clock source, using "RCC_SYSCLKConfig()" function 00643 (++) If needed, modify the CPU clock prescaler by using "RCC_HCLKConfig()" function 00644 (++) Check that the new CPU clock source is taken into account by reading 00645 the clock source status, using "RCC_GetSYSCLKSource()" function 00646 (+) Decreasing the CPU frequency 00647 (++) Modify the CPU clock source, using "RCC_SYSCLKConfig()" function 00648 (++) If needed, modify the CPU clock prescaler by using "RCC_HCLKConfig()" function 00649 (++) Check that the new CPU clock source is taken into account by reading 00650 the clock source status, using "RCC_GetSYSCLKSource()" function 00651 (++) Program the new number of WS, using "FLASH_SetLatency()" function 00652 (++) Check that the new number of WS is taken into account by reading FLASH_ACR 00653 (++) Disable the Flash Prefetch buffer using "FLASH_PrefetchBufferCmd(DISABLE)" 00654 function 00655 (++) Check that Flash Prefetch buffer deactivation is taken into account by reading FLASH_ACR 00656 using the FLASH_GetPrefetchBufferStatus() function. 00657 00658 @endverbatim 00659 * @{ 00660 */ 00661 00662 /** 00663 * @brief Configures the system clock (SYSCLK). 00664 * @note The HSI is used (enabled by hardware) as system clock source after 00665 * startup from Reset, wake-up from STOP and STANDBY mode, or in case 00666 * of failure of the HSE used directly or indirectly as system clock 00667 * (if the Clock Security System CSS is enabled). 00668 * @note A switch from one clock source to another occurs only if the target 00669 * clock source is ready (clock stable after startup delay or PLL locked). 00670 * If a clock source which is not yet ready is selected, the switch will 00671 * occur when the clock source will be ready. 00672 * You can use RCC_GetSYSCLKSource() function to know which clock is 00673 * currently used as system clock source. 00674 * @param RCC_SYSCLKSource: specifies the clock source used as system clock source 00675 * This parameter can be one of the following values: 00676 * @arg RCC_SYSCLKSource_HSI: HSI selected as system clock source 00677 * @arg RCC_SYSCLKSource_HSE: HSE selected as system clock source 00678 * @arg RCC_SYSCLKSource_PLLCLK: PLL selected as system clock source 00679 * @retval None 00680 */ 00681 void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource) 00682 { 00683 uint32_t tmpreg = 0; 00684 00685 /* Check the parameters */ 00686 assert_param(IS_RCC_SYSCLK_SOURCE(RCC_SYSCLKSource)); 00687 00688 tmpreg = RCC->CFGR; 00689 00690 /* Clear SW[1:0] bits */ 00691 tmpreg &= ~RCC_CFGR_SW; 00692 00693 /* Set SW[1:0] bits according to RCC_SYSCLKSource value */ 00694 tmpreg |= RCC_SYSCLKSource; 00695 00696 /* Store the new value */ 00697 RCC->CFGR = tmpreg; 00698 } 00699 00700 /** 00701 * @brief Returns the clock source used as system clock. 00702 * @param None 00703 * @retval The clock source used as system clock. The returned value can be one 00704 * of the following values: 00705 * - 0x00: HSI used as system clock 00706 * - 0x04: HSE used as system clock 00707 * - 0x08: PLL used as system clock 00708 */ 00709 uint8_t RCC_GetSYSCLKSource(void) 00710 { 00711 return ((uint8_t)(RCC->CFGR & RCC_CFGR_SWS)); 00712 } 00713 00714 /** 00715 * @brief Configures the AHB clock (HCLK). 00716 * @note Depending on the device voltage range, the software has to set correctly 00717 * these bits to ensure that the system frequency does not exceed the 00718 * maximum allowed frequency (for more details refer to section above 00719 * "CPU, AHB and APB busses clocks configuration functions"). 00720 * @param RCC_SYSCLK: defines the AHB clock divider. This clock is derived from 00721 * the system clock (SYSCLK). 00722 * This parameter can be one of the following values: 00723 * @arg RCC_SYSCLK_Div1: AHB clock = SYSCLK 00724 * @arg RCC_SYSCLK_Div2: AHB clock = SYSCLK/2 00725 * @arg RCC_SYSCLK_Div4: AHB clock = SYSCLK/4 00726 * @arg RCC_SYSCLK_Div8: AHB clock = SYSCLK/8 00727 * @arg RCC_SYSCLK_Div16: AHB clock = SYSCLK/16 00728 * @arg RCC_SYSCLK_Div64: AHB clock = SYSCLK/64 00729 * @arg RCC_SYSCLK_Div128: AHB clock = SYSCLK/128 00730 * @arg RCC_SYSCLK_Div256: AHB clock = SYSCLK/256 00731 * @arg RCC_SYSCLK_Div512: AHB clock = SYSCLK/512 00732 * @retval None 00733 */ 00734 void RCC_HCLKConfig(uint32_t RCC_SYSCLK) 00735 { 00736 uint32_t tmpreg = 0; 00737 00738 /* Check the parameters */ 00739 assert_param(IS_RCC_HCLK(RCC_SYSCLK)); 00740 00741 tmpreg = RCC->CFGR; 00742 00743 /* Clear HPRE[3:0] bits */ 00744 tmpreg &= ~RCC_CFGR_HPRE; 00745 00746 /* Set HPRE[3:0] bits according to RCC_SYSCLK value */ 00747 tmpreg |= RCC_SYSCLK; 00748 00749 /* Store the new value */ 00750 RCC->CFGR = tmpreg; 00751 } 00752 00753 /** 00754 * @brief Configures the Low Speed APB clock (PCLK1). 00755 * @param RCC_HCLK: defines the APB1 clock divider. This clock is derived from 00756 * the AHB clock (HCLK). 00757 * This parameter can be one of the following values: 00758 * @arg RCC_HCLK_Div1: APB1 clock = HCLK 00759 * @arg RCC_HCLK_Div2: APB1 clock = HCLK/2 00760 * @arg RCC_HCLK_Div4: APB1 clock = HCLK/4 00761 * @arg RCC_HCLK_Div8: APB1 clock = HCLK/8 00762 * @arg RCC_HCLK_Div16: APB1 clock = HCLK/16 00763 * @retval None 00764 */ 00765 void RCC_PCLK1Config(uint32_t RCC_HCLK) 00766 { 00767 uint32_t tmpreg = 0; 00768 00769 /* Check the parameters */ 00770 assert_param(IS_RCC_PCLK(RCC_HCLK)); 00771 00772 tmpreg = RCC->CFGR; 00773 /* Clear PPRE1[2:0] bits */ 00774 tmpreg &= ~RCC_CFGR_PPRE1; 00775 00776 /* Set PPRE1[2:0] bits according to RCC_HCLK value */ 00777 tmpreg |= RCC_HCLK; 00778 00779 /* Store the new value */ 00780 RCC->CFGR = tmpreg; 00781 } 00782 00783 /** 00784 * @brief Configures the High Speed APB clock (PCLK2). 00785 * @param RCC_HCLK: defines the APB2 clock divider. This clock is derived from 00786 * the AHB clock (HCLK). 00787 * This parameter can be one of the following values: 00788 * @arg RCC_HCLK_Div1: APB2 clock = HCLK 00789 * @arg RCC_HCLK_Div2: APB2 clock = HCLK/2 00790 * @arg RCC_HCLK_Div4: APB2 clock = HCLK/4 00791 * @arg RCC_HCLK_Div8: APB2 clock = HCLK/8 00792 * @arg RCC_HCLK_Div16: APB2 clock = HCLK/16 00793 * @retval None 00794 */ 00795 void RCC_PCLK2Config(uint32_t RCC_HCLK) 00796 { 00797 uint32_t tmpreg = 0; 00798 00799 /* Check the parameters */ 00800 assert_param(IS_RCC_PCLK(RCC_HCLK)); 00801 00802 tmpreg = RCC->CFGR; 00803 /* Clear PPRE2[2:0] bits */ 00804 tmpreg &= ~RCC_CFGR_PPRE2; 00805 /* Set PPRE2[2:0] bits according to RCC_HCLK value */ 00806 tmpreg |= RCC_HCLK << 3; 00807 /* Store the new value */ 00808 RCC->CFGR = tmpreg; 00809 } 00810 00811 /** 00812 * @brief Returns the frequencies of the System, AHB, APB2 and APB1 busses clocks. 00813 * 00814 * @note This function returns the frequencies of : 00815 * System, AHB, APB2 and APB1 busses clocks, ADC1/2/3/4 clocks, 00816 * USART1/2/3/4/5 clocks, I2C1/2 clocks and TIM1/8 Clocks. 00817 * 00818 * @note The frequency returned by this function is not the real frequency 00819 * in the chip. It is calculated based on the predefined constant and 00820 * the source selected by RCC_SYSCLKConfig(). 00821 * 00822 * @note If SYSCLK source is HSI, function returns constant HSI_VALUE(*) 00823 * 00824 * @note If SYSCLK source is HSE, function returns constant HSE_VALUE(**) 00825 * 00826 * @note If SYSCLK source is PLL, function returns constant HSE_VALUE(**) 00827 * or HSI_VALUE(*) multiplied by the PLL factors. 00828 * 00829 * @note (*) HSI_VALUE is a constant defined in stm32f30x.h file (default value 00830 * 8 MHz) but the real value may vary depending on the variations 00831 * in voltage and temperature, refer to RCC_AdjustHSICalibrationValue(). 00832 * 00833 * @note (**) HSE_VALUE is a constant defined in stm32f30x.h file (default value 00834 * 8 MHz), user has to ensure that HSE_VALUE is same as the real 00835 * frequency of the crystal used. Otherwise, this function may 00836 * return wrong result. 00837 * 00838 * @note The result of this function could be not correct when using fractional 00839 * value for HSE crystal. 00840 * 00841 * @param RCC_Clocks: pointer to a RCC_ClocksTypeDef structure which will hold 00842 * the clocks frequencies. 00843 * 00844 * @note This function can be used by the user application to compute the 00845 * baudrate for the communication peripherals or configure other parameters. 00846 * @note Each time SYSCLK, HCLK, PCLK1 and/or PCLK2 clock changes, this function 00847 * must be called to update the structure's field. Otherwise, any 00848 * configuration based on this function will be incorrect. 00849 * 00850 * @retval None 00851 */ 00852 void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks) 00853 { 00854 uint32_t tmp = 0, pllmull = 0, pllsource = 0, prediv1factor = 0, presc = 0, pllclk = 0; 00855 uint32_t apb2presc = 0, ahbpresc = 0; 00856 00857 /* Get SYSCLK source -------------------------------------------------------*/ 00858 tmp = RCC->CFGR & RCC_CFGR_SWS; 00859 00860 switch (tmp) 00861 { 00862 case 0x00: /* HSI used as system clock */ 00863 RCC_Clocks->SYSCLK_Frequency = HSI_VALUE; 00864 break; 00865 case 0x04: /* HSE used as system clock */ 00866 RCC_Clocks->SYSCLK_Frequency = HSE_VALUE; 00867 break; 00868 case 0x08: /* PLL used as system clock */ 00869 /* Get PLL clock source and multiplication factor ----------------------*/ 00870 pllmull = RCC->CFGR & RCC_CFGR_PLLMULL; 00871 pllsource = RCC->CFGR & RCC_CFGR_PLLSRC; 00872 pllmull = ( pllmull >> 18) + 2; 00873 00874 if (pllsource == 0x00) 00875 { 00876 /* HSI oscillator clock divided by 2 selected as PLL clock entry */ 00877 pllclk = (HSI_VALUE >> 1) * pllmull; 00878 } 00879 else 00880 { 00881 prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1; 00882 /* HSE oscillator clock selected as PREDIV1 clock entry */ 00883 pllclk = (HSE_VALUE / prediv1factor) * pllmull; 00884 } 00885 RCC_Clocks->SYSCLK_Frequency = pllclk; 00886 break; 00887 default: /* HSI used as system clock */ 00888 RCC_Clocks->SYSCLK_Frequency = HSI_VALUE; 00889 break; 00890 } 00891 /* Compute HCLK, PCLK clocks frequencies -----------------------------------*/ 00892 /* Get HCLK prescaler */ 00893 tmp = RCC->CFGR & RCC_CFGR_HPRE; 00894 tmp = tmp >> 4; 00895 ahbpresc = APBAHBPrescTable[tmp]; 00896 /* HCLK clock frequency */ 00897 RCC_Clocks->HCLK_Frequency = RCC_Clocks->SYSCLK_Frequency >> ahbpresc; 00898 00899 /* Get PCLK1 prescaler */ 00900 tmp = RCC->CFGR & RCC_CFGR_PPRE1; 00901 tmp = tmp >> 8; 00902 presc = APBAHBPrescTable[tmp]; 00903 /* PCLK1 clock frequency */ 00904 RCC_Clocks->PCLK1_Frequency = RCC_Clocks->HCLK_Frequency >> presc; 00905 00906 /* Get PCLK2 prescaler */ 00907 tmp = RCC->CFGR & RCC_CFGR_PPRE2; 00908 tmp = tmp >> 11; 00909 apb2presc = APBAHBPrescTable[tmp]; 00910 00911 /* PCLK2 clock frequency */ 00912 RCC_Clocks->PCLK2_Frequency = RCC_Clocks->HCLK_Frequency >> apb2presc; 00913 00914 /* Get ADC12CLK prescaler */ 00915 tmp = RCC->CFGR2 & RCC_CFGR2_ADCPRE12; 00916 tmp = tmp >> 4; 00917 presc = ADCPrescTable[tmp & 0x0F]; 00918 if (((tmp & 0x10) != 0) && (presc != 0)) 00919 { 00920 /* ADC12CLK clock frequency is derived from PLL clock */ 00921 RCC_Clocks->ADC12CLK_Frequency = pllclk / presc; 00922 } 00923 else 00924 { 00925 /* ADC12CLK clock frequency is AHB clock */ 00926 RCC_Clocks->ADC12CLK_Frequency = RCC_Clocks->SYSCLK_Frequency; 00927 } 00928 00929 /* Get ADC34CLK prescaler */ 00930 tmp = RCC->CFGR2 & RCC_CFGR2_ADCPRE34; 00931 tmp = tmp >> 9; 00932 presc = ADCPrescTable[tmp & 0x0F]; 00933 if (((tmp & 0x10) != 0) && (presc != 0)) 00934 { 00935 /* ADC34CLK clock frequency is derived from PLL clock */ 00936 RCC_Clocks->ADC34CLK_Frequency = pllclk / presc; 00937 } 00938 else 00939 { 00940 /* ADC34CLK clock frequency is AHB clock */ 00941 RCC_Clocks->ADC34CLK_Frequency = RCC_Clocks->SYSCLK_Frequency; 00942 } 00943 00944 /* I2C1CLK clock frequency */ 00945 if((RCC->CFGR3 & RCC_CFGR3_I2C1SW) != RCC_CFGR3_I2C1SW) 00946 { 00947 /* I2C1 Clock is HSI Osc. */ 00948 RCC_Clocks->I2C1CLK_Frequency = HSI_VALUE; 00949 } 00950 else 00951 { 00952 /* I2C1 Clock is System Clock */ 00953 RCC_Clocks->I2C1CLK_Frequency = RCC_Clocks->SYSCLK_Frequency; 00954 } 00955 00956 /* I2C2CLK clock frequency */ 00957 if((RCC->CFGR3 & RCC_CFGR3_I2C2SW) != RCC_CFGR3_I2C2SW) 00958 { 00959 /* I2C2 Clock is HSI Osc. */ 00960 RCC_Clocks->I2C2CLK_Frequency = HSI_VALUE; 00961 } 00962 else 00963 { 00964 /* I2C2 Clock is System Clock */ 00965 RCC_Clocks->I2C2CLK_Frequency = RCC_Clocks->SYSCLK_Frequency; 00966 } 00967 00968 /* I2C3CLK clock frequency */ 00969 if((RCC->CFGR3 & RCC_CFGR3_I2C3SW) != RCC_CFGR3_I2C3SW) 00970 { 00971 /* I2C3 Clock is HSI Osc. */ 00972 RCC_Clocks->I2C3CLK_Frequency = HSI_VALUE; 00973 } 00974 else 00975 { 00976 /* I2C3 Clock is System Clock */ 00977 RCC_Clocks->I2C3CLK_Frequency = RCC_Clocks->SYSCLK_Frequency; 00978 } 00979 00980 /* TIM1CLK clock frequency */ 00981 if(((RCC->CFGR3 & RCC_CFGR3_TIM1SW) == RCC_CFGR3_TIM1SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \ 00982 && (apb2presc == ahbpresc)) 00983 { 00984 /* TIM1 Clock is 2 * pllclk */ 00985 RCC_Clocks->TIM1CLK_Frequency = pllclk * 2; 00986 } 00987 else 00988 { 00989 /* TIM1 Clock is APB2 clock. */ 00990 RCC_Clocks->TIM1CLK_Frequency = RCC_Clocks->PCLK2_Frequency; 00991 } 00992 00993 #ifdef STM32F303xE 00994 uint32_t apb1presc = 0; 00995 apb1presc = APBAHBPrescTable[tmp]; 00996 /* TIM2CLK clock frequency */ 00997 if(((RCC->CFGR3 & RCC_CFGR3_TIM2SW) == RCC_CFGR3_TIM2SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \ 00998 && (apb1presc == ahbpresc)) 00999 { 01000 /* TIM2 Clock is pllclk */ 01001 RCC_Clocks->TIM2CLK_Frequency = pllclk * 2 ; 01002 } 01003 else 01004 { 01005 /* TIM2 Clock is APB2 clock. */ 01006 RCC_Clocks->TIM2CLK_Frequency = RCC_Clocks->PCLK1_Frequency; 01007 } 01008 01009 /* TIM3CLK clock frequency */ 01010 if(((RCC->CFGR3 & RCC_CFGR3_TIM3SW) == RCC_CFGR3_TIM3SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \ 01011 && (apb1presc == ahbpresc)) 01012 { 01013 /* TIM3 Clock is pllclk */ 01014 RCC_Clocks->TIM3CLK_Frequency = pllclk * 2; 01015 } 01016 else 01017 { 01018 /* TIM3 Clock is APB2 clock. */ 01019 RCC_Clocks->TIM3CLK_Frequency = RCC_Clocks->PCLK1_Frequency; 01020 } 01021 #endif /* STM32F303xE */ 01022 01023 /* TIM1CLK clock frequency */ 01024 if(((RCC->CFGR3 & RCC_CFGR3_HRTIM1SW) == RCC_CFGR3_HRTIM1SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \ 01025 && (apb2presc == ahbpresc)) 01026 { 01027 /* HRTIM1 Clock is 2 * pllclk */ 01028 RCC_Clocks->HRTIM1CLK_Frequency = pllclk * 2; 01029 } 01030 else 01031 { 01032 /* HRTIM1 Clock is APB2 clock. */ 01033 RCC_Clocks->HRTIM1CLK_Frequency = RCC_Clocks->PCLK2_Frequency; 01034 } 01035 01036 /* TIM8CLK clock frequency */ 01037 if(((RCC->CFGR3 & RCC_CFGR3_TIM8SW) == RCC_CFGR3_TIM8SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \ 01038 && (apb2presc == ahbpresc)) 01039 { 01040 /* TIM8 Clock is 2 * pllclk */ 01041 RCC_Clocks->TIM8CLK_Frequency = pllclk * 2; 01042 } 01043 else 01044 { 01045 /* TIM8 Clock is APB2 clock. */ 01046 RCC_Clocks->TIM8CLK_Frequency = RCC_Clocks->PCLK2_Frequency; 01047 } 01048 01049 /* TIM15CLK clock frequency */ 01050 if(((RCC->CFGR3 & RCC_CFGR3_TIM15SW) == RCC_CFGR3_TIM15SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \ 01051 && (apb2presc == ahbpresc)) 01052 { 01053 /* TIM15 Clock is 2 * pllclk */ 01054 RCC_Clocks->TIM15CLK_Frequency = pllclk * 2; 01055 } 01056 else 01057 { 01058 /* TIM15 Clock is APB2 clock. */ 01059 RCC_Clocks->TIM15CLK_Frequency = RCC_Clocks->PCLK2_Frequency; 01060 } 01061 01062 /* TIM16CLK clock frequency */ 01063 if(((RCC->CFGR3 & RCC_CFGR3_TIM16SW) == RCC_CFGR3_TIM16SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \ 01064 && (apb2presc == ahbpresc)) 01065 { 01066 /* TIM16 Clock is 2 * pllclk */ 01067 RCC_Clocks->TIM16CLK_Frequency = pllclk * 2; 01068 } 01069 else 01070 { 01071 /* TIM16 Clock is APB2 clock. */ 01072 RCC_Clocks->TIM16CLK_Frequency = RCC_Clocks->PCLK2_Frequency; 01073 } 01074 01075 /* TIM17CLK clock frequency */ 01076 if(((RCC->CFGR3 & RCC_CFGR3_TIM17SW) == RCC_CFGR3_TIM17SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \ 01077 && (apb2presc == ahbpresc)) 01078 { 01079 /* TIM17 Clock is 2 * pllclk */ 01080 RCC_Clocks->TIM17CLK_Frequency = pllclk * 2; 01081 } 01082 else 01083 { 01084 /* TIM17 Clock is APB2 clock. */ 01085 RCC_Clocks->TIM16CLK_Frequency = RCC_Clocks->PCLK2_Frequency; 01086 } 01087 01088 /* TIM20CLK clock frequency */ 01089 if(((RCC->CFGR3 & RCC_CFGR3_TIM20SW) == RCC_CFGR3_TIM20SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \ 01090 && (apb2presc == ahbpresc)) 01091 { 01092 /* TIM20 Clock is 2 * pllclk */ 01093 RCC_Clocks->TIM20CLK_Frequency = pllclk * 2; 01094 } 01095 else 01096 { 01097 /* TIM20 Clock is APB2 clock. */ 01098 RCC_Clocks->TIM20CLK_Frequency = RCC_Clocks->PCLK2_Frequency; 01099 } 01100 01101 /* USART1CLK clock frequency */ 01102 if((RCC->CFGR3 & RCC_CFGR3_USART1SW) == 0x0) 01103 { 01104 #if defined(STM32F303x8) || defined(STM32F334x8) || defined(STM32F301x8) || defined(STM32F302x8) 01105 /* USART1 Clock is PCLK1 instead of PCLK2 (limitation described in the 01106 STM32F302/01/34 x4/x6/x8 respective erratasheets) */ 01107 RCC_Clocks->USART1CLK_Frequency = RCC_Clocks->PCLK1_Frequency; 01108 #else 01109 /* USART Clock is PCLK2 */ 01110 RCC_Clocks->USART1CLK_Frequency = RCC_Clocks->PCLK2_Frequency; 01111 #endif 01112 } 01113 else if((RCC->CFGR3 & RCC_CFGR3_USART1SW) == RCC_CFGR3_USART1SW_0) 01114 { 01115 /* USART Clock is System Clock */ 01116 RCC_Clocks->USART1CLK_Frequency = RCC_Clocks->SYSCLK_Frequency; 01117 } 01118 else if((RCC->CFGR3 & RCC_CFGR3_USART1SW) == RCC_CFGR3_USART1SW_1) 01119 { 01120 /* USART Clock is LSE Osc. */ 01121 RCC_Clocks->USART1CLK_Frequency = LSE_VALUE; 01122 } 01123 else if((RCC->CFGR3 & RCC_CFGR3_USART1SW) == RCC_CFGR3_USART1SW) 01124 { 01125 /* USART Clock is HSI Osc. */ 01126 RCC_Clocks->USART1CLK_Frequency = HSI_VALUE; 01127 } 01128 01129 /* USART2CLK clock frequency */ 01130 if((RCC->CFGR3 & RCC_CFGR3_USART2SW) == 0x0) 01131 { 01132 /* USART Clock is PCLK */ 01133 RCC_Clocks->USART2CLK_Frequency = RCC_Clocks->PCLK1_Frequency; 01134 } 01135 else if((RCC->CFGR3 & RCC_CFGR3_USART2SW) == RCC_CFGR3_USART2SW_0) 01136 { 01137 /* USART Clock is System Clock */ 01138 RCC_Clocks->USART2CLK_Frequency = RCC_Clocks->SYSCLK_Frequency; 01139 } 01140 else if((RCC->CFGR3 & RCC_CFGR3_USART2SW) == RCC_CFGR3_USART2SW_1) 01141 { 01142 /* USART Clock is LSE Osc. */ 01143 RCC_Clocks->USART2CLK_Frequency = LSE_VALUE; 01144 } 01145 else if((RCC->CFGR3 & RCC_CFGR3_USART2SW) == RCC_CFGR3_USART2SW) 01146 { 01147 /* USART Clock is HSI Osc. */ 01148 RCC_Clocks->USART2CLK_Frequency = HSI_VALUE; 01149 } 01150 01151 /* USART3CLK clock frequency */ 01152 if((RCC->CFGR3 & RCC_CFGR3_USART3SW) == 0x0) 01153 { 01154 /* USART Clock is PCLK */ 01155 RCC_Clocks->USART3CLK_Frequency = RCC_Clocks->PCLK1_Frequency; 01156 } 01157 else if((RCC->CFGR3 & RCC_CFGR3_USART3SW) == RCC_CFGR3_USART3SW_0) 01158 { 01159 /* USART Clock is System Clock */ 01160 RCC_Clocks->USART3CLK_Frequency = RCC_Clocks->SYSCLK_Frequency; 01161 } 01162 else if((RCC->CFGR3 & RCC_CFGR3_USART3SW) == RCC_CFGR3_USART3SW_1) 01163 { 01164 /* USART Clock is LSE Osc. */ 01165 RCC_Clocks->USART3CLK_Frequency = LSE_VALUE; 01166 } 01167 else if((RCC->CFGR3 & RCC_CFGR3_USART3SW) == RCC_CFGR3_USART3SW) 01168 { 01169 /* USART Clock is HSI Osc. */ 01170 RCC_Clocks->USART3CLK_Frequency = HSI_VALUE; 01171 } 01172 01173 /* UART4CLK clock frequency */ 01174 if((RCC->CFGR3 & RCC_CFGR3_UART4SW) == 0x0) 01175 { 01176 /* USART Clock is PCLK */ 01177 RCC_Clocks->UART4CLK_Frequency = RCC_Clocks->PCLK1_Frequency; 01178 } 01179 else if((RCC->CFGR3 & RCC_CFGR3_UART4SW) == RCC_CFGR3_UART4SW_0) 01180 { 01181 /* USART Clock is System Clock */ 01182 RCC_Clocks->UART4CLK_Frequency = RCC_Clocks->SYSCLK_Frequency; 01183 } 01184 else if((RCC->CFGR3 & RCC_CFGR3_UART4SW) == RCC_CFGR3_UART4SW_1) 01185 { 01186 /* USART Clock is LSE Osc. */ 01187 RCC_Clocks->UART4CLK_Frequency = LSE_VALUE; 01188 } 01189 else if((RCC->CFGR3 & RCC_CFGR3_UART4SW) == RCC_CFGR3_UART4SW) 01190 { 01191 /* USART Clock is HSI Osc. */ 01192 RCC_Clocks->UART4CLK_Frequency = HSI_VALUE; 01193 } 01194 01195 /* UART5CLK clock frequency */ 01196 if((RCC->CFGR3 & RCC_CFGR3_UART5SW) == 0x0) 01197 { 01198 /* USART Clock is PCLK */ 01199 RCC_Clocks->UART5CLK_Frequency = RCC_Clocks->PCLK1_Frequency; 01200 } 01201 else if((RCC->CFGR3 & RCC_CFGR3_UART5SW) == RCC_CFGR3_UART5SW_0) 01202 { 01203 /* USART Clock is System Clock */ 01204 RCC_Clocks->UART5CLK_Frequency = RCC_Clocks->SYSCLK_Frequency; 01205 } 01206 else if((RCC->CFGR3 & RCC_CFGR3_UART5SW) == RCC_CFGR3_UART5SW_1) 01207 { 01208 /* USART Clock is LSE Osc. */ 01209 RCC_Clocks->UART5CLK_Frequency = LSE_VALUE; 01210 } 01211 else if((RCC->CFGR3 & RCC_CFGR3_UART5SW) == RCC_CFGR3_UART5SW) 01212 { 01213 /* USART Clock is HSI Osc. */ 01214 RCC_Clocks->UART5CLK_Frequency = HSI_VALUE; 01215 } 01216 } 01217 01218 /** 01219 * @} 01220 */ 01221 01222 /** @defgroup RCC_Group3 Peripheral clocks configuration functions 01223 * @brief Peripheral clocks configuration functions 01224 * 01225 @verbatim 01226 =============================================================================== 01227 ##### Peripheral clocks configuration functions ##### 01228 =============================================================================== 01229 [..] This section provide functions allowing to configure the Peripheral clocks. 01230 (#) The RTC clock which is derived from the LSE, LSI or HSE_Div32 01231 (HSE divided by 32). 01232 (#) After restart from Reset or wakeup from STANDBY, all peripherals are 01233 off except internal SRAM, Flash and SWD. Before to start using 01234 a peripheral you have to enable its interface clock. You can do this 01235 using RCC_AHBPeriphClockCmd(), RCC_APB2PeriphClockCmd() 01236 and RCC_APB1PeriphClockCmd() functions. 01237 (#) To reset the peripherals configuration (to the default state after 01238 device reset) you can use RCC_AHBPeriphResetCmd(), RCC_APB2PeriphResetCmd() 01239 and RCC_APB1PeriphResetCmd() functions. 01240 @endverbatim 01241 * @{ 01242 */ 01243 01244 /** 01245 * @brief Configures the ADC clock (ADCCLK). 01246 * @param RCC_PLLCLK: defines the ADC clock divider. This clock is derived from 01247 * the PLL Clock. 01248 * This parameter can be one of the following values: 01249 * @arg RCC_ADC12PLLCLK_OFF: ADC12 clock disabled 01250 * @arg RCC_ADC12PLLCLK_Div1: ADC12 clock = PLLCLK/1 01251 * @arg RCC_ADC12PLLCLK_Div2: ADC12 clock = PLLCLK/2 01252 * @arg RCC_ADC12PLLCLK_Div4: ADC12 clock = PLLCLK/4 01253 * @arg RCC_ADC12PLLCLK_Div6: ADC12 clock = PLLCLK/6 01254 * @arg RCC_ADC12PLLCLK_Div8: ADC12 clock = PLLCLK/8 01255 * @arg RCC_ADC12PLLCLK_Div10: ADC12 clock = PLLCLK/10 01256 * @arg RCC_ADC12PLLCLK_Div12: ADC12 clock = PLLCLK/12 01257 * @arg RCC_ADC12PLLCLK_Div16: ADC12 clock = PLLCLK/16 01258 * @arg RCC_ADC12PLLCLK_Div32: ADC12 clock = PLLCLK/32 01259 * @arg RCC_ADC12PLLCLK_Div64: ADC12 clock = PLLCLK/64 01260 * @arg RCC_ADC12PLLCLK_Div128: ADC12 clock = PLLCLK/128 01261 * @arg RCC_ADC12PLLCLK_Div256: ADC12 clock = PLLCLK/256 01262 * @arg RCC_ADC34PLLCLK_OFF: ADC34 clock disabled 01263 * @arg RCC_ADC34PLLCLK_Div1: ADC34 clock = PLLCLK/1 01264 * @arg RCC_ADC34PLLCLK_Div2: ADC34 clock = PLLCLK/2 01265 * @arg RCC_ADC34PLLCLK_Div4: ADC34 clock = PLLCLK/4 01266 * @arg RCC_ADC34PLLCLK_Div6: ADC34 clock = PLLCLK/6 01267 * @arg RCC_ADC34PLLCLK_Div8: ADC34 clock = PLLCLK/8 01268 * @arg RCC_ADC34PLLCLK_Div10: ADC34 clock = PLLCLK/10 01269 * @arg RCC_ADC34PLLCLK_Div12: ADC34 clock = PLLCLK/12 01270 * @arg RCC_ADC34PLLCLK_Div16: ADC34 clock = PLLCLK/16 01271 * @arg RCC_ADC34PLLCLK_Div32: ADC34 clock = PLLCLK/32 01272 * @arg RCC_ADC34PLLCLK_Div64: ADC34 clock = PLLCLK/64 01273 * @arg RCC_ADC34PLLCLK_Div128: ADC34 clock = PLLCLK/128 01274 * @arg RCC_ADC34PLLCLK_Div256: ADC34 clock = PLLCLK/256 01275 * @retval None 01276 */ 01277 void RCC_ADCCLKConfig(uint32_t RCC_PLLCLK) 01278 { 01279 uint32_t tmp = 0; 01280 01281 /* Check the parameters */ 01282 assert_param(IS_RCC_ADCCLK(RCC_PLLCLK)); 01283 01284 tmp = (RCC_PLLCLK >> 28); 01285 01286 /* Clears ADCPRE34 bits */ 01287 if (tmp != 0) 01288 { 01289 RCC->CFGR2 &= ~RCC_CFGR2_ADCPRE34; 01290 } 01291 /* Clears ADCPRE12 bits */ 01292 else 01293 { 01294 RCC->CFGR2 &= ~RCC_CFGR2_ADCPRE12; 01295 } 01296 /* Set ADCPRE bits according to RCC_PLLCLK value */ 01297 RCC->CFGR2 |= RCC_PLLCLK; 01298 } 01299 01300 /** 01301 * @brief Configures the I2C clock (I2CCLK). 01302 * @param RCC_I2CCLK: defines the I2C clock source. This clock is derived 01303 * from the HSI or System clock. 01304 * This parameter can be one of the following values: 01305 * @arg RCC_I2CxCLK_HSI: I2Cx clock = HSI 01306 * @arg RCC_I2CxCLK_SYSCLK: I2Cx clock = System Clock 01307 * (x can be 1 or 2 or 3). 01308 * @retval None 01309 */ 01310 void RCC_I2CCLKConfig(uint32_t RCC_I2CCLK) 01311 { 01312 uint32_t tmp = 0; 01313 01314 /* Check the parameters */ 01315 assert_param(IS_RCC_I2CCLK(RCC_I2CCLK)); 01316 01317 tmp = (RCC_I2CCLK >> 28); 01318 01319 /* Clear I2CSW bit */ 01320 switch (tmp) 01321 { 01322 case 0x00: 01323 RCC->CFGR3 &= ~RCC_CFGR3_I2C1SW; 01324 break; 01325 case 0x01: 01326 RCC->CFGR3 &= ~RCC_CFGR3_I2C2SW; 01327 break; 01328 case 0x02: 01329 RCC->CFGR3 &= ~RCC_CFGR3_I2C3SW; 01330 break; 01331 default: 01332 break; 01333 } 01334 01335 /* Set I2CSW bits according to RCC_I2CCLK value */ 01336 RCC->CFGR3 |= RCC_I2CCLK; 01337 } 01338 01339 /** 01340 * @brief Configures the TIMx clock sources(TIMCLK). 01341 * @note For STM32F303xC devices, TIMx can be clocked from the PLL running at 144 MHz 01342 * when the system clock source is the PLL and HCLK & PCLK2 clocks are not divided in respect to SYSCLK. 01343 * For the devices STM32F334x8, STM32F302x8 and STM32F303xE, TIMx can be clocked from the PLL running at 01344 * 144 MHz when the system clock source is the PLL and AHB or APB2 subsystem clocks are not divided by 01345 * more than 2 cumulatively. 01346 * @note If one of the previous conditions is missed, the TIM clock source 01347 * configuration is lost and calling again this function becomes mandatory. 01348 * @param RCC_TIMCLK: defines the TIMx clock source. 01349 * This parameter can be one of the following values: 01350 * @arg RCC_TIMxCLK_PCLK: TIMx clock = APB clock (doubled frequency when prescaled) 01351 * @arg RCC_TIMxCLK_PLLCLK: TIMx clock = PLL output (running up to 144 MHz) 01352 * (x can be 1, 8, 15, 16, 17, 20, 2, 3,4). 01353 * @note For STM32F303xC devices, TIM1 and TIM8 can be clocked at 144MHz. 01354 * For STM32F303xE devices, TIM1/8/20/2/3/4/15/16/17 can be clocked at 144MHz. 01355 * For STM32F334x8 devices , only TIM1 can be clocked at 144MHz. 01356 * For STM32F302x8 devices, TIM1/15/16/17 can be clocked at 144MHz 01357 * @retval None 01358 */ 01359 void RCC_TIMCLKConfig(uint32_t RCC_TIMCLK) 01360 { 01361 uint32_t tmp = 0; 01362 01363 /* Check the parameters */ 01364 assert_param(IS_RCC_TIMCLK(RCC_TIMCLK)); 01365 01366 tmp = (RCC_TIMCLK >> 28); 01367 01368 /* Clear TIMSW bit */ 01369 01370 switch (tmp) 01371 { 01372 case 0x00: 01373 RCC->CFGR3 &= ~RCC_CFGR3_TIM1SW; 01374 break; 01375 case 0x01: 01376 RCC->CFGR3 &= ~RCC_CFGR3_TIM8SW; 01377 break; 01378 case 0x02: 01379 RCC->CFGR3 &= ~RCC_CFGR3_TIM15SW; 01380 break; 01381 case 0x03: 01382 RCC->CFGR3 &= ~RCC_CFGR3_TIM16SW; 01383 break; 01384 case 0x04: 01385 RCC->CFGR3 &= ~RCC_CFGR3_TIM17SW; 01386 break; 01387 case 0x05: 01388 RCC->CFGR3 &= ~RCC_CFGR3_TIM20SW; 01389 case 0x06: 01390 RCC->CFGR3 &= ~RCC_CFGR3_TIM2SW; 01391 case 0x07: 01392 RCC->CFGR3 &= ~RCC_CFGR3_TIM3SW; 01393 break; 01394 default: 01395 break; 01396 } 01397 01398 /* Set I2CSW bits according to RCC_TIMCLK value */ 01399 RCC->CFGR3 |= RCC_TIMCLK; 01400 } 01401 01402 /** 01403 * @brief Configures the HRTIM1 clock sources(HRTIM1CLK). 01404 * @note The configuration of the HRTIM1 clock source is only possible when the 01405 * SYSCLK = PLL and HCLK and PCLK2 clocks are not divided in respect to SYSCLK 01406 * @note If one of the previous conditions is missed, the TIM clock source 01407 * configuration is lost and calling again this function becomes mandatory. 01408 * @param RCC_HRTIMCLK: defines the TIMx clock source. 01409 * This parameter can be one of the following values: 01410 * @arg RCC_HRTIM1CLK_HCLK: TIMx clock = APB high speed clock (doubled frequency 01411 * when prescaled) 01412 * @arg RCC_HRTIM1CLK_PLLCLK: TIMx clock = PLL output (running up to 144 MHz) 01413 * (x can be 1 or 8). 01414 * @retval None 01415 */ 01416 void RCC_HRTIM1CLKConfig(uint32_t RCC_HRTIMCLK) 01417 { 01418 /* Check the parameters */ 01419 assert_param(IS_RCC_HRTIMCLK(RCC_HRTIMCLK)); 01420 01421 /* Clear HRTIMSW bit */ 01422 RCC->CFGR3 &= ~RCC_CFGR3_HRTIM1SW; 01423 01424 /* Set HRTIMSW bits according to RCC_HRTIMCLK value */ 01425 RCC->CFGR3 |= RCC_HRTIMCLK; 01426 } 01427 01428 /** 01429 * @brief Configures the USART clock (USARTCLK). 01430 * @param RCC_USARTCLK: defines the USART clock source. This clock is derived 01431 * from the HSI or System clock. 01432 * This parameter can be one of the following values: 01433 * @arg RCC_USARTxCLK_PCLK: USART clock = APB Clock (PCLK) 01434 * @arg RCC_USARTxCLK_SYSCLK: USART clock = System Clock 01435 * @arg RCC_USARTxCLK_LSE: USART clock = LSE Clock 01436 * @arg RCC_USARTxCLK_HSI: USART clock = HSI Clock 01437 * (x can be 1, 2, 3, 4 or 5). 01438 * @retval None 01439 */ 01440 void RCC_USARTCLKConfig(uint32_t RCC_USARTCLK) 01441 { 01442 uint32_t tmp = 0; 01443 01444 /* Check the parameters */ 01445 assert_param(IS_RCC_USARTCLK(RCC_USARTCLK)); 01446 01447 tmp = (RCC_USARTCLK >> 28); 01448 01449 /* Clear USARTSW[1:0] bit */ 01450 switch (tmp) 01451 { 01452 case 0x01: /* clear USART1SW */ 01453 RCC->CFGR3 &= ~RCC_CFGR3_USART1SW; 01454 break; 01455 case 0x02: /* clear USART2SW */ 01456 RCC->CFGR3 &= ~RCC_CFGR3_USART2SW; 01457 break; 01458 case 0x03: /* clear USART3SW */ 01459 RCC->CFGR3 &= ~RCC_CFGR3_USART3SW; 01460 break; 01461 case 0x04: /* clear UART4SW */ 01462 RCC->CFGR3 &= ~RCC_CFGR3_UART4SW; 01463 break; 01464 case 0x05: /* clear UART5SW */ 01465 RCC->CFGR3 &= ~RCC_CFGR3_UART5SW; 01466 break; 01467 default: 01468 break; 01469 } 01470 01471 /* Set USARTSW bits according to RCC_USARTCLK value */ 01472 RCC->CFGR3 |= RCC_USARTCLK; 01473 } 01474 01475 /** 01476 * @brief Configures the USB clock (USBCLK). 01477 * @param RCC_USBCLKSource: specifies the USB clock source. This clock is 01478 * derived from the PLL output. 01479 * This parameter can be one of the following values: 01480 * @arg RCC_USBCLKSource_PLLCLK_1Div5: PLL clock divided by 1,5 selected as USB 01481 * clock source 01482 * @arg RCC_USBCLKSource_PLLCLK_Div1: PLL clock selected as USB clock source 01483 * @retval None 01484 */ 01485 void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource) 01486 { 01487 /* Check the parameters */ 01488 assert_param(IS_RCC_USBCLK_SOURCE(RCC_USBCLKSource)); 01489 01490 *(__IO uint32_t *) CFGR_USBPRE_BB = RCC_USBCLKSource; 01491 } 01492 01493 /** 01494 * @brief Configures the RTC clock (RTCCLK). 01495 * @note As the RTC clock configuration bits are in the Backup domain and write 01496 * access is denied to this domain after reset, you have to enable write 01497 * access using PWR_BackupAccessCmd(ENABLE) function before to configure 01498 * the RTC clock source (to be done once after reset). 01499 * @note Once the RTC clock is configured it can't be changed unless the RTC 01500 * is reset using RCC_BackupResetCmd function, or by a Power On Reset (POR) 01501 * 01502 * @param RCC_RTCCLKSource: specifies the RTC clock source. 01503 * This parameter can be one of the following values: 01504 * @arg RCC_RTCCLKSource_LSE: LSE selected as RTC clock 01505 * @arg RCC_RTCCLKSource_LSI: LSI selected as RTC clock 01506 * @arg RCC_RTCCLKSource_HSE_Div32: HSE divided by 32 selected as RTC clock 01507 * 01508 * @note If the LSE or LSI is used as RTC clock source, the RTC continues to 01509 * work in STOP and STANDBY modes, and can be used as wakeup source. 01510 * However, when the HSE clock is used as RTC clock source, the RTC 01511 * cannot be used in STOP and STANDBY modes. 01512 * @note The maximum input clock frequency for RTC is 2MHz (when using HSE as 01513 * RTC clock source). 01514 * @retval None 01515 */ 01516 void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource) 01517 { 01518 /* Check the parameters */ 01519 assert_param(IS_RCC_RTCCLK_SOURCE(RCC_RTCCLKSource)); 01520 01521 /* Select the RTC clock source */ 01522 RCC->BDCR |= RCC_RTCCLKSource; 01523 } 01524 01525 /** 01526 * @brief Configures the I2S clock source (I2SCLK). 01527 * @note This function must be called before enabling the SPI2 and SPI3 clocks. 01528 * @param RCC_I2SCLKSource: specifies the I2S clock source. 01529 * This parameter can be one of the following values: 01530 * @arg RCC_I2S2CLKSource_SYSCLK: SYSCLK clock used as I2S clock source 01531 * @arg RCC_I2S2CLKSource_Ext: External clock mapped on the I2S_CKIN pin 01532 * used as I2S clock source 01533 * @retval None 01534 */ 01535 void RCC_I2SCLKConfig(uint32_t RCC_I2SCLKSource) 01536 { 01537 /* Check the parameters */ 01538 assert_param(IS_RCC_I2SCLK_SOURCE(RCC_I2SCLKSource)); 01539 01540 *(__IO uint32_t *) CFGR_I2SSRC_BB = RCC_I2SCLKSource; 01541 } 01542 01543 /** 01544 * @brief Enables or disables the RTC clock. 01545 * @note This function must be used only after the RTC clock source was selected 01546 * using the RCC_RTCCLKConfig function. 01547 * @param NewState: new state of the RTC clock. 01548 * This parameter can be: ENABLE or DISABLE. 01549 * @retval None 01550 */ 01551 void RCC_RTCCLKCmd(FunctionalState NewState) 01552 { 01553 /* Check the parameters */ 01554 assert_param(IS_FUNCTIONAL_STATE(NewState)); 01555 01556 *(__IO uint32_t *) BDCR_RTCEN_BB = (uint32_t)NewState; 01557 } 01558 01559 /** 01560 * @brief Forces or releases the Backup domain reset. 01561 * @note This function resets the RTC peripheral (including the backup registers) 01562 * and the RTC clock source selection in RCC_BDCR register. 01563 * @param NewState: new state of the Backup domain reset. 01564 * This parameter can be: ENABLE or DISABLE. 01565 * @retval None 01566 */ 01567 void RCC_BackupResetCmd(FunctionalState NewState) 01568 { 01569 /* Check the parameters */ 01570 assert_param(IS_FUNCTIONAL_STATE(NewState)); 01571 01572 *(__IO uint32_t *) BDCR_BDRST_BB = (uint32_t)NewState; 01573 } 01574 01575 /** 01576 * @brief Enables or disables the AHB peripheral clock. 01577 * @note After reset, the peripheral clock (used for registers read/write access) 01578 * is disabled and the application software has to enable this clock before 01579 * using it. 01580 * @param RCC_AHBPeriph: specifies the AHB peripheral to gates its clock. 01581 * This parameter can be any combination of the following values: 01582 * @arg RCC_AHBPeriph_GPIOA 01583 * @arg RCC_AHBPeriph_GPIOB 01584 * @arg RCC_AHBPeriph_GPIOC 01585 * @arg RCC_AHBPeriph_GPIOD 01586 * @arg RCC_AHBPeriph_GPIOE 01587 * @arg RCC_AHBPeriph_GPIOF 01588 * @arg RCC_AHBPeriph_GPIOG 01589 * @arg RCC_AHBPeriph_GPIOH 01590 * @arg RCC_AHBPeriph_TS 01591 * @arg RCC_AHBPeriph_CRC 01592 * @arg RCC_AHBPeriph_FMC 01593 * @arg RCC_AHBPeriph_FLITF (has effect only when the Flash memory is in power down mode) 01594 * @arg RCC_AHBPeriph_SRAM 01595 * @arg RCC_AHBPeriph_DMA2 01596 * @arg RCC_AHBPeriph_DMA1 01597 * @arg RCC_AHBPeriph_ADC34 01598 * @arg RCC_AHBPeriph_ADC12 01599 * @param NewState: new state of the specified peripheral clock. 01600 * This parameter can be: ENABLE or DISABLE. 01601 * @retval None 01602 */ 01603 void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState) 01604 { 01605 /* Check the parameters */ 01606 assert_param(IS_RCC_AHB_PERIPH(RCC_AHBPeriph)); 01607 assert_param(IS_FUNCTIONAL_STATE(NewState)); 01608 01609 if (NewState != DISABLE) 01610 { 01611 RCC->AHBENR |= RCC_AHBPeriph; 01612 } 01613 else 01614 { 01615 RCC->AHBENR &= ~RCC_AHBPeriph; 01616 } 01617 } 01618 01619 /** 01620 * @brief Enables or disables the High Speed APB (APB2) peripheral clock. 01621 * @note After reset, the peripheral clock (used for registers read/write access) 01622 * is disabled and the application software has to enable this clock before 01623 * using it. 01624 * @param RCC_APB2Periph: specifies the APB2 peripheral to gates its clock. 01625 * This parameter can be any combination of the following values: 01626 * @arg RCC_APB2Periph_SYSCFG 01627 * @arg RCC_APB2Periph_SPI1 01628 * @arg RCC_APB2Periph_USART1 01629 * @arg RCC_APB2Periph_SPI4 01630 * @arg RCC_APB2Periph_TIM15 01631 * @arg RCC_APB2Periph_TIM16 01632 * @arg RCC_APB2Periph_TIM17 01633 * @arg RCC_APB2Periph_TIM1 01634 * @arg RCC_APB2Periph_TIM8 01635 * @arg RCC_APB2Periph_HRTIM1 01636 * @arg RCC_APB2Periph_TIM20 01637 * @param NewState: new state of the specified peripheral clock. 01638 * This parameter can be: ENABLE or DISABLE. 01639 * @retval None 01640 */ 01641 void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState) 01642 { 01643 /* Check the parameters */ 01644 assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph)); 01645 assert_param(IS_FUNCTIONAL_STATE(NewState)); 01646 01647 if (NewState != DISABLE) 01648 { 01649 RCC->APB2ENR |= RCC_APB2Periph; 01650 } 01651 else 01652 { 01653 RCC->APB2ENR &= ~RCC_APB2Periph; 01654 } 01655 } 01656 01657 /** 01658 * @brief Enables or disables the Low Speed APB (APB1) peripheral clock. 01659 * @note After reset, the peripheral clock (used for registers read/write access) 01660 * is disabled and the application software has to enable this clock before 01661 * using it. 01662 * @param RCC_APB1Periph: specifies the APB1 peripheral to gates its clock. 01663 * This parameter can be any combination of the following values: 01664 * @arg RCC_APB1Periph_TIM2 01665 * @arg RCC_APB1Periph_TIM3 01666 * @arg RCC_APB1Periph_TIM4 01667 * @arg RCC_APB1Periph_TIM6 01668 * @arg RCC_APB1Periph_TIM7 01669 * @arg RCC_APB1Periph_WWDG 01670 * @arg RCC_APB1Periph_SPI2 01671 * @arg RCC_APB1Periph_SPI3 01672 * @arg RCC_APB1Periph_USART2 01673 * @arg RCC_APB1Periph_USART3 01674 * @arg RCC_APB1Periph_UART4 01675 * @arg RCC_APB1Periph_UART5 01676 * @arg RCC_APB1Periph_I2C1 01677 * @arg RCC_APB1Periph_I2C2 01678 * @arg RCC_APB1Periph_USB 01679 * @arg RCC_APB1Periph_CAN1 01680 * @arg RCC_APB1Periph_PWR 01681 * @arg RCC_APB1Periph_DAC1 01682 * @arg RCC_APB1Periph_DAC2 01683 * @arg RCC_APB1Periph_I2C3 01684 * @param NewState: new state of the specified peripheral clock. 01685 * This parameter can be: ENABLE or DISABLE. 01686 * @retval None 01687 */ 01688 void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState) 01689 { 01690 /* Check the parameters */ 01691 assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph)); 01692 assert_param(IS_FUNCTIONAL_STATE(NewState)); 01693 01694 if (NewState != DISABLE) 01695 { 01696 RCC->APB1ENR |= RCC_APB1Periph; 01697 } 01698 else 01699 { 01700 RCC->APB1ENR &= ~RCC_APB1Periph; 01701 } 01702 } 01703 01704 /** 01705 * @brief Forces or releases AHB peripheral reset. 01706 * @param RCC_AHBPeriph: specifies the AHB peripheral to reset. 01707 * This parameter can be any combination of the following values: 01708 * @arg RCC_AHBPeriph_FMC 01709 * @arg RCC_AHBPeriph_GPIOH 01710 * @arg RCC_AHBPeriph_GPIOA 01711 * @arg RCC_AHBPeriph_GPIOB 01712 * @arg RCC_AHBPeriph_GPIOC 01713 * @arg RCC_AHBPeriph_GPIOD 01714 * @arg RCC_AHBPeriph_GPIOE 01715 * @arg RCC_AHBPeriph_GPIOF 01716 * @arg RCC_AHBPeriph_GPIOG 01717 * @arg RCC_AHBPeriph_TS 01718 * @arg RCC_AHBPeriph_ADC34 01719 * @arg RCC_AHBPeriph_ADC12 01720 * @param NewState: new state of the specified peripheral reset. 01721 * This parameter can be: ENABLE or DISABLE. 01722 * @retval None 01723 */ 01724 void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState) 01725 { 01726 /* Check the parameters */ 01727 assert_param(IS_RCC_AHB_RST_PERIPH(RCC_AHBPeriph)); 01728 assert_param(IS_FUNCTIONAL_STATE(NewState)); 01729 01730 if (NewState != DISABLE) 01731 { 01732 RCC->AHBRSTR |= RCC_AHBPeriph; 01733 } 01734 else 01735 { 01736 RCC->AHBRSTR &= ~RCC_AHBPeriph; 01737 } 01738 } 01739 01740 /** 01741 * @brief Forces or releases High Speed APB (APB2) peripheral reset. 01742 * @param RCC_APB2Periph: specifies the APB2 peripheral to reset. 01743 * This parameter can be any combination of the following values: 01744 * @arg RCC_APB2Periph_SYSCFG 01745 * @arg RCC_APB2Periph_SPI1 01746 * @arg RCC_APB2Periph_USART1 01747 * @arg RCC_APB2Periph_SPI4 01748 * @arg RCC_APB2Periph_TIM15 01749 * @arg RCC_APB2Periph_TIM16 01750 * @arg RCC_APB2Periph_TIM17 01751 * @arg RCC_APB2Periph_TIM1 01752 * @arg RCC_APB2Periph_TIM8 01753 * @arg RCC_APB2Periph_TIM20 01754 * @arg RCC_APB2Periph_HRTIM1 01755 * @param NewState: new state of the specified peripheral reset. 01756 * This parameter can be: ENABLE or DISABLE. 01757 * @retval None 01758 */ 01759 void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState) 01760 { 01761 /* Check the parameters */ 01762 assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph)); 01763 assert_param(IS_FUNCTIONAL_STATE(NewState)); 01764 01765 if (NewState != DISABLE) 01766 { 01767 RCC->APB2RSTR |= RCC_APB2Periph; 01768 } 01769 else 01770 { 01771 RCC->APB2RSTR &= ~RCC_APB2Periph; 01772 } 01773 } 01774 01775 /** 01776 * @brief Forces or releases Low Speed APB (APB1) peripheral reset. 01777 * @param RCC_APB1Periph: specifies the APB1 peripheral to reset. 01778 * This parameter can be any combination of the following values: 01779 * @arg RCC_APB1Periph_TIM2 01780 * @arg RCC_APB1Periph_TIM3 01781 * @arg RCC_APB1Periph_TIM4 01782 * @arg RCC_APB1Periph_TIM6 01783 * @arg RCC_APB1Periph_TIM7 01784 * @arg RCC_APB1Periph_WWDG 01785 * @arg RCC_APB1Periph_SPI2 01786 * @arg RCC_APB1Periph_SPI3 01787 * @arg RCC_APB1Periph_USART2 01788 * @arg RCC_APB1Periph_USART3 01789 * @arg RCC_APB1Periph_UART4 01790 * @arg RCC_APB1Periph_UART5 01791 * @arg RCC_APB1Periph_I2C1 01792 * @arg RCC_APB1Periph_I2C2 01793 * @arg RCC_APB1Periph_I2C3 01794 * @arg RCC_APB1Periph_USB 01795 * @arg RCC_APB1Periph_CAN1 01796 * @arg RCC_APB1Periph_PWR 01797 * @arg RCC_APB1Periph_DAC 01798 * @param NewState: new state of the specified peripheral clock. 01799 * This parameter can be: ENABLE or DISABLE. 01800 * @retval None 01801 */ 01802 void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState) 01803 { 01804 /* Check the parameters */ 01805 assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph)); 01806 assert_param(IS_FUNCTIONAL_STATE(NewState)); 01807 01808 if (NewState != DISABLE) 01809 { 01810 RCC->APB1RSTR |= RCC_APB1Periph; 01811 } 01812 else 01813 { 01814 RCC->APB1RSTR &= ~RCC_APB1Periph; 01815 } 01816 } 01817 01818 /** 01819 * @} 01820 */ 01821 01822 /** @defgroup RCC_Group4 Interrupts and flags management functions 01823 * @brief Interrupts and flags management functions 01824 * 01825 @verbatim 01826 =============================================================================== 01827 ##### Interrupts and flags management functions ##### 01828 =============================================================================== 01829 01830 @endverbatim 01831 * @{ 01832 */ 01833 01834 /** 01835 * @brief Enables or disables the specified RCC interrupts. 01836 * @note The CSS interrupt doesn't have an enable bit; once the CSS is enabled 01837 * and if the HSE clock fails, the CSS interrupt occurs and an NMI is 01838 * automatically generated. The NMI will be executed indefinitely, and 01839 * since NMI has higher priority than any other IRQ (and main program) 01840 * the application will be stacked in the NMI ISR unless the CSS interrupt 01841 * pending bit is cleared. 01842 * @param RCC_IT: specifies the RCC interrupt sources to be enabled or disabled. 01843 * This parameter can be any combination of the following values: 01844 * @arg RCC_IT_LSIRDY: LSI ready interrupt 01845 * @arg RCC_IT_LSERDY: LSE ready interrupt 01846 * @arg RCC_IT_HSIRDY: HSI ready interrupt 01847 * @arg RCC_IT_HSERDY: HSE ready interrupt 01848 * @arg RCC_IT_PLLRDY: PLL ready interrupt 01849 * @param NewState: new state of the specified RCC interrupts. 01850 * This parameter can be: ENABLE or DISABLE. 01851 * @retval None 01852 */ 01853 void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState) 01854 { 01855 /* Check the parameters */ 01856 assert_param(IS_RCC_IT(RCC_IT)); 01857 assert_param(IS_FUNCTIONAL_STATE(NewState)); 01858 01859 if (NewState != DISABLE) 01860 { 01861 /* Perform Byte access to RCC_CIR[13:8] bits to enable the selected interrupts */ 01862 *(__IO uint8_t *) CIR_BYTE2_ADDRESS |= RCC_IT; 01863 } 01864 else 01865 { 01866 /* Perform Byte access to RCC_CIR[13:8] bits to disable the selected interrupts */ 01867 *(__IO uint8_t *) CIR_BYTE2_ADDRESS &= (uint8_t)~RCC_IT; 01868 } 01869 } 01870 01871 /** 01872 * @brief Checks whether the specified RCC flag is set or not. 01873 * @param RCC_FLAG: specifies the flag to check. 01874 * This parameter can be one of the following values: 01875 * @arg RCC_FLAG_HSIRDY: HSI oscillator clock ready 01876 * @arg RCC_FLAG_HSERDY: HSE oscillator clock ready 01877 * @arg RCC_FLAG_PLLRDY: PLL clock ready 01878 * @arg RCC_FLAG_MCOF: MCO Flag 01879 * @arg RCC_FLAG_LSERDY: LSE oscillator clock ready 01880 * @arg RCC_FLAG_LSIRDY: LSI oscillator clock ready 01881 * @arg RCC_FLAG_OBLRST: Option Byte Loader (OBL) reset 01882 * @arg RCC_FLAG_PINRST: Pin reset 01883 * @arg RCC_FLAG_PORRST: POR/PDR reset 01884 * @arg RCC_FLAG_SFTRST: Software reset 01885 * @arg RCC_FLAG_IWDGRST: Independent Watchdog reset 01886 * @arg RCC_FLAG_WWDGRST: Window Watchdog reset 01887 * @arg RCC_FLAG_LPWRRST: Low Power reset 01888 * @retval The new state of RCC_FLAG (SET or RESET). 01889 */ 01890 FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG) 01891 { 01892 uint32_t tmp = 0; 01893 uint32_t statusreg = 0; 01894 FlagStatus bitstatus = RESET; 01895 01896 /* Check the parameters */ 01897 assert_param(IS_RCC_FLAG(RCC_FLAG)); 01898 01899 /* Get the RCC register index */ 01900 tmp = RCC_FLAG >> 5; 01901 01902 if (tmp == 0) /* The flag to check is in CR register */ 01903 { 01904 statusreg = RCC->CR; 01905 } 01906 else if (tmp == 1) /* The flag to check is in BDCR register */ 01907 { 01908 statusreg = RCC->BDCR; 01909 } 01910 else if (tmp == 4) /* The flag to check is in CFGR register */ 01911 { 01912 statusreg = RCC->CFGR; 01913 } 01914 else /* The flag to check is in CSR register */ 01915 { 01916 statusreg = RCC->CSR; 01917 } 01918 01919 /* Get the flag position */ 01920 tmp = RCC_FLAG & FLAG_MASK; 01921 01922 if ((statusreg & ((uint32_t)1 << tmp)) != (uint32_t)RESET) 01923 { 01924 bitstatus = SET; 01925 } 01926 else 01927 { 01928 bitstatus = RESET; 01929 } 01930 /* Return the flag status */ 01931 return bitstatus; 01932 } 01933 01934 /** 01935 * @brief Clears the RCC reset flags. 01936 * The reset flags are: RCC_FLAG_OBLRST, RCC_FLAG_PINRST, RCC_FLAG_PORRST, 01937 * RCC_FLAG_SFTRST, RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST, RCC_FLAG_LPWRRST. 01938 * @param None 01939 * @retval None 01940 */ 01941 void RCC_ClearFlag(void) 01942 { 01943 /* Set RMVF bit to clear the reset flags */ 01944 RCC->CSR |= RCC_CSR_RMVF; 01945 } 01946 01947 /** 01948 * @brief Checks whether the specified RCC interrupt has occurred or not. 01949 * @param RCC_IT: specifies the RCC interrupt source to check. 01950 * This parameter can be one of the following values: 01951 * @arg RCC_IT_LSIRDY: LSI ready interrupt 01952 * @arg RCC_IT_LSERDY: LSE ready interrupt 01953 * @arg RCC_IT_HSIRDY: HSI ready interrupt 01954 * @arg RCC_IT_HSERDY: HSE ready interrupt 01955 * @arg RCC_IT_PLLRDY: PLL ready interrupt 01956 * @arg RCC_IT_CSS: Clock Security System interrupt 01957 * @retval The new state of RCC_IT (SET or RESET). 01958 */ 01959 ITStatus RCC_GetITStatus(uint8_t RCC_IT) 01960 { 01961 ITStatus bitstatus = RESET; 01962 01963 /* Check the parameters */ 01964 assert_param(IS_RCC_GET_IT(RCC_IT)); 01965 01966 /* Check the status of the specified RCC interrupt */ 01967 if ((RCC->CIR & RCC_IT) != (uint32_t)RESET) 01968 { 01969 bitstatus = SET; 01970 } 01971 else 01972 { 01973 bitstatus = RESET; 01974 } 01975 /* Return the RCC_IT status */ 01976 return bitstatus; 01977 } 01978 01979 /** 01980 * @brief Clears the RCC's interrupt pending bits. 01981 * @param RCC_IT: specifies the interrupt pending bit to clear. 01982 * This parameter can be any combination of the following values: 01983 * @arg RCC_IT_LSIRDY: LSI ready interrupt 01984 * @arg RCC_IT_LSERDY: LSE ready interrupt 01985 * @arg RCC_IT_HSIRDY: HSI ready interrupt 01986 * @arg RCC_IT_HSERDY: HSE ready interrupt 01987 * @arg RCC_IT_PLLRDY: PLL ready interrupt 01988 * @arg RCC_IT_CSS: Clock Security System interrupt 01989 * @retval None 01990 */ 01991 void RCC_ClearITPendingBit(uint8_t RCC_IT) 01992 { 01993 /* Check the parameters */ 01994 assert_param(IS_RCC_CLEAR_IT(RCC_IT)); 01995 01996 /* Perform Byte access to RCC_CIR[23:16] bits to clear the selected interrupt 01997 pending bits */ 01998 *(__IO uint8_t *) CIR_BYTE3_ADDRESS = RCC_IT; 01999 } 02000 02001 /** 02002 * @} 02003 */ 02004 02005 /** 02006 * @} 02007 */ 02008 02009 /** 02010 * @} 02011 */ 02012 02013 /** 02014 * @} 02015 */ 02016 02017 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
Generated on Tue Jul 12 2022 17:34:44 by
