|   | 
| Functions | |
| void | RCC_ADCCLKConfig (uint32_t RCC_PLLCLK) | 
| Configures the ADC clock (ADCCLK).  More... | |
| void | RCC_AdjustHSICalibrationValue (uint8_t HSICalibrationValue) | 
| Adjusts the Internal High Speed oscillator (HSI) calibration value.  More... | |
| void | RCC_AHBPeriphClockCmd (uint32_t RCC_AHBPeriph, FunctionalState NewState) | 
| Enables or disables the AHB peripheral clock.  More... | |
| void | RCC_AHBPeriphResetCmd (uint32_t RCC_AHBPeriph, FunctionalState NewState) | 
| Forces or releases AHB peripheral reset.  More... | |
| void | RCC_APB1PeriphClockCmd (uint32_t RCC_APB1Periph, FunctionalState NewState) | 
| Enables or disables the Low Speed APB (APB1) peripheral clock.  More... | |
| void | RCC_APB1PeriphResetCmd (uint32_t RCC_APB1Periph, FunctionalState NewState) | 
| Forces or releases Low Speed APB (APB1) peripheral reset.  More... | |
| void | RCC_APB2PeriphClockCmd (uint32_t RCC_APB2Periph, FunctionalState NewState) | 
| Enables or disables the High Speed APB (APB2) peripheral clock.  More... | |
| void | RCC_APB2PeriphResetCmd (uint32_t RCC_APB2Periph, FunctionalState NewState) | 
| Forces or releases High Speed APB (APB2) peripheral reset.  More... | |
| void | RCC_BackupResetCmd (FunctionalState NewState) | 
| Forces or releases the Backup domain reset.  More... | |
| void | RCC_ClearFlag (void) | 
| Clears the RCC reset flags. The reset flags are: RCC_FLAG_PINRST, RCC_FLAG_PORRST, RCC_FLAG_SFTRST, RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST, RCC_FLAG_LPWRRST.  More... | |
| void | RCC_ClearITPendingBit (uint8_t RCC_IT) | 
| Clears the RCC's interrupt pending bits.  More... | |
| void | RCC_ClockSecuritySystemCmd (FunctionalState NewState) | 
| Enables or disables the Clock Security System.  More... | |
| void | RCC_DeInit (void) | 
| Resets the RCC clock configuration to the default reset state.  More... | |
| void | RCC_GetClocksFreq (RCC_ClocksTypeDef *RCC_Clocks) | 
| Returns the frequencies of different on chip clocks; SYSCLK, HCLK, PCLK1 and PCLK2.  More... | |
| FlagStatus | RCC_GetFlagStatus (uint8_t RCC_FLAG) | 
| Checks whether the specified RCC flag is set or not.  More... | |
| ITStatus | RCC_GetITStatus (uint8_t RCC_IT) | 
| Checks whether the specified RCC interrupt has occurred or not.  More... | |
| uint8_t | RCC_GetSYSCLKSource (void) | 
| Returns the clock source used as system clock.  More... | |
| void | RCC_HCLKConfig (uint32_t RCC_SYSCLK) | 
| Configures the AHB clock (HCLK).  More... | |
| void | RCC_HRTIM1CLKConfig (uint32_t RCC_HRTIMCLK) | 
| Configures the HRTIM1 clock sources(HRTIM1CLK).  More... | |
| void | RCC_HSEConfig (uint8_t RCC_HSE) | 
| Configures the External High Speed oscillator (HSE).  More... | |
| void | RCC_HSICmd (FunctionalState NewState) | 
| Enables or disables the Internal High Speed oscillator (HSI).  More... | |
| void | RCC_I2CCLKConfig (uint32_t RCC_I2CCLK) | 
| Configures the I2C clock (I2CCLK).  More... | |
| void | RCC_I2SCLKConfig (uint32_t RCC_I2SCLKSource) | 
| Configures the I2S clock source (I2SCLK).  More... | |
| void | RCC_ITConfig (uint8_t RCC_IT, FunctionalState NewState) | 
| Enables or disables the specified RCC interrupts.  More... | |
| void | RCC_LSEConfig (uint32_t RCC_LSE) | 
| Configures the External Low Speed oscillator (LSE).  More... | |
| void | RCC_LSEDriveConfig (uint32_t RCC_LSEDrive) | 
| Configures the External Low Speed oscillator (LSE) drive capability.  More... | |
| void | RCC_LSICmd (FunctionalState NewState) | 
| Enables or disables the Internal Low Speed oscillator (LSI).  More... | |
| void | RCC_MCOConfig (uint8_t RCC_MCOSource, uint32_t RCC_MCOPrescaler) | 
| Selects the clock source to output on MCO pin (PA8) and the corresponding prescsaler.  More... | |
| void | RCC_PCLK1Config (uint32_t RCC_HCLK) | 
| Configures the Low Speed APB clock (PCLK1).  More... | |
| void | RCC_PCLK2Config (uint32_t RCC_HCLK) | 
| Configures the High Speed APB clock (PCLK2).  More... | |
| void | RCC_PLLCmd (FunctionalState NewState) | 
| Enables or disables the main PLL.  More... | |
| void | RCC_PLLConfig (uint32_t RCC_PLLSource, uint32_t RCC_PLLMul) | 
| Configures the PLL clock source and multiplication factor.  More... | |
| void | RCC_PREDIV1Config (uint32_t RCC_PREDIV1_Div) | 
| Configures the PREDIV1 division factor.  More... | |
| void | RCC_RTCCLKCmd (FunctionalState NewState) | 
| Enables or disables the RTC clock.  More... | |
| void | RCC_RTCCLKConfig (uint32_t RCC_RTCCLKSource) | 
| Configures the RTC clock (RTCCLK).  More... | |
| void | RCC_SYSCLKConfig (uint32_t RCC_SYSCLKSource) | 
| Configures the system clock (SYSCLK).  More... | |
| void | RCC_TIMCLKConfig (uint32_t RCC_TIMCLK) | 
| Configures the TIMx clock sources(TIMCLK).  More... | |
| void | RCC_USARTCLKConfig (uint32_t RCC_USARTCLK) | 
| Configures the USART clock (USARTCLK).  More... | |
| void | RCC_USBCLKConfig (uint32_t RCC_USBCLKSource) | 
| Configures the USB clock (USBCLK).  More... | |
| ErrorStatus | RCC_WaitForHSEStartUp (void) | 
| Waits for HSE start-up.  More... | |
| void RCC_ADCCLKConfig | ( | uint32_t | RCC_PLLCLK | ) | 
Configures the ADC clock (ADCCLK).
| RCC_PCLK2 | defines the ADC clock divider. This clock is derived from the APB2 clock (PCLK2). This parameter can be one of the following values: 
 | 
