Create release.yml
[betaflight.git] / lib / main / STM32F3 / Drivers / STM32F30x_StdPeriph_Driver / src / stm32f30x_rcc.c
blob98808110fc53a9d355c074062d3f8d5a46672c30
1 /**
2 ******************************************************************************
3 * @file stm32f30x_rcc.c
4 * @author MCD Application Team
5 * @version V1.1.1
6 * @date 04-April-2014
7 * @brief This file provides firmware functions to manage the following
8 * functionalities of the Reset and clock control (RCC) peripheral:
9 * + Internal/external clocks, PLL, CSS and MCO configuration
10 * + System, AHB and APB busses clocks configuration
11 * + Peripheral clocks configuration
12 * + Interrupts and flags management
14 @verbatim
16 ===============================================================================
17 ##### RCC specific features #####
18 ===============================================================================
19 [..] After reset the device is running from HSI (8 MHz) with Flash 0 WS,
20 all peripherals are off except internal SRAM, Flash and SWD.
21 (+) There is no prescaler on High speed (AHB) and Low speed (APB) busses;
22 all peripherals mapped on these busses are running at HSI speed.
23 (+) The clock for all peripherals is switched off, except the SRAM and FLASH.
24 (+) All GPIOs are in input floating state, except the SWD pins which
25 are assigned to be used for debug purpose.
26 [..] Once the device starts from reset, the user application has to:
27 (+) Configure the clock source to be used to drive the System clock
28 (if the application needs higher frequency/performance).
29 (+) Configure the System clock frequency and Flash settings.
30 (+) Configure the AHB and APB busses prescalers.
31 (+) Enable the clock for the peripheral(s) to be used.
32 (+) Configure the clock source(s) for peripherals which clocks are not
33 derived from the System clock (ADC, TIM, I2C, USART, RTC and IWDG).
35 @endverbatim
37 ******************************************************************************
38 * @attention
40 * <h2><center>&copy; COPYRIGHT 2014 STMicroelectronics</center></h2>
42 * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
43 * You may not use this file except in compliance with the License.
44 * You may obtain a copy of the License at:
46 * http://www.st.com/software_license_agreement_liberty_v2
48 * Unless required by applicable law or agreed to in writing, software
49 * distributed under the License is distributed on an "AS IS" BASIS,
50 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
51 * See the License for the specific language governing permissions and
52 * limitations under the License.
54 ******************************************************************************
57 /* Includes ------------------------------------------------------------------*/
58 #include "stm32f30x_rcc.h"
60 /** @addtogroup STM32F30x_StdPeriph_Driver
61 * @{
64 /** @defgroup RCC
65 * @brief RCC driver modules
66 * @{
67 */
69 /* Private typedef -----------------------------------------------------------*/
70 /* Private define ------------------------------------------------------------*/
71 /* ------------ RCC registers bit address in the alias region ----------- */
72 #define RCC_OFFSET (RCC_BASE - PERIPH_BASE)
74 /* --- CR Register ---*/
76 /* Alias word address of HSION bit */
77 #define CR_OFFSET (RCC_OFFSET + 0x00)
78 #define HSION_BitNumber 0x00
79 #define CR_HSION_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (HSION_BitNumber * 4))
81 /* Alias word address of PLLON bit */
82 #define PLLON_BitNumber 0x18
83 #define CR_PLLON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLON_BitNumber * 4))
85 /* Alias word address of CSSON bit */
86 #define CSSON_BitNumber 0x13
87 #define CR_CSSON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (CSSON_BitNumber * 4))
89 /* --- CFGR Register ---*/
90 /* Alias word address of USBPRE bit */
91 #define CFGR_OFFSET (RCC_OFFSET + 0x04)
92 #define USBPRE_BitNumber 0x16
93 #define CFGR_USBPRE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (USBPRE_BitNumber * 4))
94 /* Alias word address of I2SSRC bit */
95 #define I2SSRC_BitNumber 0x17
96 #define CFGR_I2SSRC_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (I2SSRC_BitNumber * 4))
98 /* --- BDCR Register ---*/
100 /* Alias word address of RTCEN bit */
101 #define BDCR_OFFSET (RCC_OFFSET + 0x20)
102 #define RTCEN_BitNumber 0x0F
103 #define BDCR_RTCEN_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (RTCEN_BitNumber * 4))
105 /* Alias word address of BDRST bit */
106 #define BDRST_BitNumber 0x10
107 #define BDCR_BDRST_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (BDRST_BitNumber * 4))
109 /* --- CSR Register ---*/
111 /* Alias word address of LSION bit */
112 #define CSR_OFFSET (RCC_OFFSET + 0x24)
113 #define LSION_BitNumber 0x00
114 #define CSR_LSION_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (LSION_BitNumber * 4))
116 /* ---------------------- RCC registers bit mask ------------------------ */
117 /* RCC Flag Mask */
118 #define FLAG_MASK ((uint8_t)0x1F)
120 /* CFGR register byte 3 (Bits[31:23]) base address */
121 #define CFGR_BYTE3_ADDRESS ((uint32_t)0x40021007)
123 /* CIR register byte 2 (Bits[15:8]) base address */
124 #define CIR_BYTE2_ADDRESS ((uint32_t)0x40021009)
126 /* CIR register byte 3 (Bits[23:16]) base address */
127 #define CIR_BYTE3_ADDRESS ((uint32_t)0x4002100A)
129 /* CR register byte 2 (Bits[23:16]) base address */
130 #define CR_BYTE2_ADDRESS ((uint32_t)0x40021002)
132 /* Private macro -------------------------------------------------------------*/
133 /* Private variables ---------------------------------------------------------*/
134 static __I uint8_t APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};
135 static __I uint16_t ADCPrescTable[16] = {1, 2, 4, 6, 8, 10, 12, 16, 32, 64, 128, 256, 0, 0, 0, 0 };
137 /* Private function prototypes -----------------------------------------------*/
138 /* Private functions ---------------------------------------------------------*/
140 /** @defgroup RCC_Private_Functions
141 * @{
144 /** @defgroup RCC_Group1 Internal and external clocks, PLL, CSS and MCO configuration functions
145 * @brief Internal and external clocks, PLL, CSS and MCO configuration functions
147 @verbatim
148 ===============================================================================
149 ##### Internal-external clocks, PLL, CSS and MCO configuration functions #####
150 ===============================================================================
151 [..] This section provides functions allowing to configure the internal/external
152 clocks, PLL, CSS and MCO.
153 (#) HSI (high-speed internal), 8 MHz factory-trimmed RC used directly
154 or through the PLL as System clock source.
155 The HSI clock can be used also to clock the USART and I2C peripherals.
156 (#) LSI (low-speed internal), 40 KHz low consumption RC used as IWDG and/or RTC
157 clock source.
158 (#) HSE (high-speed external), 4 to 32 MHz crystal oscillator used directly or
159 through the PLL as System clock source. Can be used also as RTC clock source.
160 (#) LSE (low-speed external), 32 KHz oscillator used as RTC clock source.
161 LSE can be used also to clock the USART peripherals.
162 (#) PLL (clocked by HSI or HSE), for System clock.
163 (#) CSS (Clock security system), once enabled and if a HSE clock failure occurs
164 (HSE used directly or through PLL as System clock source), the System clock
165 is automatically switched to HSI and an interrupt is generated if enabled.
166 The interrupt is linked to the Cortex-M4 NMI (Non-Maskable Interrupt)
167 exception vector.
168 (#) MCO (microcontroller clock output), used to output SYSCLK, HSI, HSE, LSI, LSE,
169 PLL clock on PA8 pin.
171 @endverbatim
172 * @{
176 * @brief Resets the RCC clock configuration to the default reset state.
177 * @note The default reset state of the clock configuration is given below:
178 * @note HSI ON and used as system clock source
179 * @note HSE and PLL OFF
180 * @note AHB, APB1 and APB2 prescalers set to 1.
181 * @note CSS and MCO OFF
182 * @note All interrupts disabled
183 * @note However, this function doesn't modify the configuration of the
184 * @note Peripheral clocks
185 * @note LSI, LSE and RTC clocks
186 * @param None
187 * @retval None
189 void RCC_DeInit(void)
191 /* Set HSION bit */
192 RCC->CR |= (uint32_t)0x00000001;
194 /* Reset SW[1:0], HPRE[3:0], PPRE[2:0] and MCOSEL[2:0] bits */
195 RCC->CFGR &= (uint32_t)0xF8FFC000;
197 /* Reset HSEON, CSSON and PLLON bits */
198 RCC->CR &= (uint32_t)0xFEF6FFFF;
200 /* Reset HSEBYP bit */
201 RCC->CR &= (uint32_t)0xFFFBFFFF;
203 /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */
204 RCC->CFGR &= (uint32_t)0xFF80FFFF;
206 /* Reset PREDIV1[3:0] and ADCPRE[13:4] bits */
207 RCC->CFGR2 &= (uint32_t)0xFFFFC000;
209 /* Reset USARTSW[1:0], I2CSW and TIMSW bits */
210 RCC->CFGR3 &= (uint32_t)0xF00ECCC;
212 /* Disable all interrupts */
213 RCC->CIR = 0x00000000;
217 * @brief Configures the External High Speed oscillator (HSE).
218 * @note After enabling the HSE (RCC_HSE_ON or RCC_HSE_Bypass), the application
219 * software should wait on HSERDY flag to be set indicating that HSE clock
220 * is stable and can be used to clock the PLL and/or system clock.
221 * @note HSE state can not be changed if it is used directly or through the
222 * PLL as system clock. In this case, you have to select another source
223 * of the system clock then change the HSE state (ex. disable it).
224 * @note The HSE is stopped by hardware when entering STOP and STANDBY modes.
225 * @note This function resets the CSSON bit, so if the Clock security system(CSS)
226 * was previously enabled you have to enable it again after calling this
227 * function.
228 * @param RCC_HSE: specifies the new state of the HSE.
229 * This parameter can be one of the following values:
230 * @arg RCC_HSE_OFF: turn OFF the HSE oscillator, HSERDY flag goes low after
231 * 6 HSE oscillator clock cycles.
232 * @arg RCC_HSE_ON: turn ON the HSE oscillator
233 * @arg RCC_HSE_Bypass: HSE oscillator bypassed with external clock
234 * @retval None
236 void RCC_HSEConfig(uint8_t RCC_HSE)
238 /* Check the parameters */
239 assert_param(IS_RCC_HSE(RCC_HSE));
241 /* Reset HSEON and HSEBYP bits before configuring the HSE ------------------*/
242 *(__IO uint8_t *) CR_BYTE2_ADDRESS = RCC_HSE_OFF;
244 /* Set the new HSE configuration -------------------------------------------*/
245 *(__IO uint8_t *) CR_BYTE2_ADDRESS = RCC_HSE;
250 * @brief Waits for HSE start-up.
251 * @note This function waits on HSERDY flag to be set and return SUCCESS if
252 * this flag is set, otherwise returns ERROR if the timeout is reached
253 * and this flag is not set. The timeout value is defined by the constant
254 * HSE_STARTUP_TIMEOUT in stm32f30x.h file. You can tailor it depending
255 * on the HSE crystal used in your application.
256 * @param None
257 * @retval An ErrorStatus enumeration value:
258 * - SUCCESS: HSE oscillator is stable and ready to use
259 * - ERROR: HSE oscillator not yet ready
261 ErrorStatus RCC_WaitForHSEStartUp(void)
263 __IO uint32_t StartUpCounter = 0;
264 ErrorStatus status = ERROR;
265 FlagStatus HSEStatus = RESET;
267 /* Wait till HSE is ready and if timeout is reached exit */
270 HSEStatus = RCC_GetFlagStatus(RCC_FLAG_HSERDY);
271 StartUpCounter++;
272 } while((StartUpCounter != HSE_STARTUP_TIMEOUT) && (HSEStatus == RESET));
274 if (RCC_GetFlagStatus(RCC_FLAG_HSERDY) != RESET)
276 status = SUCCESS;
278 else
280 status = ERROR;
282 return (status);
286 * @brief Adjusts the Internal High Speed oscillator (HSI) calibration value.
287 * @note The calibration is used to compensate for the variations in voltage
288 * and temperature that influence the frequency of the internal HSI RC.
289 * Refer to the Application Note AN3300 for more details on how to
290 * calibrate the HSI.
291 * @param HSICalibrationValue: specifies the HSI calibration trimming value.
292 * This parameter must be a number between 0 and 0x1F.
293 * @retval None
295 void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue)
297 uint32_t tmpreg = 0;
299 /* Check the parameters */
300 assert_param(IS_RCC_HSI_CALIBRATION_VALUE(HSICalibrationValue));
302 tmpreg = RCC->CR;
304 /* Clear HSITRIM[4:0] bits */
305 tmpreg &= ~RCC_CR_HSITRIM;
307 /* Set the HSITRIM[4:0] bits according to HSICalibrationValue value */
308 tmpreg |= (uint32_t)HSICalibrationValue << 3;
310 /* Store the new value */
311 RCC->CR = tmpreg;
315 * @brief Enables or disables the Internal High Speed oscillator (HSI).
316 * @note After enabling the HSI, the application software should wait on
317 * HSIRDY flag to be set indicating that HSI clock is stable and can
318 * be used to clock the PLL and/or system clock.
319 * @note HSI can not be stopped if it is used directly or through the PLL
320 * as system clock. In this case, you have to select another source
321 * of the system clock then stop the HSI.
322 * @note The HSI is stopped by hardware when entering STOP and STANDBY modes.
323 * @note When the HSI is stopped, HSIRDY flag goes low after 6 HSI oscillator
324 * clock cycles.
325 * @param NewState: new state of the HSI.
326 * This parameter can be: ENABLE or DISABLE.
327 * @retval None
329 void RCC_HSICmd(FunctionalState NewState)
331 /* Check the parameters */
332 assert_param(IS_FUNCTIONAL_STATE(NewState));
334 *(__IO uint32_t *) CR_HSION_BB = (uint32_t)NewState;
338 * @brief Configures the External Low Speed oscillator (LSE).
339 * @note As the LSE is in the Backup domain and write access is denied to this
340 * domain after reset, you have to enable write access using
341 * PWR_BackupAccessCmd(ENABLE) function before to configure the LSE
342 * (to be done once after reset).
343 * @note After enabling the LSE (RCC_LSE_ON or RCC_LSE_Bypass), the application
344 * software should wait on LSERDY flag to be set indicating that LSE clock
345 * is stable and can be used to clock the RTC.
346 * @param RCC_LSE: specifies the new state of the LSE.
347 * This parameter can be one of the following values:
348 * @arg RCC_LSE_OFF: turn OFF the LSE oscillator, LSERDY flag goes low after
349 * 6 LSE oscillator clock cycles.
350 * @arg RCC_LSE_ON: turn ON the LSE oscillator
351 * @arg RCC_LSE_Bypass: LSE oscillator bypassed with external clock
352 * @retval None
354 void RCC_LSEConfig(uint32_t RCC_LSE)
356 /* Check the parameters */
357 assert_param(IS_RCC_LSE(RCC_LSE));
359 /* Reset LSEON and LSEBYP bits before configuring the LSE ------------------*/
360 /* Reset LSEON bit */
361 RCC->BDCR &= ~(RCC_BDCR_LSEON);
363 /* Reset LSEBYP bit */
364 RCC->BDCR &= ~(RCC_BDCR_LSEBYP);
366 /* Configure LSE */
367 RCC->BDCR |= RCC_LSE;
371 * @brief Configures the External Low Speed oscillator (LSE) drive capability.
372 * @param RCC_LSEDrive: specifies the new state of the LSE drive capability.
373 * This parameter can be one of the following values:
374 * @arg RCC_LSEDrive_Low: LSE oscillator low drive capability.
375 * @arg RCC_LSEDrive_MediumLow: LSE oscillator medium low drive capability.
376 * @arg RCC_LSEDrive_MediumHigh: LSE oscillator medium high drive capability.
377 * @arg RCC_LSEDrive_High: LSE oscillator high drive capability.
378 * @retval None
380 void RCC_LSEDriveConfig(uint32_t RCC_LSEDrive)
382 /* Check the parameters */
383 assert_param(IS_RCC_LSE_DRIVE(RCC_LSEDrive));
385 /* Clear LSEDRV[1:0] bits */
386 RCC->BDCR &= ~(RCC_BDCR_LSEDRV);
388 /* Set the LSE Drive */
389 RCC->BDCR |= RCC_LSEDrive;
393 * @brief Enables or disables the Internal Low Speed oscillator (LSI).
394 * @note After enabling the LSI, the application software should wait on
395 * LSIRDY flag to be set indicating that LSI clock is stable and can
396 * be used to clock the IWDG and/or the RTC.
397 * @note LSI can not be disabled if the IWDG is running.
398 * @note When the LSI is stopped, LSIRDY flag goes low after 6 LSI oscillator
399 * clock cycles.
400 * @param NewState: new state of the LSI.
401 * This parameter can be: ENABLE or DISABLE.
402 * @retval None
404 void RCC_LSICmd(FunctionalState NewState)
406 /* Check the parameters */
407 assert_param(IS_FUNCTIONAL_STATE(NewState));
409 *(__IO uint32_t *) CSR_LSION_BB = (uint32_t)NewState;
413 * @brief Configures the PLL clock source and multiplication factor.
414 * @note This function must be used only when the PLL is disabled.
415 * @note The minimum input clock frequency for PLL is 2 MHz (when using HSE as
416 * PLL source).
417 * @param RCC_PLLSource: specifies the PLL entry clock source.
418 * This parameter can be one of the following values:
419 * @arg RCC_PLLSource_HSI_Div2: HSI oscillator clock divided by 2 selected as
420 * PLL clock entry
421 * @arg RCC_PLLSource_PREDIV1: PREDIV1 clock selected as PLL clock source
422 * @param RCC_PLLMul: specifies the PLL multiplication factor, which drive the PLLVCO clock
423 * This parameter can be RCC_PLLMul_x where x:[2,16]
425 * @retval None
427 void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul)
429 /* Check the parameters */
430 assert_param(IS_RCC_PLL_SOURCE(RCC_PLLSource));
431 assert_param(IS_RCC_PLL_MUL(RCC_PLLMul));
433 /* Clear PLL Source [16] and Multiplier [21:18] bits */
434 RCC->CFGR &= ~(RCC_CFGR_PLLMULL | RCC_CFGR_PLLSRC);
436 /* Set the PLL Source and Multiplier */
437 RCC->CFGR |= (uint32_t)(RCC_PLLSource | RCC_PLLMul);
441 * @brief Enables or disables the PLL.
442 * @note After enabling the PLL, the application software should wait on
443 * PLLRDY flag to be set indicating that PLL clock is stable and can
444 * be used as system clock source.
445 * @note The PLL can not be disabled if it is used as system clock source
446 * @note The PLL is disabled by hardware when entering STOP and STANDBY modes.
447 * @param NewState: new state of the PLL.
448 * This parameter can be: ENABLE or DISABLE.
449 * @retval None
451 void RCC_PLLCmd(FunctionalState NewState)
453 /* Check the parameters */
454 assert_param(IS_FUNCTIONAL_STATE(NewState));
456 *(__IO uint32_t *) CR_PLLON_BB = (uint32_t)NewState;
460 * @brief Configures the PREDIV1 division factor.
461 * @note This function must be used only when the PLL is disabled.
462 * @param RCC_PREDIV1_Div: specifies the PREDIV1 clock division factor.
463 * This parameter can be RCC_PREDIV1_Divx where x:[1,16]
464 * @retval None
466 void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Div)
468 uint32_t tmpreg = 0;
470 /* Check the parameters */
471 assert_param(IS_RCC_PREDIV1(RCC_PREDIV1_Div));
473 tmpreg = RCC->CFGR2;
474 /* Clear PREDIV1[3:0] bits */
475 tmpreg &= ~(RCC_CFGR2_PREDIV1);
477 /* Set the PREDIV1 division factor */
478 tmpreg |= RCC_PREDIV1_Div;
480 /* Store the new value */
481 RCC->CFGR2 = tmpreg;
485 * @brief Enables or disables the Clock Security System.
486 * @note If a failure is detected on the HSE oscillator clock, this oscillator
487 * is automatically disabled and an interrupt is generated to inform the
488 * software about the failure (Clock Security System Interrupt, CSSI),
489 * allowing the MCU to perform rescue operations. The CSSI is linked to
490 * the Cortex-M4 NMI (Non-Maskable Interrupt) exception vector.
491 * @param NewState: new state of the Clock Security System.
492 * This parameter can be: ENABLE or DISABLE.
493 * @retval None
495 void RCC_ClockSecuritySystemCmd(FunctionalState NewState)
497 /* Check the parameters */
498 assert_param(IS_FUNCTIONAL_STATE(NewState));
500 *(__IO uint32_t *) CR_CSSON_BB = (uint32_t)NewState;
503 #ifdef STM32F303xC
505 * @brief Selects the clock source to output on MCO pin (PA8).
506 * @note PA8 should be configured in alternate function mode.
507 * @param RCC_MCOSource: specifies the clock source to output.
508 * This parameter can be one of the following values:
509 * @arg RCC_MCOSource_NoClock: No clock selected.
510 * @arg RCC_MCOSource_HSI14: HSI14 oscillator clock selected.
511 * @arg RCC_MCOSource_LSI: LSI oscillator clock selected.
512 * @arg RCC_MCOSource_LSE: LSE oscillator clock selected.
513 * @arg RCC_MCOSource_SYSCLK: System clock selected.
514 * @arg RCC_MCOSource_HSI: HSI oscillator clock selected.
515 * @arg RCC_MCOSource_HSE: HSE oscillator clock selected.
516 * @arg RCC_MCOSource_PLLCLK_Div2: PLL clock divided by 2 selected.
517 * @arg RCC_MCOSource_PLLCLK: PLL clock selected.
518 * @arg RCC_MCOSource_HSI48: HSI48 clock selected.
519 * @retval None
521 void RCC_MCOConfig(uint8_t RCC_MCOSource)
523 uint32_t tmpreg = 0;
525 /* Check the parameters */
526 assert_param(IS_RCC_MCO_SOURCE(RCC_MCOSource));
528 /* Get CFGR value */
529 tmpreg = RCC->CFGR;
530 /* Clear MCO[3:0] bits */
531 tmpreg &= ~(RCC_CFGR_MCO | RCC_CFGR_PLLNODIV);
532 /* Set the RCC_MCOSource */
533 tmpreg |= RCC_MCOSource<<24;
534 /* Store the new value */
535 RCC->CFGR = tmpreg;
537 #else
540 * @brief Selects the clock source to output on MCO pin (PA8) and the corresponding
541 * prescsaler.
542 * @note PA8 should be configured in alternate function mode.
543 * @param RCC_MCOSource: specifies the clock source to output.
544 * This parameter can be one of the following values:
545 * @arg RCC_MCOSource_NoClock: No clock selected.
546 * @arg RCC_MCOSource_HSI14: HSI14 oscillator clock selected.
547 * @arg RCC_MCOSource_LSI: LSI oscillator clock selected.
548 * @arg RCC_MCOSource_LSE: LSE oscillator clock selected.
549 * @arg RCC_MCOSource_SYSCLK: System clock selected.
550 * @arg RCC_MCOSource_HSI: HSI oscillator clock selected.
551 * @arg RCC_MCOSource_HSE: HSE oscillator clock selected.
552 * @arg RCC_MCOSource_PLLCLK_Div2: PLL clock divided by 2 selected.
553 * @arg RCC_MCOSource_PLLCLK: PLL clock selected.
554 * @arg RCC_MCOSource_HSI48: HSI48 clock selected.
555 * @param RCC_MCOPrescaler: specifies the prescaler on MCO pin.
556 * This parameter can be one of the following values:
557 * @arg RCC_MCOPrescaler_1: MCO clock is divided by 1.
558 * @arg RCC_MCOPrescaler_2: MCO clock is divided by 2.
559 * @arg RCC_MCOPrescaler_4: MCO clock is divided by 4.
560 * @arg RCC_MCOPrescaler_8: MCO clock is divided by 8.
561 * @arg RCC_MCOPrescaler_16: MCO clock is divided by 16.
562 * @arg RCC_MCOPrescaler_32: MCO clock is divided by 32.
563 * @arg RCC_MCOPrescaler_64: MCO clock is divided by 64.
564 * @arg RCC_MCOPrescaler_128: MCO clock is divided by 128.
565 * @retval None
567 void RCC_MCOConfig(uint8_t RCC_MCOSource, uint32_t RCC_MCOPrescaler)
569 uint32_t tmpreg = 0;
571 /* Check the parameters */
572 assert_param(IS_RCC_MCO_SOURCE(RCC_MCOSource));
573 assert_param(IS_RCC_MCO_PRESCALER(RCC_MCOPrescaler));
575 /* Get CFGR value */
576 tmpreg = RCC->CFGR;
577 /* Clear MCOPRE[2:0] bits */
578 tmpreg &= ~(RCC_CFGR_MCO_PRE | RCC_CFGR_MCO | RCC_CFGR_PLLNODIV);
579 /* Set the RCC_MCOSource and RCC_MCOPrescaler */
580 tmpreg |= (RCC_MCOPrescaler | RCC_MCOSource<<24);
581 /* Store the new value */
582 RCC->CFGR = tmpreg;
584 #endif /* STM32F303xC */
587 * @}
590 /** @defgroup RCC_Group2 System AHB, APB1 and APB2 busses clocks configuration functions
591 * @brief System, AHB and APB busses clocks configuration functions
593 @verbatim
594 ===============================================================================
595 ##### System, AHB, APB1 and APB2 busses clocks configuration functions #####
596 ===============================================================================
597 [..] This section provide functions allowing to configure the System, AHB, APB1 and
598 APB2 busses clocks.
599 (#) Several clock sources can be used to drive the System clock (SYSCLK): HSI,
600 HSE and PLL.
601 The AHB clock (HCLK) is derived from System clock through configurable prescaler
602 and used to clock the CPU, memory and peripherals mapped on AHB bus (DMA and GPIO).
603 APB1 (PCLK1) and APB2 (PCLK2) clocks are derived from AHB clock through
604 configurable prescalers and used to clock the peripherals mapped on these busses.
605 You can use "RCC_GetClocksFreq()" function to retrieve the frequencies of these clocks.
607 (#) The maximum frequency of the SYSCLK, HCLK, PCLK1 and PCLK2 is 72 MHz.
608 Depending on the maximum frequency, the FLASH wait states (WS) should be
609 adapted accordingly:
610 +---------------------------------+
611 | Wait states | HCLK clock |
612 | (Latency) | frequency (MHz) |
613 |-------------- |-----------------|
614 |0WS(1CPU cycle)| 0 < HCLK <= 24 |
615 |---------------|-----------------|
616 |1WS(2CPU cycle)|24 < HCLK <=48 |
617 |---------------|-----------------|
618 |2WS(3CPU cycle)|48 < HCLK <= 72 |
619 +---------------------------------+
621 (#) After reset, the System clock source is the HSI (8 MHz) with 0 WS and
622 prefetch is disabled.
623 [..]
624 (@) All the peripheral clocks are derived from the System clock (SYSCLK)
625 except:
626 (+@) The FLASH program/erase clock which is always HSI 8MHz clock.
627 (+@) The USB 48 MHz clock which is derived from the PLL VCO clock.
628 (+@) The USART clock which can be derived as well from HSI 8MHz, LSI or LSE.
629 (+@) The I2C clock which can be derived as well from HSI 8MHz clock.
630 (+@) The ADC clock which is derived from PLL output.
631 (+@) The RTC clock which is derived from the LSE, LSI or 1 MHz HSE_RTC
632 (HSE divided by a programmable prescaler). The System clock (SYSCLK)
633 frequency must be higher or equal to the RTC clock frequency.
634 (+@) IWDG clock which is always the LSI clock.
635 [..] It is recommended to use the following software sequences to tune the number
636 of wait states needed to access the Flash memory with the CPU frequency (HCLK).
637 (+) Increasing the CPU frequency
638 (++) Program the Flash Prefetch buffer, using "FLASH_PrefetchBufferCmd(ENABLE)"
639 function
640 (++) Check that Flash Prefetch buffer activation is taken into account by
641 reading FLASH_ACR using the FLASH_GetPrefetchBufferStatus() function
642 (++) Program Flash WS to 1 or 2, using "FLASH_SetLatency()" function
643 (++) Check that the new number of WS is taken into account by reading FLASH_ACR
644 (++) Modify the CPU clock source, using "RCC_SYSCLKConfig()" function
645 (++) If needed, modify the CPU clock prescaler by using "RCC_HCLKConfig()" function
646 (++) Check that the new CPU clock source is taken into account by reading
647 the clock source status, using "RCC_GetSYSCLKSource()" function
648 (+) Decreasing the CPU frequency
649 (++) Modify the CPU clock source, using "RCC_SYSCLKConfig()" function
650 (++) If needed, modify the CPU clock prescaler by using "RCC_HCLKConfig()" function
651 (++) Check that the new CPU clock source is taken into account by reading
652 the clock source status, using "RCC_GetSYSCLKSource()" function
653 (++) Program the new number of WS, using "FLASH_SetLatency()" function
654 (++) Check that the new number of WS is taken into account by reading FLASH_ACR
655 (++) Disable the Flash Prefetch buffer using "FLASH_PrefetchBufferCmd(DISABLE)"
656 function
657 (++) Check that Flash Prefetch buffer deactivation is taken into account by reading FLASH_ACR
658 using the FLASH_GetPrefetchBufferStatus() function.
660 @endverbatim
661 * @{
665 * @brief Configures the system clock (SYSCLK).
666 * @note The HSI is used (enabled by hardware) as system clock source after
667 * startup from Reset, wake-up from STOP and STANDBY mode, or in case
668 * of failure of the HSE used directly or indirectly as system clock
669 * (if the Clock Security System CSS is enabled).
670 * @note A switch from one clock source to another occurs only if the target
671 * clock source is ready (clock stable after startup delay or PLL locked).
672 * If a clock source which is not yet ready is selected, the switch will
673 * occur when the clock source will be ready.
674 * You can use RCC_GetSYSCLKSource() function to know which clock is
675 * currently used as system clock source.
676 * @param RCC_SYSCLKSource: specifies the clock source used as system clock source
677 * This parameter can be one of the following values:
678 * @arg RCC_SYSCLKSource_HSI: HSI selected as system clock source
679 * @arg RCC_SYSCLKSource_HSE: HSE selected as system clock source
680 * @arg RCC_SYSCLKSource_PLLCLK: PLL selected as system clock source
681 * @retval None
683 void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource)
685 uint32_t tmpreg = 0;
687 /* Check the parameters */
688 assert_param(IS_RCC_SYSCLK_SOURCE(RCC_SYSCLKSource));
690 tmpreg = RCC->CFGR;
692 /* Clear SW[1:0] bits */
693 tmpreg &= ~RCC_CFGR_SW;
695 /* Set SW[1:0] bits according to RCC_SYSCLKSource value */
696 tmpreg |= RCC_SYSCLKSource;
698 /* Store the new value */
699 RCC->CFGR = tmpreg;
703 * @brief Returns the clock source used as system clock.
704 * @param None
705 * @retval The clock source used as system clock. The returned value can be one
706 * of the following values:
707 * - 0x00: HSI used as system clock
708 * - 0x04: HSE used as system clock
709 * - 0x08: PLL used as system clock
711 uint8_t RCC_GetSYSCLKSource(void)
713 return ((uint8_t)(RCC->CFGR & RCC_CFGR_SWS));
717 * @brief Configures the AHB clock (HCLK).
718 * @note Depending on the device voltage range, the software has to set correctly
719 * these bits to ensure that the system frequency does not exceed the
720 * maximum allowed frequency (for more details refer to section above
721 * "CPU, AHB and APB busses clocks configuration functions").
722 * @param RCC_SYSCLK: defines the AHB clock divider. This clock is derived from
723 * the system clock (SYSCLK).
724 * This parameter can be one of the following values:
725 * @arg RCC_SYSCLK_Div1: AHB clock = SYSCLK
726 * @arg RCC_SYSCLK_Div2: AHB clock = SYSCLK/2
727 * @arg RCC_SYSCLK_Div4: AHB clock = SYSCLK/4
728 * @arg RCC_SYSCLK_Div8: AHB clock = SYSCLK/8
729 * @arg RCC_SYSCLK_Div16: AHB clock = SYSCLK/16
730 * @arg RCC_SYSCLK_Div64: AHB clock = SYSCLK/64
731 * @arg RCC_SYSCLK_Div128: AHB clock = SYSCLK/128
732 * @arg RCC_SYSCLK_Div256: AHB clock = SYSCLK/256
733 * @arg RCC_SYSCLK_Div512: AHB clock = SYSCLK/512
734 * @retval None
736 void RCC_HCLKConfig(uint32_t RCC_SYSCLK)
738 uint32_t tmpreg = 0;
740 /* Check the parameters */
741 assert_param(IS_RCC_HCLK(RCC_SYSCLK));
743 tmpreg = RCC->CFGR;
745 /* Clear HPRE[3:0] bits */
746 tmpreg &= ~RCC_CFGR_HPRE;
748 /* Set HPRE[3:0] bits according to RCC_SYSCLK value */
749 tmpreg |= RCC_SYSCLK;
751 /* Store the new value */
752 RCC->CFGR = tmpreg;
756 * @brief Configures the Low Speed APB clock (PCLK1).
757 * @param RCC_HCLK: defines the APB1 clock divider. This clock is derived from
758 * the AHB clock (HCLK).
759 * This parameter can be one of the following values:
760 * @arg RCC_HCLK_Div1: APB1 clock = HCLK
761 * @arg RCC_HCLK_Div2: APB1 clock = HCLK/2
762 * @arg RCC_HCLK_Div4: APB1 clock = HCLK/4
763 * @arg RCC_HCLK_Div8: APB1 clock = HCLK/8
764 * @arg RCC_HCLK_Div16: APB1 clock = HCLK/16
765 * @retval None
767 void RCC_PCLK1Config(uint32_t RCC_HCLK)
769 uint32_t tmpreg = 0;
771 /* Check the parameters */
772 assert_param(IS_RCC_PCLK(RCC_HCLK));
774 tmpreg = RCC->CFGR;
775 /* Clear PPRE1[2:0] bits */
776 tmpreg &= ~RCC_CFGR_PPRE1;
778 /* Set PPRE1[2:0] bits according to RCC_HCLK value */
779 tmpreg |= RCC_HCLK;
781 /* Store the new value */
782 RCC->CFGR = tmpreg;
786 * @brief Configures the High Speed APB clock (PCLK2).
787 * @param RCC_HCLK: defines the APB2 clock divider. This clock is derived from
788 * the AHB clock (HCLK).
789 * This parameter can be one of the following values:
790 * @arg RCC_HCLK_Div1: APB2 clock = HCLK
791 * @arg RCC_HCLK_Div2: APB2 clock = HCLK/2
792 * @arg RCC_HCLK_Div4: APB2 clock = HCLK/4
793 * @arg RCC_HCLK_Div8: APB2 clock = HCLK/8
794 * @arg RCC_HCLK_Div16: APB2 clock = HCLK/16
795 * @retval None
797 void RCC_PCLK2Config(uint32_t RCC_HCLK)
799 uint32_t tmpreg = 0;
801 /* Check the parameters */
802 assert_param(IS_RCC_PCLK(RCC_HCLK));
804 tmpreg = RCC->CFGR;
805 /* Clear PPRE2[2:0] bits */
806 tmpreg &= ~RCC_CFGR_PPRE2;
807 /* Set PPRE2[2:0] bits according to RCC_HCLK value */
808 tmpreg |= RCC_HCLK << 3;
809 /* Store the new value */
810 RCC->CFGR = tmpreg;
814 * @brief Returns the frequencies of the System, AHB, APB2 and APB1 busses clocks.
816 * @note This function returns the frequencies of :
817 * System, AHB, APB2 and APB1 busses clocks, ADC1/2/3/4 clocks,
818 * USART1/2/3/4/5 clocks, I2C1/2 clocks and TIM1/8 Clocks.
820 * @note The frequency returned by this function is not the real frequency
821 * in the chip. It is calculated based on the predefined constant and
822 * the source selected by RCC_SYSCLKConfig().
824 * @note If SYSCLK source is HSI, function returns constant HSI_VALUE(*)
826 * @note If SYSCLK source is HSE, function returns constant HSE_VALUE(**)
828 * @note If SYSCLK source is PLL, function returns constant HSE_VALUE(**)
829 * or HSI_VALUE(*) multiplied by the PLL factors.
831 * @note (*) HSI_VALUE is a constant defined in stm32f30x.h file (default value
832 * 8 MHz) but the real value may vary depending on the variations
833 * in voltage and temperature, refer to RCC_AdjustHSICalibrationValue().
835 * @note (**) HSE_VALUE is a constant defined in stm32f30x.h file (default value
836 * 8 MHz), user has to ensure that HSE_VALUE is same as the real
837 * frequency of the crystal used. Otherwise, this function may
838 * return wrong result.
840 * @note The result of this function could be not correct when using fractional
841 * value for HSE crystal.
843 * @param RCC_Clocks: pointer to a RCC_ClocksTypeDef structure which will hold
844 * the clocks frequencies.
846 * @note This function can be used by the user application to compute the
847 * baudrate for the communication peripherals or configure other parameters.
848 * @note Each time SYSCLK, HCLK, PCLK1 and/or PCLK2 clock changes, this function
849 * must be called to update the structure's field. Otherwise, any
850 * configuration based on this function will be incorrect.
852 * @retval None
854 void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks)
856 uint32_t tmp = 0, pllmull = 0, pllsource = 0, prediv1factor = 0, presc = 0, pllclk = 0;
857 uint32_t apb2presc = 0, ahbpresc = 0;
859 /* Get SYSCLK source -------------------------------------------------------*/
860 tmp = RCC->CFGR & RCC_CFGR_SWS;
862 switch (tmp)
864 case 0x00: /* HSI used as system clock */
865 RCC_Clocks->SYSCLK_Frequency = HSI_VALUE;
866 break;
867 case 0x04: /* HSE used as system clock */
868 RCC_Clocks->SYSCLK_Frequency = HSE_VALUE;
869 break;
870 case 0x08: /* PLL used as system clock */
871 /* Get PLL clock source and multiplication factor ----------------------*/
872 pllmull = RCC->CFGR & RCC_CFGR_PLLMULL;
873 pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
874 pllmull = ( pllmull >> 18) + 2;
876 if (pllsource == 0x00)
878 /* HSI oscillator clock divided by 2 selected as PLL clock entry */
879 pllclk = (HSI_VALUE >> 1) * pllmull;
881 else
883 prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1;
884 /* HSE oscillator clock selected as PREDIV1 clock entry */
885 pllclk = (HSE_VALUE / prediv1factor) * pllmull;
887 RCC_Clocks->SYSCLK_Frequency = pllclk;
888 break;
889 default: /* HSI used as system clock */
890 RCC_Clocks->SYSCLK_Frequency = HSI_VALUE;
891 break;
893 /* Compute HCLK, PCLK clocks frequencies -----------------------------------*/
894 /* Get HCLK prescaler */
895 tmp = RCC->CFGR & RCC_CFGR_HPRE;
896 tmp = tmp >> 4;
897 ahbpresc = APBAHBPrescTable[tmp];
898 /* HCLK clock frequency */
899 RCC_Clocks->HCLK_Frequency = RCC_Clocks->SYSCLK_Frequency >> ahbpresc;
901 /* Get PCLK1 prescaler */
902 tmp = RCC->CFGR & RCC_CFGR_PPRE1;
903 tmp = tmp >> 8;
904 presc = APBAHBPrescTable[tmp];
905 /* PCLK1 clock frequency */
906 RCC_Clocks->PCLK1_Frequency = RCC_Clocks->HCLK_Frequency >> presc;
908 /* Get PCLK2 prescaler */
909 tmp = RCC->CFGR & RCC_CFGR_PPRE2;
910 tmp = tmp >> 11;
911 apb2presc = APBAHBPrescTable[tmp];
912 /* PCLK2 clock frequency */
913 RCC_Clocks->PCLK2_Frequency = RCC_Clocks->HCLK_Frequency >> apb2presc;
915 /* Get ADC12CLK prescaler */
916 tmp = RCC->CFGR2 & RCC_CFGR2_ADCPRE12;
917 tmp = tmp >> 4;
918 presc = ADCPrescTable[tmp & 0x0F];
919 if (((tmp & 0x10) != 0) && (presc != 0))
921 /* ADC12CLK clock frequency is derived from PLL clock */
922 RCC_Clocks->ADC12CLK_Frequency = pllclk / presc;
924 else
926 /* ADC12CLK clock frequency is AHB clock */
927 RCC_Clocks->ADC12CLK_Frequency = RCC_Clocks->SYSCLK_Frequency;
930 /* Get ADC34CLK prescaler */
931 tmp = RCC->CFGR2 & RCC_CFGR2_ADCPRE34;
932 tmp = tmp >> 9;
933 presc = ADCPrescTable[tmp & 0x0F];
934 if (((tmp & 0x10) != 0) && (presc != 0))
936 /* ADC34CLK clock frequency is derived from PLL clock */
937 RCC_Clocks->ADC34CLK_Frequency = pllclk / presc;
939 else
941 /* ADC34CLK clock frequency is AHB clock */
942 RCC_Clocks->ADC34CLK_Frequency = RCC_Clocks->SYSCLK_Frequency;
945 /* I2C1CLK clock frequency */
946 if((RCC->CFGR3 & RCC_CFGR3_I2C1SW) != RCC_CFGR3_I2C1SW)
948 /* I2C1 Clock is HSI Osc. */
949 RCC_Clocks->I2C1CLK_Frequency = HSI_VALUE;
951 else
953 /* I2C1 Clock is System Clock */
954 RCC_Clocks->I2C1CLK_Frequency = RCC_Clocks->SYSCLK_Frequency;
957 /* I2C2CLK clock frequency */
958 if((RCC->CFGR3 & RCC_CFGR3_I2C2SW) != RCC_CFGR3_I2C2SW)
960 /* I2C2 Clock is HSI Osc. */
961 RCC_Clocks->I2C2CLK_Frequency = HSI_VALUE;
963 else
965 /* I2C2 Clock is System Clock */
966 RCC_Clocks->I2C2CLK_Frequency = RCC_Clocks->SYSCLK_Frequency;
969 /* I2C3CLK clock frequency */
970 if((RCC->CFGR3 & RCC_CFGR3_I2C3SW) != RCC_CFGR3_I2C3SW)
972 /* I2C3 Clock is HSI Osc. */
973 RCC_Clocks->I2C3CLK_Frequency = HSI_VALUE;
975 else
977 /* I2C3 Clock is System Clock */
978 RCC_Clocks->I2C3CLK_Frequency = RCC_Clocks->SYSCLK_Frequency;
981 /* TIM1CLK clock frequency */
982 if(((RCC->CFGR3 & RCC_CFGR3_TIM1SW) == RCC_CFGR3_TIM1SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \
983 && (apb2presc == ahbpresc))
985 /* TIM1 Clock is 2 * pllclk */
986 RCC_Clocks->TIM1CLK_Frequency = pllclk * 2;
988 else
990 /* TIM1 Clock is APB2 clock. */
991 RCC_Clocks->TIM1CLK_Frequency = RCC_Clocks->PCLK2_Frequency;
994 /* TIM1CLK clock frequency */
995 if(((RCC->CFGR3 & RCC_CFGR3_HRTIM1SW) == RCC_CFGR3_HRTIM1SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \
996 && (apb2presc == ahbpresc))
998 /* HRTIM1 Clock is 2 * pllclk */
999 RCC_Clocks->HRTIM1CLK_Frequency = pllclk * 2;
1001 else
1003 /* HRTIM1 Clock is APB2 clock. */
1004 RCC_Clocks->HRTIM1CLK_Frequency = RCC_Clocks->PCLK2_Frequency;
1007 /* TIM8CLK clock frequency */
1008 if(((RCC->CFGR3 & RCC_CFGR3_TIM8SW) == RCC_CFGR3_TIM8SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \
1009 && (apb2presc == ahbpresc))
1011 /* TIM8 Clock is 2 * pllclk */
1012 RCC_Clocks->TIM8CLK_Frequency = pllclk * 2;
1014 else
1016 /* TIM8 Clock is APB2 clock. */
1017 RCC_Clocks->TIM8CLK_Frequency = RCC_Clocks->PCLK2_Frequency;
1020 /* TIM15CLK clock frequency */
1021 if(((RCC->CFGR3 & RCC_CFGR3_TIM15SW) == RCC_CFGR3_TIM15SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \
1022 && (apb2presc == ahbpresc))
1024 /* TIM15 Clock is 2 * pllclk */
1025 RCC_Clocks->TIM15CLK_Frequency = pllclk * 2;
1027 else
1029 /* TIM15 Clock is APB2 clock. */
1030 RCC_Clocks->TIM15CLK_Frequency = RCC_Clocks->PCLK2_Frequency;
1033 /* TIM16CLK clock frequency */
1034 if(((RCC->CFGR3 & RCC_CFGR3_TIM16SW) == RCC_CFGR3_TIM16SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \
1035 && (apb2presc == ahbpresc))
1037 /* TIM16 Clock is 2 * pllclk */
1038 RCC_Clocks->TIM16CLK_Frequency = pllclk * 2;
1040 else
1042 /* TIM16 Clock is APB2 clock. */
1043 RCC_Clocks->TIM16CLK_Frequency = RCC_Clocks->PCLK2_Frequency;
1046 /* TIM17CLK clock frequency */
1047 if(((RCC->CFGR3 & RCC_CFGR3_TIM17SW) == RCC_CFGR3_TIM17SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \
1048 && (apb2presc == ahbpresc))
1050 /* TIM17 Clock is 2 * pllclk */
1051 RCC_Clocks->TIM17CLK_Frequency = pllclk * 2;
1053 else
1055 /* TIM17 Clock is APB2 clock. */
1056 RCC_Clocks->TIM16CLK_Frequency = RCC_Clocks->PCLK2_Frequency;
1059 /* USART1CLK clock frequency */
1060 if((RCC->CFGR3 & RCC_CFGR3_USART1SW) == 0x0)
1062 #if defined(STM32F303x8) || defined(STM32F334x8) || defined(STM32F301x8) || defined(STM32F302x8)
1063 /* USART1 Clock is PCLK1 instead of PCLK2 (limitation described in the
1064 STM32F302/01/34 x4/x6/x8 respective erratasheets) */
1065 RCC_Clocks->USART1CLK_Frequency = RCC_Clocks->PCLK1_Frequency;
1066 #else
1067 /* USART Clock is PCLK2 */
1068 RCC_Clocks->USART1CLK_Frequency = RCC_Clocks->PCLK2_Frequency;
1069 #endif
1071 else if((RCC->CFGR3 & RCC_CFGR3_USART1SW) == RCC_CFGR3_USART1SW_0)
1073 /* USART Clock is System Clock */
1074 RCC_Clocks->USART1CLK_Frequency = RCC_Clocks->SYSCLK_Frequency;
1076 else if((RCC->CFGR3 & RCC_CFGR3_USART1SW) == RCC_CFGR3_USART1SW_1)
1078 /* USART Clock is LSE Osc. */
1079 RCC_Clocks->USART1CLK_Frequency = LSE_VALUE;
1081 else if((RCC->CFGR3 & RCC_CFGR3_USART1SW) == RCC_CFGR3_USART1SW)
1083 /* USART Clock is HSI Osc. */
1084 RCC_Clocks->USART1CLK_Frequency = HSI_VALUE;
1087 /* USART2CLK clock frequency */
1088 if((RCC->CFGR3 & RCC_CFGR3_USART2SW) == 0x0)
1090 /* USART Clock is PCLK */
1091 RCC_Clocks->USART2CLK_Frequency = RCC_Clocks->PCLK1_Frequency;
1093 else if((RCC->CFGR3 & RCC_CFGR3_USART2SW) == RCC_CFGR3_USART2SW_0)
1095 /* USART Clock is System Clock */
1096 RCC_Clocks->USART2CLK_Frequency = RCC_Clocks->SYSCLK_Frequency;
1098 else if((RCC->CFGR3 & RCC_CFGR3_USART2SW) == RCC_CFGR3_USART2SW_1)
1100 /* USART Clock is LSE Osc. */
1101 RCC_Clocks->USART2CLK_Frequency = LSE_VALUE;
1103 else if((RCC->CFGR3 & RCC_CFGR3_USART2SW) == RCC_CFGR3_USART2SW)
1105 /* USART Clock is HSI Osc. */
1106 RCC_Clocks->USART2CLK_Frequency = HSI_VALUE;
1109 /* USART3CLK clock frequency */
1110 if((RCC->CFGR3 & RCC_CFGR3_USART3SW) == 0x0)
1112 /* USART Clock is PCLK */
1113 RCC_Clocks->USART3CLK_Frequency = RCC_Clocks->PCLK1_Frequency;
1115 else if((RCC->CFGR3 & RCC_CFGR3_USART3SW) == RCC_CFGR3_USART3SW_0)
1117 /* USART Clock is System Clock */
1118 RCC_Clocks->USART3CLK_Frequency = RCC_Clocks->SYSCLK_Frequency;
1120 else if((RCC->CFGR3 & RCC_CFGR3_USART3SW) == RCC_CFGR3_USART3SW_1)
1122 /* USART Clock is LSE Osc. */
1123 RCC_Clocks->USART3CLK_Frequency = LSE_VALUE;
1125 else if((RCC->CFGR3 & RCC_CFGR3_USART3SW) == RCC_CFGR3_USART3SW)
1127 /* USART Clock is HSI Osc. */
1128 RCC_Clocks->USART3CLK_Frequency = HSI_VALUE;
1131 /* UART4CLK clock frequency */
1132 if((RCC->CFGR3 & RCC_CFGR3_UART4SW) == 0x0)
1134 /* USART Clock is PCLK */
1135 RCC_Clocks->UART4CLK_Frequency = RCC_Clocks->PCLK1_Frequency;
1137 else if((RCC->CFGR3 & RCC_CFGR3_UART4SW) == RCC_CFGR3_UART4SW_0)
1139 /* USART Clock is System Clock */
1140 RCC_Clocks->UART4CLK_Frequency = RCC_Clocks->SYSCLK_Frequency;
1142 else if((RCC->CFGR3 & RCC_CFGR3_UART4SW) == RCC_CFGR3_UART4SW_1)
1144 /* USART Clock is LSE Osc. */
1145 RCC_Clocks->UART4CLK_Frequency = LSE_VALUE;
1147 else if((RCC->CFGR3 & RCC_CFGR3_UART4SW) == RCC_CFGR3_UART4SW)
1149 /* USART Clock is HSI Osc. */
1150 RCC_Clocks->UART4CLK_Frequency = HSI_VALUE;
1153 /* UART5CLK clock frequency */
1154 if((RCC->CFGR3 & RCC_CFGR3_UART5SW) == 0x0)
1156 /* USART Clock is PCLK */
1157 RCC_Clocks->UART5CLK_Frequency = RCC_Clocks->PCLK1_Frequency;
1159 else if((RCC->CFGR3 & RCC_CFGR3_UART5SW) == RCC_CFGR3_UART5SW_0)
1161 /* USART Clock is System Clock */
1162 RCC_Clocks->UART5CLK_Frequency = RCC_Clocks->SYSCLK_Frequency;
1164 else if((RCC->CFGR3 & RCC_CFGR3_UART5SW) == RCC_CFGR3_UART5SW_1)
1166 /* USART Clock is LSE Osc. */
1167 RCC_Clocks->UART5CLK_Frequency = LSE_VALUE;
1169 else if((RCC->CFGR3 & RCC_CFGR3_UART5SW) == RCC_CFGR3_UART5SW)
1171 /* USART Clock is HSI Osc. */
1172 RCC_Clocks->UART5CLK_Frequency = HSI_VALUE;
1177 * @}
1180 /** @defgroup RCC_Group3 Peripheral clocks configuration functions
1181 * @brief Peripheral clocks configuration functions
1183 @verbatim
1184 ===============================================================================
1185 ##### Peripheral clocks configuration functions #####
1186 ===============================================================================
1187 [..] This section provide functions allowing to configure the Peripheral clocks.
1188 (#) The RTC clock which is derived from the LSE, LSI or HSE_Div32
1189 (HSE divided by 32).
1190 (#) After restart from Reset or wakeup from STANDBY, all peripherals are
1191 off except internal SRAM, Flash and SWD. Before to start using
1192 a peripheral you have to enable its interface clock. You can do this
1193 using RCC_AHBPeriphClockCmd(), RCC_APB2PeriphClockCmd()
1194 and RCC_APB1PeriphClockCmd() functions.
1195 (#) To reset the peripherals configuration (to the default state after
1196 device reset) you can use RCC_AHBPeriphResetCmd(), RCC_APB2PeriphResetCmd()
1197 and RCC_APB1PeriphResetCmd() functions.
1198 @endverbatim
1199 * @{
1203 * @brief Configures the ADC clock (ADCCLK).
1204 * @param RCC_PLLCLK: defines the ADC clock divider. This clock is derived from
1205 * the PLL Clock.
1206 * This parameter can be one of the following values:
1207 * @arg RCC_ADC12PLLCLK_OFF: ADC12 clock disabled
1208 * @arg RCC_ADC12PLLCLK_Div1: ADC12 clock = PLLCLK/1
1209 * @arg RCC_ADC12PLLCLK_Div2: ADC12 clock = PLLCLK/2
1210 * @arg RCC_ADC12PLLCLK_Div4: ADC12 clock = PLLCLK/4
1211 * @arg RCC_ADC12PLLCLK_Div6: ADC12 clock = PLLCLK/6
1212 * @arg RCC_ADC12PLLCLK_Div8: ADC12 clock = PLLCLK/8
1213 * @arg RCC_ADC12PLLCLK_Div10: ADC12 clock = PLLCLK/10
1214 * @arg RCC_ADC12PLLCLK_Div12: ADC12 clock = PLLCLK/12
1215 * @arg RCC_ADC12PLLCLK_Div16: ADC12 clock = PLLCLK/16
1216 * @arg RCC_ADC12PLLCLK_Div32: ADC12 clock = PLLCLK/32
1217 * @arg RCC_ADC12PLLCLK_Div64: ADC12 clock = PLLCLK/64
1218 * @arg RCC_ADC12PLLCLK_Div128: ADC12 clock = PLLCLK/128
1219 * @arg RCC_ADC12PLLCLK_Div256: ADC12 clock = PLLCLK/256
1220 * @arg RCC_ADC34PLLCLK_OFF: ADC34 clock disabled
1221 * @arg RCC_ADC34PLLCLK_Div1: ADC34 clock = PLLCLK/1
1222 * @arg RCC_ADC34PLLCLK_Div2: ADC34 clock = PLLCLK/2
1223 * @arg RCC_ADC34PLLCLK_Div4: ADC34 clock = PLLCLK/4
1224 * @arg RCC_ADC34PLLCLK_Div6: ADC34 clock = PLLCLK/6
1225 * @arg RCC_ADC34PLLCLK_Div8: ADC34 clock = PLLCLK/8
1226 * @arg RCC_ADC34PLLCLK_Div10: ADC34 clock = PLLCLK/10
1227 * @arg RCC_ADC34PLLCLK_Div12: ADC34 clock = PLLCLK/12
1228 * @arg RCC_ADC34PLLCLK_Div16: ADC34 clock = PLLCLK/16
1229 * @arg RCC_ADC34PLLCLK_Div32: ADC34 clock = PLLCLK/32
1230 * @arg RCC_ADC34PLLCLK_Div64: ADC34 clock = PLLCLK/64
1231 * @arg RCC_ADC34PLLCLK_Div128: ADC34 clock = PLLCLK/128
1232 * @arg RCC_ADC34PLLCLK_Div256: ADC34 clock = PLLCLK/256
1233 * @retval None
1235 void RCC_ADCCLKConfig(uint32_t RCC_PLLCLK)
1237 uint32_t tmp = 0;
1239 /* Check the parameters */
1240 assert_param(IS_RCC_ADCCLK(RCC_PLLCLK));
1242 tmp = (RCC_PLLCLK >> 28);
1244 /* Clears ADCPRE34 bits */
1245 if (tmp != 0)
1247 RCC->CFGR2 &= ~RCC_CFGR2_ADCPRE34;
1249 /* Clears ADCPRE12 bits */
1250 else
1252 RCC->CFGR2 &= ~RCC_CFGR2_ADCPRE12;
1254 /* Set ADCPRE bits according to RCC_PLLCLK value */
1255 RCC->CFGR2 |= RCC_PLLCLK;
1259 * @brief Configures the I2C clock (I2CCLK).
1260 * @param RCC_I2CCLK: defines the I2C clock source. This clock is derived
1261 * from the HSI or System clock.
1262 * This parameter can be one of the following values:
1263 * @arg RCC_I2CxCLK_HSI: I2Cx clock = HSI
1264 * @arg RCC_I2CxCLK_SYSCLK: I2Cx clock = System Clock
1265 * (x can be 1 or 2 or 3).
1266 * @retval None
1268 void RCC_I2CCLKConfig(uint32_t RCC_I2CCLK)
1270 uint32_t tmp = 0;
1272 /* Check the parameters */
1273 assert_param(IS_RCC_I2CCLK(RCC_I2CCLK));
1275 tmp = (RCC_I2CCLK >> 28);
1277 /* Clear I2CSW bit */
1278 switch (tmp)
1280 case 0x00:
1281 RCC->CFGR3 &= ~RCC_CFGR3_I2C1SW;
1282 break;
1283 case 0x01:
1284 RCC->CFGR3 &= ~RCC_CFGR3_I2C2SW;
1285 break;
1286 case 0x02:
1287 RCC->CFGR3 &= ~RCC_CFGR3_I2C3SW;
1288 break;
1289 default:
1290 break;
1293 /* Set I2CSW bits according to RCC_I2CCLK value */
1294 RCC->CFGR3 |= RCC_I2CCLK;
1298 * @brief Configures the TIMx clock sources(TIMCLK).
1299 * @note The configuration of the TIMx clock source is only possible when the
1300 * SYSCLK = PLL and HCLK and PCLK2 clocks are not divided in respect to SYSCLK
1301 * @note If one of the previous conditions is missed, the TIM clock source
1302 * configuration is lost and calling again this function becomes mandatory.
1303 * @param RCC_TIMCLK: defines the TIMx clock source.
1304 * This parameter can be one of the following values:
1305 * @arg RCC_TIMxCLK_HCLK: TIMx clock = APB high speed clock (doubled frequency
1306 * when prescaled)
1307 * @arg RCC_TIMxCLK_PLLCLK: TIMx clock = PLL output (running up to 144 MHz)
1308 * (x can be 1, 8, 15, 16, 17).
1309 * @retval None
1311 void RCC_TIMCLKConfig(uint32_t RCC_TIMCLK)
1313 uint32_t tmp = 0;
1315 /* Check the parameters */
1316 assert_param(IS_RCC_TIMCLK(RCC_TIMCLK));
1318 tmp = (RCC_TIMCLK >> 28);
1320 /* Clear TIMSW bit */
1322 switch (tmp)
1324 case 0x00:
1325 RCC->CFGR3 &= ~RCC_CFGR3_TIM1SW;
1326 break;
1327 case 0x01:
1328 RCC->CFGR3 &= ~RCC_CFGR3_TIM8SW;
1329 break;
1330 case 0x02:
1331 RCC->CFGR3 &= ~RCC_CFGR3_TIM15SW;
1332 break;
1333 case 0x03:
1334 RCC->CFGR3 &= ~RCC_CFGR3_TIM16SW;
1335 break;
1336 case 0x04:
1337 RCC->CFGR3 &= ~RCC_CFGR3_TIM17SW;
1338 break;
1339 default:
1340 break;
1343 /* Set I2CSW bits according to RCC_TIMCLK value */
1344 RCC->CFGR3 |= RCC_TIMCLK;
1348 * @brief Configures the HRTIM1 clock sources(HRTIM1CLK).
1349 * @note The configuration of the HRTIM1 clock source is only possible when the
1350 * SYSCLK = PLL and HCLK and PCLK2 clocks are not divided in respect to SYSCLK
1351 * @note If one of the previous conditions is missed, the TIM clock source
1352 * configuration is lost and calling again this function becomes mandatory.
1353 * @param RCC_HRTIMCLK: defines the TIMx clock source.
1354 * This parameter can be one of the following values:
1355 * @arg RCC_HRTIM1CLK_HCLK: TIMx clock = APB high speed clock (doubled frequency
1356 * when prescaled)
1357 * @arg RCC_HRTIM1CLK_PLLCLK: TIMx clock = PLL output (running up to 144 MHz)
1358 * (x can be 1 or 8).
1359 * @retval None
1361 void RCC_HRTIM1CLKConfig(uint32_t RCC_HRTIMCLK)
1363 /* Check the parameters */
1364 assert_param(IS_RCC_HRTIMCLK(RCC_HRTIMCLK));
1366 /* Clear HRTIMSW bit */
1367 RCC->CFGR3 &= ~RCC_CFGR3_HRTIM1SW;
1369 /* Set HRTIMSW bits according to RCC_HRTIMCLK value */
1370 RCC->CFGR3 |= RCC_HRTIMCLK;
1374 * @brief Configures the USART clock (USARTCLK).
1375 * @param RCC_USARTCLK: defines the USART clock source. This clock is derived
1376 * from the HSI or System clock.
1377 * This parameter can be one of the following values:
1378 * @arg RCC_USARTxCLK_PCLK: USART clock = APB Clock (PCLK)
1379 * @arg RCC_USARTxCLK_SYSCLK: USART clock = System Clock
1380 * @arg RCC_USARTxCLK_LSE: USART clock = LSE Clock
1381 * @arg RCC_USARTxCLK_HSI: USART clock = HSI Clock
1382 * (x can be 1, 2, 3, 4 or 5).
1383 * @retval None
1385 void RCC_USARTCLKConfig(uint32_t RCC_USARTCLK)
1387 uint32_t tmp = 0;
1389 /* Check the parameters */
1390 assert_param(IS_RCC_USARTCLK(RCC_USARTCLK));
1392 tmp = (RCC_USARTCLK >> 28);
1394 /* Clear USARTSW[1:0] bit */
1395 switch (tmp)
1397 case 0x01: /* clear USART1SW */
1398 RCC->CFGR3 &= ~RCC_CFGR3_USART1SW;
1399 break;
1400 case 0x02: /* clear USART2SW */
1401 RCC->CFGR3 &= ~RCC_CFGR3_USART2SW;
1402 break;
1403 case 0x03: /* clear USART3SW */
1404 RCC->CFGR3 &= ~RCC_CFGR3_USART3SW;
1405 break;
1406 case 0x04: /* clear UART4SW */
1407 RCC->CFGR3 &= ~RCC_CFGR3_UART4SW;
1408 break;
1409 case 0x05: /* clear UART5SW */
1410 RCC->CFGR3 &= ~RCC_CFGR3_UART5SW;
1411 break;
1412 default:
1413 break;
1416 /* Set USARTSW bits according to RCC_USARTCLK value */
1417 RCC->CFGR3 |= RCC_USARTCLK;
1421 * @brief Configures the USB clock (USBCLK).
1422 * @param RCC_USBCLKSource: specifies the USB clock source. This clock is
1423 * derived from the PLL output.
1424 * This parameter can be one of the following values:
1425 * @arg RCC_USBCLKSource_PLLCLK_1Div5: PLL clock divided by 1,5 selected as USB
1426 * clock source
1427 * @arg RCC_USBCLKSource_PLLCLK_Div1: PLL clock selected as USB clock source
1428 * @retval None
1430 void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource)
1432 /* Check the parameters */
1433 assert_param(IS_RCC_USBCLK_SOURCE(RCC_USBCLKSource));
1435 *(__IO uint32_t *) CFGR_USBPRE_BB = RCC_USBCLKSource;
1439 * @brief Configures the RTC clock (RTCCLK).
1440 * @note As the RTC clock configuration bits are in the Backup domain and write
1441 * access is denied to this domain after reset, you have to enable write
1442 * access using PWR_BackupAccessCmd(ENABLE) function before to configure
1443 * the RTC clock source (to be done once after reset).
1444 * @note Once the RTC clock is configured it can't be changed unless the RTC
1445 * is reset using RCC_BackupResetCmd function, or by a Power On Reset (POR)
1447 * @param RCC_RTCCLKSource: specifies the RTC clock source.
1448 * This parameter can be one of the following values:
1449 * @arg RCC_RTCCLKSource_LSE: LSE selected as RTC clock
1450 * @arg RCC_RTCCLKSource_LSI: LSI selected as RTC clock
1451 * @arg RCC_RTCCLKSource_HSE_Div32: HSE divided by 32 selected as RTC clock
1453 * @note If the LSE or LSI is used as RTC clock source, the RTC continues to
1454 * work in STOP and STANDBY modes, and can be used as wakeup source.
1455 * However, when the HSE clock is used as RTC clock source, the RTC
1456 * cannot be used in STOP and STANDBY modes.
1457 * @note The maximum input clock frequency for RTC is 2MHz (when using HSE as
1458 * RTC clock source).
1459 * @retval None
1461 void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource)
1463 /* Check the parameters */
1464 assert_param(IS_RCC_RTCCLK_SOURCE(RCC_RTCCLKSource));
1466 /* Select the RTC clock source */
1467 RCC->BDCR |= RCC_RTCCLKSource;
1471 * @brief Configures the I2S clock source (I2SCLK).
1472 * @note This function must be called before enabling the SPI2 and SPI3 clocks.
1473 * @param RCC_I2SCLKSource: specifies the I2S clock source.
1474 * This parameter can be one of the following values:
1475 * @arg RCC_I2S2CLKSource_SYSCLK: SYSCLK clock used as I2S clock source
1476 * @arg RCC_I2S2CLKSource_Ext: External clock mapped on the I2S_CKIN pin
1477 * used as I2S clock source
1478 * @retval None
1480 void RCC_I2SCLKConfig(uint32_t RCC_I2SCLKSource)
1482 /* Check the parameters */
1483 assert_param(IS_RCC_I2SCLK_SOURCE(RCC_I2SCLKSource));
1485 *(__IO uint32_t *) CFGR_I2SSRC_BB = RCC_I2SCLKSource;
1489 * @brief Enables or disables the RTC clock.
1490 * @note This function must be used only after the RTC clock source was selected
1491 * using the RCC_RTCCLKConfig function.
1492 * @param NewState: new state of the RTC clock.
1493 * This parameter can be: ENABLE or DISABLE.
1494 * @retval None
1496 void RCC_RTCCLKCmd(FunctionalState NewState)
1498 /* Check the parameters */
1499 assert_param(IS_FUNCTIONAL_STATE(NewState));
1501 *(__IO uint32_t *) BDCR_RTCEN_BB = (uint32_t)NewState;
1505 * @brief Forces or releases the Backup domain reset.
1506 * @note This function resets the RTC peripheral (including the backup registers)
1507 * and the RTC clock source selection in RCC_BDCR register.
1508 * @param NewState: new state of the Backup domain reset.
1509 * This parameter can be: ENABLE or DISABLE.
1510 * @retval None
1512 void RCC_BackupResetCmd(FunctionalState NewState)
1514 /* Check the parameters */
1515 assert_param(IS_FUNCTIONAL_STATE(NewState));
1517 *(__IO uint32_t *) BDCR_BDRST_BB = (uint32_t)NewState;
1521 * @brief Enables or disables the AHB peripheral clock.
1522 * @note After reset, the peripheral clock (used for registers read/write access)
1523 * is disabled and the application software has to enable this clock before
1524 * using it.
1525 * @param RCC_AHBPeriph: specifies the AHB peripheral to gates its clock.
1526 * This parameter can be any combination of the following values:
1527 * @arg RCC_AHBPeriph_GPIOA
1528 * @arg RCC_AHBPeriph_GPIOB
1529 * @arg RCC_AHBPeriph_GPIOC
1530 * @arg RCC_AHBPeriph_GPIOD
1531 * @arg RCC_AHBPeriph_GPIOE
1532 * @arg RCC_AHBPeriph_GPIOF
1533 * @arg RCC_AHBPeriph_TS
1534 * @arg RCC_AHBPeriph_CRC
1535 * @arg RCC_AHBPeriph_FLITF (has effect only when the Flash memory is in power down mode)
1536 * @arg RCC_AHBPeriph_SRAM
1537 * @arg RCC_AHBPeriph_DMA2
1538 * @arg RCC_AHBPeriph_DMA1
1539 * @arg RCC_AHBPeriph_ADC34
1540 * @arg RCC_AHBPeriph_ADC12
1541 * @param NewState: new state of the specified peripheral clock.
1542 * This parameter can be: ENABLE or DISABLE.
1543 * @retval None
1545 void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState)
1547 /* Check the parameters */
1548 assert_param(IS_RCC_AHB_PERIPH(RCC_AHBPeriph));
1549 assert_param(IS_FUNCTIONAL_STATE(NewState));
1551 if (NewState != DISABLE)
1553 RCC->AHBENR |= RCC_AHBPeriph;
1555 else
1557 RCC->AHBENR &= ~RCC_AHBPeriph;
1562 * @brief Enables or disables the High Speed APB (APB2) peripheral clock.
1563 * @note After reset, the peripheral clock (used for registers read/write access)
1564 * is disabled and the application software has to enable this clock before
1565 * using it.
1566 * @param RCC_APB2Periph: specifies the APB2 peripheral to gates its clock.
1567 * This parameter can be any combination of the following values:
1568 * @arg RCC_APB2Periph_SYSCFG
1569 * @arg RCC_APB2Periph_SPI1
1570 * @arg RCC_APB2Periph_USART1
1571 * @arg RCC_APB2Periph_TIM15
1572 * @arg RCC_APB2Periph_TIM16
1573 * @arg RCC_APB2Periph_TIM17
1574 * @arg RCC_APB2Periph_TIM1
1575 * @arg RCC_APB2Periph_TIM8
1576 * @arg RCC_APB2Periph_HRTIM1
1577 * @param NewState: new state of the specified peripheral clock.
1578 * This parameter can be: ENABLE or DISABLE.
1579 * @retval None
1581 void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
1583 /* Check the parameters */
1584 assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph));
1585 assert_param(IS_FUNCTIONAL_STATE(NewState));
1587 if (NewState != DISABLE)
1589 RCC->APB2ENR |= RCC_APB2Periph;
1591 else
1593 RCC->APB2ENR &= ~RCC_APB2Periph;
1598 * @brief Enables or disables the Low Speed APB (APB1) peripheral clock.
1599 * @note After reset, the peripheral clock (used for registers read/write access)
1600 * is disabled and the application software has to enable this clock before
1601 * using it.
1602 * @param RCC_APB1Periph: specifies the APB1 peripheral to gates its clock.
1603 * This parameter can be any combination of the following values:
1604 * @arg RCC_APB1Periph_TIM2
1605 * @arg RCC_APB1Periph_TIM3
1606 * @arg RCC_APB1Periph_TIM4
1607 * @arg RCC_APB1Periph_TIM6
1608 * @arg RCC_APB1Periph_TIM7
1609 * @arg RCC_APB1Periph_WWDG
1610 * @arg RCC_APB1Periph_SPI2
1611 * @arg RCC_APB1Periph_SPI3
1612 * @arg RCC_APB1Periph_USART2
1613 * @arg RCC_APB1Periph_USART3
1614 * @arg RCC_APB1Periph_UART4
1615 * @arg RCC_APB1Periph_UART5
1616 * @arg RCC_APB1Periph_I2C1
1617 * @arg RCC_APB1Periph_I2C2
1618 * @arg RCC_APB1Periph_USB
1619 * @arg RCC_APB1Periph_CAN1
1620 * @arg RCC_APB1Periph_PWR
1621 * @arg RCC_APB1Periph_DAC1
1622 * @arg RCC_APB1Periph_DAC2
1623 * @param NewState: new state of the specified peripheral clock.
1624 * This parameter can be: ENABLE or DISABLE.
1625 * @retval None
1627 void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
1629 /* Check the parameters */
1630 assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph));
1631 assert_param(IS_FUNCTIONAL_STATE(NewState));
1633 if (NewState != DISABLE)
1635 RCC->APB1ENR |= RCC_APB1Periph;
1637 else
1639 RCC->APB1ENR &= ~RCC_APB1Periph;
1644 * @brief Forces or releases AHB peripheral reset.
1645 * @param RCC_AHBPeriph: specifies the AHB peripheral to reset.
1646 * This parameter can be any combination of the following values:
1647 * @arg RCC_AHBPeriph_GPIOA
1648 * @arg RCC_AHBPeriph_GPIOB
1649 * @arg RCC_AHBPeriph_GPIOC
1650 * @arg RCC_AHBPeriph_GPIOD
1651 * @arg RCC_AHBPeriph_GPIOE
1652 * @arg RCC_AHBPeriph_GPIOF
1653 * @arg RCC_AHBPeriph_TS
1654 * @arg RCC_AHBPeriph_ADC34
1655 * @arg RCC_AHBPeriph_ADC12
1656 * @param NewState: new state of the specified peripheral reset.
1657 * This parameter can be: ENABLE or DISABLE.
1658 * @retval None
1660 void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState)
1662 /* Check the parameters */
1663 assert_param(IS_RCC_AHB_RST_PERIPH(RCC_AHBPeriph));
1664 assert_param(IS_FUNCTIONAL_STATE(NewState));
1666 if (NewState != DISABLE)
1668 RCC->AHBRSTR |= RCC_AHBPeriph;
1670 else
1672 RCC->AHBRSTR &= ~RCC_AHBPeriph;
1677 * @brief Forces or releases High Speed APB (APB2) peripheral reset.
1678 * @param RCC_APB2Periph: specifies the APB2 peripheral to reset.
1679 * This parameter can be any combination of the following values:
1680 * @arg RCC_APB2Periph_SYSCFG
1681 * @arg RCC_APB2Periph_SPI1
1682 * @arg RCC_APB2Periph_USART1
1683 * @arg RCC_APB2Periph_TIM15
1684 * @arg RCC_APB2Periph_TIM16
1685 * @arg RCC_APB2Periph_TIM17
1686 * @arg RCC_APB2Periph_TIM1
1687 * @arg RCC_APB2Periph_TIM8
1688 * @arg RCC_APB2Periph_HRTIM1
1689 * @param NewState: new state of the specified peripheral reset.
1690 * This parameter can be: ENABLE or DISABLE.
1691 * @retval None
1693 void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
1695 /* Check the parameters */
1696 assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph));
1697 assert_param(IS_FUNCTIONAL_STATE(NewState));
1699 if (NewState != DISABLE)
1701 RCC->APB2RSTR |= RCC_APB2Periph;
1703 else
1705 RCC->APB2RSTR &= ~RCC_APB2Periph;
1710 * @brief Forces or releases Low Speed APB (APB1) peripheral reset.
1711 * @param RCC_APB1Periph: specifies the APB1 peripheral to reset.
1712 * This parameter can be any combination of the following values:
1713 * @arg RCC_APB1Periph_TIM2
1714 * @arg RCC_APB1Periph_TIM3
1715 * @arg RCC_APB1Periph_TIM4
1716 * @arg RCC_APB1Periph_TIM6
1717 * @arg RCC_APB1Periph_TIM7
1718 * @arg RCC_APB1Periph_WWDG
1719 * @arg RCC_APB1Periph_SPI2
1720 * @arg RCC_APB1Periph_SPI3
1721 * @arg RCC_APB1Periph_USART2
1722 * @arg RCC_APB1Periph_USART3
1723 * @arg RCC_APB1Periph_UART4
1724 * @arg RCC_APB1Periph_UART5
1725 * @arg RCC_APB1Periph_I2C1
1726 * @arg RCC_APB1Periph_I2C2
1727 * @arg RCC_APB1Periph_I2C3
1728 * @arg RCC_APB1Periph_USB
1729 * @arg RCC_APB1Periph_CAN1
1730 * @arg RCC_APB1Periph_PWR
1731 * @arg RCC_APB1Periph_DAC
1732 * @param NewState: new state of the specified peripheral clock.
1733 * This parameter can be: ENABLE or DISABLE.
1734 * @retval None
1736 void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
1738 /* Check the parameters */
1739 assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph));
1740 assert_param(IS_FUNCTIONAL_STATE(NewState));
1742 if (NewState != DISABLE)
1744 RCC->APB1RSTR |= RCC_APB1Periph;
1746 else
1748 RCC->APB1RSTR &= ~RCC_APB1Periph;
1753 * @}
1756 /** @defgroup RCC_Group4 Interrupts and flags management functions
1757 * @brief Interrupts and flags management functions
1759 @verbatim
1760 ===============================================================================
1761 ##### Interrupts and flags management functions #####
1762 ===============================================================================
1764 @endverbatim
1765 * @{
1769 * @brief Enables or disables the specified RCC interrupts.
1770 * @note The CSS interrupt doesn't have an enable bit; once the CSS is enabled
1771 * and if the HSE clock fails, the CSS interrupt occurs and an NMI is
1772 * automatically generated. The NMI will be executed indefinitely, and
1773 * since NMI has higher priority than any other IRQ (and main program)
1774 * the application will be stacked in the NMI ISR unless the CSS interrupt
1775 * pending bit is cleared.
1776 * @param RCC_IT: specifies the RCC interrupt sources to be enabled or disabled.
1777 * This parameter can be any combination of the following values:
1778 * @arg RCC_IT_LSIRDY: LSI ready interrupt
1779 * @arg RCC_IT_LSERDY: LSE ready interrupt
1780 * @arg RCC_IT_HSIRDY: HSI ready interrupt
1781 * @arg RCC_IT_HSERDY: HSE ready interrupt
1782 * @arg RCC_IT_PLLRDY: PLL ready interrupt
1783 * @param NewState: new state of the specified RCC interrupts.
1784 * This parameter can be: ENABLE or DISABLE.
1785 * @retval None
1787 void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState)
1789 /* Check the parameters */
1790 assert_param(IS_RCC_IT(RCC_IT));
1791 assert_param(IS_FUNCTIONAL_STATE(NewState));
1793 if (NewState != DISABLE)
1795 /* Perform Byte access to RCC_CIR[13:8] bits to enable the selected interrupts */
1796 *(__IO uint8_t *) CIR_BYTE2_ADDRESS |= RCC_IT;
1798 else
1800 /* Perform Byte access to RCC_CIR[13:8] bits to disable the selected interrupts */
1801 *(__IO uint8_t *) CIR_BYTE2_ADDRESS &= (uint8_t)~RCC_IT;
1806 * @brief Checks whether the specified RCC flag is set or not.
1807 * @param RCC_FLAG: specifies the flag to check.
1808 * This parameter can be one of the following values:
1809 * @arg RCC_FLAG_HSIRDY: HSI oscillator clock ready
1810 * @arg RCC_FLAG_HSERDY: HSE oscillator clock ready
1811 * @arg RCC_FLAG_PLLRDY: PLL clock ready
1812 * @arg RCC_FLAG_MCOF: MCO Flag
1813 * @arg RCC_FLAG_LSERDY: LSE oscillator clock ready
1814 * @arg RCC_FLAG_LSIRDY: LSI oscillator clock ready
1815 * @arg RCC_FLAG_OBLRST: Option Byte Loader (OBL) reset
1816 * @arg RCC_FLAG_PINRST: Pin reset
1817 * @arg RCC_FLAG_PORRST: POR/PDR reset
1818 * @arg RCC_FLAG_SFTRST: Software reset
1819 * @arg RCC_FLAG_IWDGRST: Independent Watchdog reset
1820 * @arg RCC_FLAG_WWDGRST: Window Watchdog reset
1821 * @arg RCC_FLAG_LPWRRST: Low Power reset
1822 * @retval The new state of RCC_FLAG (SET or RESET).
1824 FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG)
1826 uint32_t tmp = 0;
1827 uint32_t statusreg = 0;
1828 FlagStatus bitstatus = RESET;
1830 /* Check the parameters */
1831 assert_param(IS_RCC_FLAG(RCC_FLAG));
1833 /* Get the RCC register index */
1834 tmp = RCC_FLAG >> 5;
1836 if (tmp == 0) /* The flag to check is in CR register */
1838 statusreg = RCC->CR;
1840 else if (tmp == 1) /* The flag to check is in BDCR register */
1842 statusreg = RCC->BDCR;
1844 else if (tmp == 4) /* The flag to check is in CFGR register */
1846 statusreg = RCC->CFGR;
1848 else /* The flag to check is in CSR register */
1850 statusreg = RCC->CSR;
1853 /* Get the flag position */
1854 tmp = RCC_FLAG & FLAG_MASK;
1856 if ((statusreg & ((uint32_t)1 << tmp)) != (uint32_t)RESET)
1858 bitstatus = SET;
1860 else
1862 bitstatus = RESET;
1864 /* Return the flag status */
1865 return bitstatus;
1869 * @brief Clears the RCC reset flags.
1870 * The reset flags are: RCC_FLAG_OBLRST, RCC_FLAG_PINRST, RCC_FLAG_PORRST,
1871 * RCC_FLAG_SFTRST, RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST, RCC_FLAG_LPWRRST.
1872 * @param None
1873 * @retval None
1875 void RCC_ClearFlag(void)
1877 /* Set RMVF bit to clear the reset flags */
1878 RCC->CSR |= RCC_CSR_RMVF;
1882 * @brief Checks whether the specified RCC interrupt has occurred or not.
1883 * @param RCC_IT: specifies the RCC interrupt source to check.
1884 * This parameter can be one of the following values:
1885 * @arg RCC_IT_LSIRDY: LSI ready interrupt
1886 * @arg RCC_IT_LSERDY: LSE ready interrupt
1887 * @arg RCC_IT_HSIRDY: HSI ready interrupt
1888 * @arg RCC_IT_HSERDY: HSE ready interrupt
1889 * @arg RCC_IT_PLLRDY: PLL ready interrupt
1890 * @arg RCC_IT_CSS: Clock Security System interrupt
1891 * @retval The new state of RCC_IT (SET or RESET).
1893 ITStatus RCC_GetITStatus(uint8_t RCC_IT)
1895 ITStatus bitstatus = RESET;
1897 /* Check the parameters */
1898 assert_param(IS_RCC_GET_IT(RCC_IT));
1900 /* Check the status of the specified RCC interrupt */
1901 if ((RCC->CIR & RCC_IT) != (uint32_t)RESET)
1903 bitstatus = SET;
1905 else
1907 bitstatus = RESET;
1909 /* Return the RCC_IT status */
1910 return bitstatus;
1914 * @brief Clears the RCC's interrupt pending bits.
1915 * @param RCC_IT: specifies the interrupt pending bit to clear.
1916 * This parameter can be any combination of the following values:
1917 * @arg RCC_IT_LSIRDY: LSI ready interrupt
1918 * @arg RCC_IT_LSERDY: LSE ready interrupt
1919 * @arg RCC_IT_HSIRDY: HSI ready interrupt
1920 * @arg RCC_IT_HSERDY: HSE ready interrupt
1921 * @arg RCC_IT_PLLRDY: PLL ready interrupt
1922 * @arg RCC_IT_CSS: Clock Security System interrupt
1923 * @retval None
1925 void RCC_ClearITPendingBit(uint8_t RCC_IT)
1927 /* Check the parameters */
1928 assert_param(IS_RCC_CLEAR_IT(RCC_IT));
1930 /* Perform Byte access to RCC_CIR[23:16] bits to clear the selected interrupt
1931 pending bits */
1932 *(__IO uint8_t *) CIR_BYTE3_ADDRESS = RCC_IT;
1936 * @}
1940 * @}
1944 * @}
1948 * @}
1951 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/