| None | 
| RCC_PLLCLK | defines the ADC clock divider. This clock is derived from the PLL Clock. This parameter can be one of the following values: 
 | 
| None | 
Definition at line 767 of file stm32f10x_rcc.c.
| void RCC_AdjustHSICalibrationValue | ( | uint8_t | HSICalibrationValue | ) | 
Adjusts the Internal High Speed oscillator (HSI) calibration value.
| HSICalibrationValue | specifies the calibration trimming value. This parameter must be a number between 0 and 0x1F. | 
| None | 
| HSICalibrationValue | specifies the HSI calibration trimming value. This parameter must be a number between 0 and 0x1F. | 
| None | 
| HSICalibrationValue | specifies the calibration trimming value. This parameter must be a number between 0 and 0x1F. | 
| None | 
Definition at line 339 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_AHBPeriphClockCmd | ( | uint32_t | RCC_AHBPeriph, | 
| FunctionalState | NewState | ||
| ) | 
Enables or disables the AHB peripheral clock.
| RCC_AHBPeriph | specifies the AHB peripheral to gates its clock. | 
For STM32_Connectivity_line_devices, this parameter can be any combination of the following values:
For other_STM32_devices, this parameter can be any combination of the following values:
| NewState | new state of the specified peripheral clock. This parameter can be: ENABLE or DISABLE. | 
| None | 
| RCC_AHBPeriph | specifies the AHB peripheral to gates its clock. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified peripheral clock. This parameter can be: ENABLE or DISABLE. | 
| None | 
Definition at line 1065 of file stm32f10x_rcc.c.
| void RCC_AHBPeriphResetCmd | ( | uint32_t | RCC_AHBPeriph, | 
| FunctionalState | NewState | ||
| ) | 
Forces or releases AHB peripheral reset.
| RCC_AHBPeriph | specifies the AHB peripheral to reset. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified peripheral reset. This parameter can be: ENABLE or DISABLE. | 
| None | 
Definition at line 1660 of file stm32f30x_rcc.c.
| void RCC_APB1PeriphClockCmd | ( | uint32_t | RCC_APB1Periph, | 
| FunctionalState | NewState | ||
| ) | 
Enables or disables the Low Speed APB (APB1) peripheral clock.
| RCC_APB1Periph | specifies the APB1 peripheral to gates its clock. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified peripheral clock. This parameter can be: ENABLE or DISABLE. | 
| None | 
| RCC_APB1Periph | specifies the APB1 peripheral to gates its clock. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified peripheral clock. This parameter can be: ENABLE or DISABLE. | 
| None | 
| RCC_APB1Periph | specifies the APB1 peripheral to gates its clock. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified peripheral clock. This parameter can be: ENABLE or DISABLE. | 
| None | 
| RCC_APB1Periph | specifies the APB1 peripheral to gates its clock. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified peripheral clock. This parameter can be: ENABLE or DISABLE. | 
| None | 
Definition at line 2004 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_APB1PeriphResetCmd | ( | uint32_t | RCC_APB1Periph, | 
| FunctionalState | NewState | ||
| ) | 
Forces or releases Low Speed APB (APB1) peripheral reset.
| RCC_APB1Periph | specifies the APB1 peripheral to reset. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified peripheral reset. This parameter can be: ENABLE or DISABLE. | 
| None | 
| RCC_APB1Periph | specifies the APB1 peripheral to reset. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified peripheral reset. This parameter can be: ENABLE or DISABLE. | 
| None | 
| RCC_APB1Periph | specifies the APB1 peripheral to reset. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified peripheral clock. This parameter can be: ENABLE or DISABLE. | 
| None | 
| RCC_APB1Periph | specifies the APB1 peripheral to reset. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified peripheral clock. This parameter can be: ENABLE or DISABLE. | 
| None | 
Definition at line 2204 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_APB2PeriphClockCmd | ( | uint32_t | RCC_APB2Periph, | 
| FunctionalState | NewState | ||
| ) | 
Enables or disables the High Speed APB (APB2) peripheral clock.
| RCC_APB2Periph | specifies the APB2 peripheral to gates its clock. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified peripheral clock. This parameter can be: ENABLE or DISABLE. | 
| None | 
| RCC_APB2Periph | specifies the APB2 peripheral to gates its clock. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified peripheral clock. This parameter can be: ENABLE or DISABLE. | 
| None | 
| RCC_APB2Periph | specifies the APB2 peripheral to gates its clock. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified peripheral clock. This parameter can be: ENABLE or DISABLE. | 
| None | 
| RCC_APB2Periph | specifies the APB2 peripheral to gates its clock. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified peripheral clock. This parameter can be: ENABLE or DISABLE. | 
| None | 
Definition at line 2051 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_APB2PeriphResetCmd | ( | uint32_t | RCC_APB2Periph, | 
| FunctionalState | NewState | ||
| ) | 
Forces or releases High Speed APB (APB2) peripheral reset.
| RCC_APB2Periph | specifies the APB2 peripheral to reset. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified peripheral reset. This parameter can be: ENABLE or DISABLE. | 
| None | 
| RCC_APB2Periph | specifies the APB2 peripheral to reset. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified peripheral reset. This parameter can be: ENABLE or DISABLE. | 
| None | 
| RCC_APB2Periph | specifies the APB2 peripheral to reset. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified peripheral reset. This parameter can be: ENABLE or DISABLE. | 
| None | 
| RCC_APB2Periph | specifies the APB2 peripheral to reset. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified peripheral reset. This parameter can be: ENABLE or DISABLE. | 
| None | 
Definition at line 2247 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_BackupResetCmd | ( | FunctionalState | NewState | ) | 
Forces or releases the Backup domain reset.
| NewState | new state of the Backup domain reset. This parameter can be: ENABLE or DISABLE. | 
| None | 
| NewState | new state of the Backup domain reset. This parameter can be: ENABLE or DISABLE. | 
| None | 
| NewState | new state of the Backup domain reset. This parameter can be: ENABLE or DISABLE. | 
| None | 
Definition at line 1519 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_ClearFlag | ( | void | ) | 
Clears the RCC reset flags. The reset flags are: RCC_FLAG_PINRST, RCC_FLAG_PORRST, RCC_FLAG_SFTRST, RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST, RCC_FLAG_LPWRRST.
Clears the RCC reset flags. The reset flags are: RCC_FLAG_OBLRST, RCC_FLAG_PINRST, RCC_FLAG_PORRST, RCC_FLAG_SFTRST, RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST, RCC_FLAG_LPWRRST.
| None | 
| None | Clears the RCC reset flags. The reset flags are: RCC_FLAG_PINRST, RCC_FLAG_PORRST, RCC_FLAG_SFTRST, RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST, RCC_FLAG_LPWRRST. | 
| None | 
| None | 
Definition at line 2870 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_ClearITPendingBit | ( | uint8_t | RCC_IT | ) | 
Clears the RCC's interrupt pending bits.
| RCC_IT | specifies the interrupt pending bit to clear. This parameter can be any combination of the following values: 
 | 
| None | 
| RCC_IT | specifies the interrupt pending bit to clear. This parameter can be any combination of the following values: 
 | 
| None | 
| RCC_IT | specifies the interrupt pending bit to clear. This parameter can be any combination of the following values: 
 | 
| None | 
| RCC_IT | specifies the interrupt pending bit to clear. | 
For STM32_Connectivity_line_devices, this parameter can be any combination of the following values:
For other_STM32_devices, this parameter can be any combination of the following values:
| None | 
Definition at line 2924 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_ClockSecuritySystemCmd | ( | FunctionalState | NewState | ) | 
Enables or disables the Clock Security System.
| NewState | new state of the Clock Security System. This parameter can be: ENABLE or DISABLE. | 
| None | 
| NewState | new state of the Clock Security System.. This parameter can be: ENABLE or DISABLE. | 
| None | 
Definition at line 879 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_DeInit | ( | void | ) | 
Resets the RCC clock configuration to the default reset state.
| None | 
| None | 
| None | 
| None | 
| None | 
| None | 
Definition at line 225 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_GetClocksFreq | ( | RCC_ClocksTypeDef * | RCC_Clocks | ) | 
Returns the frequencies of different on chip clocks; SYSCLK, HCLK, PCLK1 and PCLK2.
Returns the frequencies of the System, AHB, APB2 and APB1 busses clocks.
| RCC_Clocks | pointer to a RCC_ClocksTypeDef structure which will hold the clocks frequencies. | 
| None | 
| RCC_Clocks | pointer to a RCC_ClocksTypeDef structure which will hold the clocks frequencies. | 
| None | Returns the frequencies of different on chip clocks; SYSCLK, HCLK, PCLK1 and PCLK2. | 
| RCC_Clocks | pointer to a RCC_ClocksTypeDef structure which will hold the clocks frequencies. | 
| None | 
Definition at line 1317 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| FlagStatus RCC_GetFlagStatus | ( | uint8_t | RCC_FLAG | ) | 
Checks whether the specified RCC flag is set or not.
| RCC_FLAG | specifies the flag to check. This parameter can be one of the following values: 
 | 
| The | new state of RCC_FLAG (SET or RESET). | 
| RCC_FLAG | specifies the flag to check. This parameter can be one of the following values: 
 | 
| The | new state of RCC_FLAG (SET or RESET). | 
| RCC_FLAG | specifies the flag to check. This parameter can be one of the following values: 
 | 
| The | new state of RCC_FLAG (SET or RESET). | 
| RCC_FLAG | specifies the flag to check. | 
For STM32_Connectivity_line_devices, this parameter can be one of the following values:
For other_STM32_devices, this parameter can be one of the following values:
| The | new state of RCC_FLAG (SET or RESET). | 
Definition at line 2825 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| ITStatus RCC_GetITStatus | ( | uint8_t | RCC_IT | ) | 
Checks whether the specified RCC interrupt has occurred or not.
| RCC_IT | specifies the RCC interrupt source to check. This parameter can be one of the following values: 
 | 
| The | new state of RCC_IT (SET or RESET). | 
| RCC_IT | specifies the RCC interrupt source to check. This parameter can be one of the following values: 
 | 
| The | new state of RCC_IT (SET or RESET). | 
| RCC_IT | specifies the RCC interrupt source to check. This parameter can be one of the following values: 
 | 
| The | new state of RCC_IT (SET or RESET). | 
| RCC_IT | specifies the RCC interrupt source to check. | 
For STM32_Connectivity_line_devices, this parameter can be one of the following values:
For other_STM32_devices, this parameter can be one of the following values:
| The | new state of RCC_IT (SET or RESET). | 
Definition at line 2890 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| uint8_t RCC_GetSYSCLKSource | ( | void | ) | 
Returns the clock source used as system clock.
| None | 
| The | clock source used as system clock. The returned value can be one of the following: 
 | 
| None | 
| The | clock source used as system clock. The returned value can be one of the following: 
 | 
| None | 
| The | clock source used as system clock. The returned value can be one of the following values: 
 | 
| None | 
| The | clock source used as system clock. The returned value can be one of the following: 
 | 
Definition at line 1178 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_HCLKConfig | ( | uint32_t | RCC_SYSCLK | ) | 
Configures the AHB clock (HCLK).
| RCC_SYSCLK | defines the AHB clock divider. This clock is derived from the system clock (SYSCLK). This parameter can be one of the following values: 
 | 
| None | 
| RCC_SYSCLK | defines the AHB clock divider. This clock is derived from the system clock (SYSCLK). This parameter can be one of the following values: 
 | 
| None | 
| RCC_SYSCLK | defines the AHB clock divider. This clock is derived from the system clock (SYSCLK). This parameter can be one of the following values: 
 | 
| None | 
Definition at line 1203 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_HRTIM1CLKConfig | ( | uint32_t | RCC_HRTIMCLK | ) | 
Configures the HRTIM1 clock sources(HRTIM1CLK).
| RCC_HRTIMCLK | defines the TIMx clock source. This parameter can be one of the following values: 
 | 
| None | 
Definition at line 1361 of file stm32f30x_rcc.c.
| void RCC_HSEConfig | ( | uint8_t | RCC_HSE | ) | 
Configures the External High Speed oscillator (HSE).
| RCC_HSE | specifies the new state of the HSE. This parameter can be one of the following values: 
 | 
| None | 
| RCC_HSE | specifies the new state of the HSE. This parameter can be one of the following values: 
 | 
| None | 
Definition at line 284 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_HSICmd | ( | FunctionalState | NewState | ) | 
Enables or disables the Internal High Speed oscillator (HSI).
| NewState | new state of the HSI. This parameter can be: ENABLE or DISABLE. | 
| None | 
| NewState | new state of the HSI. This parameter can be: ENABLE or DISABLE. | 
| None | 
| NewState | new state of the HSI. This parameter can be: ENABLE or DISABLE. | 
| None | 
Definition at line 375 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_I2CCLKConfig | ( | uint32_t | RCC_I2CCLK | ) | 
Configures the I2C clock (I2CCLK).
| RCC_I2CCLK | defines the I2C clock source. This clock is derived from the HSI or System clock. This parameter can be one of the following values: 
 | 
| None | 
Definition at line 1268 of file stm32f30x_rcc.c.
| void RCC_I2SCLKConfig | ( | uint32_t | RCC_I2SCLKSource | ) | 
Configures the I2S clock source (I2SCLK).
| RCC_I2SCLKSource | specifies the I2S clock source. This parameter can be one of the following values: 
 | 
| None | 
| RCC_I2SCLKSource | specifies the I2S clock source. This parameter can be one of the following values: 
 | 
| None | 
Definition at line 1065 of file STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rcc.c.
| void RCC_ITConfig | ( | uint8_t | RCC_IT, | 
| FunctionalState | NewState | ||
| ) | 
Enables or disables the specified RCC interrupts.
| RCC_IT | specifies the RCC interrupt sources to be enabled or disabled. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified RCC interrupts. This parameter can be: ENABLE or DISABLE. | 
| None | 
| RCC_IT | specifies the RCC interrupt sources to be enabled or disabled. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified RCC interrupts. This parameter can be: ENABLE or DISABLE. | 
| None | 
| RCC_IT | specifies the RCC interrupt sources to be enabled or disabled. This parameter can be any combination of the following values: 
 | 
| NewState | new state of the specified RCC interrupts. This parameter can be: ENABLE or DISABLE. | 
| None | 
| RCC_IT | specifies the RCC interrupt sources to be enabled or disabled. | 
For STM32_Connectivity_line_devices, this parameter can be any combination of the following values
For other_STM32_devices, this parameter can be any combination of the following values
| NewState | new state of the specified RCC interrupts. This parameter can be: ENABLE or DISABLE. | 
| None | 
Definition at line 2788 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_LSEConfig | ( | uint32_t | RCC_LSE | ) | 
Configures the External Low Speed oscillator (LSE).
| RCC_LSE | specifies the new state of the LSE. This parameter can be one of the following values: 
 | 
| None | 
Definition at line 354 of file stm32f30x_rcc.c.
| void RCC_LSEDriveConfig | ( | uint32_t | RCC_LSEDrive | ) | 
Configures the External Low Speed oscillator (LSE) drive capability.
| RCC_LSEDrive | specifies the new state of the LSE drive capability. This parameter can be one of the following values: 
 | 
| None | 
Definition at line 380 of file stm32f30x_rcc.c.
| void RCC_LSICmd | ( | FunctionalState | NewState | ) | 
Enables or disables the Internal Low Speed oscillator (LSI).
| NewState | new state of the LSI. This parameter can be: ENABLE or DISABLE. | 
| None | 
| NewState | new state of the LSI. This parameter can be: ENABLE or DISABLE. | 
| None | 
| NewState | new state of the LSI. This parameter can be: ENABLE or DISABLE. | 
| None | 
Definition at line 440 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_MCOConfig | ( | uint8_t | RCC_MCOSource, | 
| uint32_t | RCC_MCOPrescaler | ||
| ) | 
Selects the clock source to output on MCO pin (PA8) and the corresponding prescsaler.
| RCC_MCOSource | specifies the clock source to output. This parameter can be one of the following values: 
 | 
| RCC_MCOPrescaler | specifies the prescaler on MCO pin. This parameter can be one of the following values: 
 | 
| None | 
Definition at line 567 of file stm32f30x_rcc.c.
| void RCC_PCLK1Config | ( | uint32_t | RCC_HCLK | ) | 
Configures the Low Speed APB clock (PCLK1).
| RCC_HCLK | defines the APB1 clock divider. This clock is derived from the AHB clock (HCLK). This parameter can be one of the following values: 
 | 
| None | 
Definition at line 1234 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_PCLK2Config | ( | uint32_t | RCC_HCLK | ) | 
Configures the High Speed APB clock (PCLK2).
| RCC_HCLK | defines the APB2 clock divider. This clock is derived from the AHB clock (HCLK). This parameter can be one of the following values: 
 | 
| None | 
Definition at line 1265 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_PLLCmd | ( | FunctionalState | NewState | ) | 
Enables or disables the main PLL.
Enables or disables the PLL.
| NewState | new state of the main PLL. This parameter can be: ENABLE or DISABLE. | 
| None | 
| NewState | new state of the PLL. This parameter can be: ENABLE or DISABLE. | 
| None | Enables or disables the main PLL. | 
| NewState | new state of the PLL. This parameter can be: ENABLE or DISABLE. | 
| None | 
Definition at line 563 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_PLLConfig | ( | uint32_t | RCC_PLLSource, | 
| uint32_t | RCC_PLLMul | ||
| ) | 
Configures the PLL clock source and multiplication factor.
| RCC_PLLSource | specifies the PLL entry clock source. For STM32_Connectivity_line_devices or STM32_Value_line_devices, this parameter can be one of the following values: 
 | 
| RCC_PLLMul | specifies the PLL multiplication factor. For STM32_Connectivity_line_devices, this parameter can be RCC_PLLMul_x where x:{[4,9], 6_5} For other_STM32_devices, this parameter can be RCC_PLLMul_x where x:[2,16] | 
| None | 
| RCC_PLLSource | specifies the PLL entry clock source. This parameter can be one of the following values: 
 | 
| RCC_PLLMul | specifies the PLL multiplication factor, which drive the PLLVCO clock This parameter can be RCC_PLLMul_x where x:[2,16] | 
| None | 
Definition at line 379 of file stm32f10x_rcc.c.
| void RCC_PREDIV1Config | ( | uint32_t | RCC_PREDIV1_Div | ) | 
Configures the PREDIV1 division factor.
| RCC_PREDIV1_Div | specifies the PREDIV1 clock division factor. This parameter can be RCC_PREDIV1_Divx where x:[1,16] | 
| None | 
Definition at line 466 of file stm32f30x_rcc.c.
| void RCC_RTCCLKCmd | ( | FunctionalState | NewState | ) | 
Enables or disables the RTC clock.
| NewState | new state of the RTC clock. This parameter can be: ENABLE or DISABLE. | 
| None | 
| NewState | new state of the RTC clock. This parameter can be: ENABLE or DISABLE. | 
| None | 
Definition at line 1502 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_RTCCLKConfig | ( | uint32_t | RCC_RTCCLKSource | ) | 
Configures the RTC clock (RTCCLK).
| RCC_RTCCLKSource | specifies the RTC clock source. This parameter can be one of the following values: 
 | 
| None | 
| RCC_RTCCLKSource | specifies the RTC clock source. This parameter can be one of the following values: 
 | 
| None | 
| RCC_RTCCLKSource | specifies the RTC clock source. This parameter can be one of the following values: 
 | 
| None | 
Definition at line 1470 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_SYSCLKConfig | ( | uint32_t | RCC_SYSCLKSource | ) | 
Configures the system clock (SYSCLK).
| RCC_SYSCLKSource | specifies the clock source used as system clock. This parameter can be one of the following values: 
 | 
| None | 
| RCC_SYSCLKSource | specifies the clock source used as system clock. This parameter can be one of the following values: 
 | 
| None | 
| RCC_SYSCLKSource | specifies the clock source used as system clock source This parameter can be one of the following values: 
 | 
| None | 
| RCC_SYSCLKSource | specifies the clock source used as system clock. This parameter can be one of the following values: 
 | 
| None | 
Definition at line 1149 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
| void RCC_TIMCLKConfig | ( | uint32_t | RCC_TIMCLK | ) | 
Configures the TIMx clock sources(TIMCLK).
| RCC_TIMCLK | defines the TIMx clock source. This parameter can be one of the following values: 
 | 
| None | 
Definition at line 1311 of file stm32f30x_rcc.c.
| void RCC_USARTCLKConfig | ( | uint32_t | RCC_USARTCLK | ) | 
Configures the USART clock (USARTCLK).
| RCC_USARTCLK | defines the USART clock source. This clock is derived from the HSI or System clock. This parameter can be one of the following values: 
 | 
| None | 
Definition at line 1385 of file stm32f30x_rcc.c.
| void RCC_USBCLKConfig | ( | uint32_t | RCC_USBCLKSource | ) | 
Configures the USB clock (USBCLK).
| RCC_USBCLKSource | specifies the USB clock source. This clock is derived from the PLL output. This parameter can be one of the following values: 
 | 
| None | 
Definition at line 729 of file stm32f10x_rcc.c.
| ErrorStatus RCC_WaitForHSEStartUp | ( | void | ) | 
Waits for HSE start-up.
| None | 
| An | ErrorStatus enumeration value: 
 | 
| None | 
| An | ErrorStatus enumeration value: 
 | 
| None | 
| An | ErrorStatus enumuration value: 
 | 
Definition at line 308 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.