Internal and external clocks, PLL, CSS and MCO configuration functions.
More...
|
void | RCC_AdjustHSICalibrationValue (uint8_t HSICalibrationValue) |
| Adjusts the Internal High Speed oscillator (HSI) calibration value. 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_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_LSEConfig (uint32_t RCC_LSE) |
| Configures the External Low Speed oscillator (LSE). More...
|
|
void | RCC_LSEConfig (uint8_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_MCO1Config (uint32_t RCC_MCO1Source, uint32_t RCC_MCO1Div) |
| Selects the clock source to output on MCO1 pin(PA8). More...
|
|
void | RCC_MCO2Config (uint32_t RCC_MCO2Source, uint32_t RCC_MCO2Div) |
| Selects the clock source to output on MCO2 pin(PC9). 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_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_PLLConfig (uint32_t RCC_PLLSource, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP, uint32_t PLLQ) |
| Configures the main PLL clock source, multiplication and division factors. More...
|
|
void | RCC_PLLI2SCmd (FunctionalState NewState) |
| Enables or disables the PLLI2S. More...
|
|
void | RCC_PLLI2SConfig (uint32_t PLLI2SN, uint32_t PLLI2SR) |
| Configures the PLLI2S clock multiplication and division factors. More...
|
|
void | RCC_PLLSAICmd (FunctionalState NewState) |
| Enables or disables the PLLSAI. More...
|
|
void | RCC_PREDIV1Config (uint32_t RCC_PREDIV1_Div) |
| Configures the PREDIV1 division factor. More...
|
|
ErrorStatus | RCC_WaitForHSEStartUp (void) |
| Waits for HSE start-up. More...
|
|
Internal and external clocks, PLL, CSS and MCO configuration functions.
===================================================================================
##### Internal and external clocks, PLL, CSS and MCO configuration functions #####
===================================================================================
[..]
This section provide functions allowing to configure the internal/external clocks,
PLLs, CSS and MCO pins.
(#) HSI (high-speed internal), 16 MHz factory-trimmed RC used directly or through
the PLL as System clock source.
(#) LSI (low-speed internal), 32 KHz low consumption RC used as IWDG and/or RTC
clock source.
(#) HSE (high-speed external), 4 to 26 MHz crystal oscillator used directly or
through the PLL as System clock source. Can be used also as RTC clock source.
(#) LSE (low-speed external), 32 KHz oscillator used as RTC clock source.
(#) PLL (clocked by HSI or HSE), featuring two different output clocks:
(++) The first output is used to generate the high speed system clock (up to 168 MHz)
(++) The second output is used to generate the clock for the USB OTG FS (48 MHz),
the random analog generator (<=48 MHz) and the SDIO (<= 48 MHz).
(#) PLLI2S (clocked by HSI or HSE), used to generate an accurate clock to achieve
high-quality audio performance on the I2S interface or SAI interface in case
of STM32F429x/439x devices.
(#) PLLSAI clocked by (HSI or HSE), used to generate an accurate clock to SAI
interface and LCD TFT controller available only for STM32F42xxx/43xxx/446xx/469xx/479xx devices.
(#) CSS (Clock security system), once enable and if a HSE clock failure occurs
(HSE used directly or through PLL as System clock source), the System clock
is automatically switched to HSI and an interrupt is generated if enabled.
The interrupt is linked to the Cortex-M4 NMI (Non-Maskable Interrupt)
exception vector.
(#) MCO1 (microcontroller clock output), used to output HSI, LSE, HSE or PLL
clock (through a configurable prescaler) on PA8 pin.
(#) MCO2 (microcontroller clock output), used to output HSE, PLL, SYSCLK or PLLI2S
clock (through a configurable prescaler) on PC9 pin.
===================================================================================
##### Internal and external clocks, PLL, CSS and MCO configuration functions #####
===================================================================================
[..]
This section provide functions allowing to configure the internal/external clocks,
PLLs, CSS and MCO pins.
(#) HSI (high-speed internal), 16 MHz factory-trimmed RC used directly or through
the PLL as System clock source.
(#) LSI (low-speed internal), 32 KHz low consumption RC used as IWDG and/or RTC
clock source.
(#) HSE (high-speed external), 4 to 26 MHz crystal oscillator used directly or
through the PLL as System clock source. Can be used also as RTC clock source.
(#) LSE (low-speed external), 32 KHz oscillator used as RTC clock source.
(#) PLL (clocked by HSI or HSE), featuring two different output clocks:
(++) The first output is used to generate the high speed system clock (up to 168 MHz)
(++) The second output is used to generate the clock for the USB OTG FS (48 MHz),
the random analog generator (<=48 MHz) and the SDIO (<= 48 MHz).
(#) PLLI2S (clocked by HSI or HSE), used to generate an accurate clock to achieve
high-quality audio performance on the I2S interface.
(#) CSS (Clock security system), once enable and if a HSE clock failure occurs
(HSE used directly or through PLL as System clock source), the System clock
is automatically switched to HSI and an interrupt is generated if enabled.
The interrupt is linked to the Cortex-M4 NMI (Non-Maskable Interrupt)
exception vector.
(#) MCO1 (microcontroller clock output), used to output HSI, LSE, HSE or PLL
clock (through a configurable prescaler) on PA8 pin.
(#) MCO2 (microcontroller clock output), used to output HSE, PLL, SYSCLK or PLLI2S
clock (through a configurable prescaler) on PC9 pin.
===============================================================================
##### Internal-external clocks, PLL, CSS and MCO configuration functions #####
===============================================================================
[..] This section provides functions allowing to configure the internal/external
clocks, PLL, CSS and MCO.
(#) HSI (high-speed internal), 8 MHz factory-trimmed RC used directly
or through the PLL as System clock source.
The HSI clock can be used also to clock the USART and I2C peripherals.
(#) LSI (low-speed internal), 40 KHz low consumption RC used as IWDG and/or RTC
clock source.
(#) HSE (high-speed external), 4 to 32 MHz crystal oscillator used directly or
through the PLL as System clock source. Can be used also as RTC clock source.
(#) LSE (low-speed external), 32 KHz oscillator used as RTC clock source.
LSE can be used also to clock the USART peripherals.
(#) PLL (clocked by HSI or HSE), for System clock.
(#) CSS (Clock security system), once enabled and if a HSE clock failure occurs
(HSE used directly or through PLL as System clock source), the System clock
is automatically switched to HSI and an interrupt is generated if enabled.
The interrupt is linked to the Cortex-M4 NMI (Non-Maskable Interrupt)
exception vector.
(#) MCO (microcontroller clock output), used to output SYSCLK, HSI, HSE, LSI, LSE,
PLL clock on PA8 pin.
void RCC_AdjustHSICalibrationValue |
( |
uint8_t |
HSICalibrationValue | ) |
|
Adjusts the Internal High Speed oscillator (HSI) calibration value.
- Note
- The calibration is used to compensate for the variations in voltage and temperature that influence the frequency of the internal HSI RC.
- Parameters
-
HSICalibrationValue | specifies the calibration trimming value. This parameter must be a number between 0 and 0x1F. |
- Return values
-
- Note
- The calibration is used to compensate for the variations in voltage and temperature that influence the frequency of the internal HSI RC. Refer to the Application Note AN3300 for more details on how to calibrate the HSI.
- Parameters
-
HSICalibrationValue | specifies the HSI calibration trimming value. This parameter must be a number between 0 and 0x1F. |
- Return values
-
Definition at line 339 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
Enables or disables the Clock Security System.
- Note
- If a failure is detected on the HSE oscillator clock, this oscillator is automatically disabled and an interrupt is generated to inform the software about the failure (Clock Security System Interrupt, CSSI), allowing the MCU to perform rescue operations. The CSSI is linked to the Cortex-M4 NMI (Non-Maskable Interrupt) exception vector.
- Parameters
-
NewState | new state of the Clock Security System. This parameter can be: ENABLE or DISABLE. |
- Return values
-
Definition at line 879 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
Resets the RCC clock configuration to the default reset state.
- Note
- The default reset state of the clock configuration is given below:
- HSI ON and used as system clock source
- HSE, PLL and PLLI2S OFF
- AHB, APB1 and APB2 prescaler set to 1.
- CSS, MCO1 and MCO2 OFF
- All interrupts disabled
-
This function doesn't modify the configuration of the
- Peripheral clocks
- LSI, LSE and RTC clocks
- Parameters
-
- Return values
-
- Note
- The default reset state of the clock configuration is given below:
-
HSI ON and used as system clock source
-
HSE and PLL OFF
-
AHB, APB1 and APB2 prescalers set to 1.
-
CSS and MCO OFF
-
All interrupts disabled
-
However, this function doesn't modify the configuration of the
-
Peripheral clocks
-
LSI, LSE and RTC clocks
- Parameters
-
- Return values
-
Definition at line 225 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
void RCC_HSEConfig |
( |
uint8_t |
RCC_HSE | ) |
|
Configures the External High Speed oscillator (HSE).
- Note
- After enabling the HSE (RCC_HSE_ON or RCC_HSE_Bypass), the application software should wait on HSERDY flag to be set indicating that HSE clock is stable and can be used to clock the PLL and/or system clock.
-
HSE state can not be changed if it is used directly or through the PLL as system clock. In this case, you have to select another source of the system clock then change the HSE state (ex. disable it).
-
The HSE is stopped by hardware when entering STOP and STANDBY modes.
-
This function reset the CSSON bit, so if the Clock security system(CSS) was previously enabled you have to enable it again after calling this function.
- Parameters
-
RCC_HSE | specifies the new state of the HSE. This parameter can be one of the following values:
- RCC_HSE_OFF: turn OFF the HSE oscillator, HSERDY flag goes low after 6 HSE oscillator clock cycles.
- RCC_HSE_ON: turn ON the HSE oscillator
- RCC_HSE_Bypass: HSE oscillator bypassed with external clock
|
- Return values
-
- Note
- After enabling the HSE (RCC_HSE_ON or RCC_HSE_Bypass), the application software should wait on HSERDY flag to be set indicating that HSE clock is stable and can be used to clock the PLL and/or system clock.
-
HSE state can not be changed if it is used directly or through the PLL as system clock. In this case, you have to select another source of the system clock then change the HSE state (ex. disable it).
-
The HSE is stopped by hardware when entering STOP and STANDBY modes.
-
This function resets the CSSON bit, so if the Clock security system(CSS) was previously enabled you have to enable it again after calling this function.
- Parameters
-
RCC_HSE | specifies the new state of the HSE. This parameter can be one of the following values:
- RCC_HSE_OFF: turn OFF the HSE oscillator, HSERDY flag goes low after 6 HSE oscillator clock cycles.
- RCC_HSE_ON: turn ON the HSE oscillator
- RCC_HSE_Bypass: HSE oscillator bypassed with external clock
|
- Return values
-
Definition at line 284 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
Enables or disables the Internal High Speed oscillator (HSI).
- Note
- The HSI is stopped by hardware when entering STOP and STANDBY modes. It is used (enabled by hardware) as system clock source after startup from Reset, wakeup from STOP and STANDBY mode, or in case of failure of the HSE used directly or indirectly as system clock (if the Clock Security System CSS is enabled).
-
HSI can not be stopped if it is used as system clock source. In this case, you have to select another source of the system clock then stop the HSI.
-
After enabling the HSI, the application software should wait on HSIRDY flag to be set indicating that HSI clock is stable and can be used as system clock source.
- Parameters
-
NewState | new state of the HSI. This parameter can be: ENABLE or DISABLE. |
- Note
- When the HSI is stopped, HSIRDY flag goes low after 6 HSI oscillator clock cycles.
- Return values
-
- Note
- After enabling the HSI, the application software should wait on HSIRDY flag to be set indicating that HSI clock is stable and can be used to clock the PLL and/or system clock.
-
HSI can not be stopped if it is used directly or through the PLL as system clock. In this case, you have to select another source of the system clock then stop the HSI.
-
The HSI is stopped by hardware when entering STOP and STANDBY modes.
-
When the HSI is stopped, HSIRDY flag goes low after 6 HSI oscillator clock cycles.
- Parameters
-
NewState | new state of the HSI. This parameter can be: ENABLE or DISABLE. |
- Return values
-
Definition at line 375 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
void RCC_LSEConfig |
( |
uint32_t |
RCC_LSE | ) |
|
Configures the External Low Speed oscillator (LSE).
- Note
- As the LSE is in the Backup domain and write access is denied to this domain after reset, you have to enable write access using PWR_BackupAccessCmd(ENABLE) function before to configure the LSE (to be done once after reset).
-
After enabling the LSE (RCC_LSE_ON or RCC_LSE_Bypass), the application software should wait on LSERDY flag to be set indicating that LSE clock is stable and can be used to clock the RTC.
- Parameters
-
RCC_LSE | specifies the new state of the LSE. This parameter can be one of the following values:
- RCC_LSE_OFF: turn OFF the LSE oscillator, LSERDY flag goes low after 6 LSE oscillator clock cycles.
- RCC_LSE_ON: turn ON the LSE oscillator
- RCC_LSE_Bypass: LSE oscillator bypassed with external clock
|
- Return values
-
Definition at line 354 of file stm32f30x_rcc.c.
void RCC_LSEConfig |
( |
uint8_t |
RCC_LSE | ) |
|
Configures the External Low Speed oscillator (LSE).
- Note
- As the LSE is in the Backup domain and write access is denied to this domain after reset, you have to enable write access using PWR_BackupAccessCmd(ENABLE) function before to configure the LSE (to be done once after reset).
-
After enabling the LSE (RCC_LSE_ON or RCC_LSE_Bypass), the application software should wait on LSERDY flag to be set indicating that LSE clock is stable and can be used to clock the RTC.
- Parameters
-
RCC_LSE | specifies the new state of the LSE. This parameter can be one of the following values:
- RCC_LSE_OFF: turn OFF the LSE oscillator, LSERDY flag goes low after 6 LSE oscillator clock cycles.
- RCC_LSE_ON: turn ON the LSE oscillator
- RCC_LSE_Bypass: LSE oscillator bypassed with external clock
|
- Return values
-
Definition at line 400 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
void RCC_LSEDriveConfig |
( |
uint32_t |
RCC_LSEDrive | ) |
|
Configures the External Low Speed oscillator (LSE) drive capability.
- Parameters
-
RCC_LSEDrive | specifies the new state of the LSE drive capability. This parameter can be one of the following values:
- RCC_LSEDrive_Low: LSE oscillator low drive capability.
- RCC_LSEDrive_MediumLow: LSE oscillator medium low drive capability.
- RCC_LSEDrive_MediumHigh: LSE oscillator medium high drive capability.
- RCC_LSEDrive_High: LSE oscillator high drive capability.
|
- Return values
-
Definition at line 380 of file stm32f30x_rcc.c.
Enables or disables the Internal Low Speed oscillator (LSI).
- Note
- After enabling the LSI, the application software should wait on LSIRDY flag to be set indicating that LSI clock is stable and can be used to clock the IWDG and/or the RTC.
-
LSI can not be disabled if the IWDG is running.
- Parameters
-
NewState | new state of the LSI. This parameter can be: ENABLE or DISABLE. |
- Note
- When the LSI is stopped, LSIRDY flag goes low after 6 LSI oscillator clock cycles.
- Return values
-
- Note
- After enabling the LSI, the application software should wait on LSIRDY flag to be set indicating that LSI clock is stable and can be used to clock the IWDG and/or the RTC.
-
LSI can not be disabled if the IWDG is running.
-
When the LSI is stopped, LSIRDY flag goes low after 6 LSI oscillator clock cycles.
- Parameters
-
NewState | new state of the LSI. This parameter can be: ENABLE or DISABLE. |
- Return values
-
Definition at line 440 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
void RCC_MCO1Config |
( |
uint32_t |
RCC_MCO1Source, |
|
|
uint32_t |
RCC_MCO1Div |
|
) |
| |
Selects the clock source to output on MCO1 pin(PA8).
- Note
- PA8 should be configured in alternate function mode.
- Parameters
-
RCC_MCO1Source | specifies the clock source to output. This parameter can be one of the following values:
- RCC_MCO1Source_HSI: HSI clock selected as MCO1 source
- RCC_MCO1Source_LSE: LSE clock selected as MCO1 source
- RCC_MCO1Source_HSE: HSE clock selected as MCO1 source
- RCC_MCO1Source_PLLCLK: main PLL clock selected as MCO1 source
|
RCC_MCO1Div | specifies the MCO1 prescaler. This parameter can be one of the following values:
- RCC_MCO1Div_1: no division applied to MCO1 clock
- RCC_MCO1Div_2: division by 2 applied to MCO1 clock
- RCC_MCO1Div_3: division by 3 applied to MCO1 clock
- RCC_MCO1Div_4: division by 4 applied to MCO1 clock
- RCC_MCO1Div_5: division by 5 applied to MCO1 clock
|
- Return values
-
Definition at line 904 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
void RCC_MCO2Config |
( |
uint32_t |
RCC_MCO2Source, |
|
|
uint32_t |
RCC_MCO2Div |
|
) |
| |
Selects the clock source to output on MCO2 pin(PC9).
- Note
- PC9 should be configured in alternate function mode.
- Parameters
-
RCC_MCO2Source | specifies the clock source to output. This parameter can be one of the following values:
- RCC_MCO2Source_SYSCLK: System clock (SYSCLK) selected as MCO2 source
- RCC_MCO2SOURCE_PLLI2SCLK: PLLI2S clock selected as MCO2 source, available for all STM32F4 devices except STM32F410xx
- RCC_MCO2SOURCE_I2SCLK: I2SCLK clock selected as MCO2 source, available only for STM32F410xx devices
- RCC_MCO2Source_HSE: HSE clock selected as MCO2 source
- RCC_MCO2Source_PLLCLK: main PLL clock selected as MCO2 source
|
RCC_MCO2Div | specifies the MCO2 prescaler. This parameter can be one of the following values:
- RCC_MCO2Div_1: no division applied to MCO2 clock
- RCC_MCO2Div_2: division by 2 applied to MCO2 clock
- RCC_MCO2Div_3: division by 3 applied to MCO2 clock
- RCC_MCO2Div_4: division by 4 applied to MCO2 clock
- RCC_MCO2Div_5: division by 5 applied to MCO2 clock
|
- Note
- For STM32F410xx devices to output I2SCLK clock on MCO2 you should have at last one of the SPI clocks enabled (SPI1, SPI2 or SPI5).
- Return values
-
- Note
- PC9 should be configured in alternate function mode.
- Parameters
-
RCC_MCO2Source | specifies the clock source to output. This parameter can be one of the following values:
- RCC_MCO2Source_SYSCLK: System clock (SYSCLK) selected as MCO2 source
- RCC_MCO2Source_PLLI2SCLK: PLLI2S clock selected as MCO2 source
- RCC_MCO2Source_HSE: HSE clock selected as MCO2 source
- RCC_MCO2Source_PLLCLK: main PLL clock selected as MCO2 source
|
RCC_MCO2Div | specifies the MCO2 prescaler. This parameter can be one of the following values:
- RCC_MCO2Div_1: no division applied to MCO2 clock
- RCC_MCO2Div_2: division by 2 applied to MCO2 clock
- RCC_MCO2Div_3: division by 3 applied to MCO2 clock
- RCC_MCO2Div_4: division by 4 applied to MCO2 clock
- RCC_MCO2Div_5: division by 5 applied to MCO2 clock
|
- Return values
-
Definition at line 949 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.
- Note
- PA8 should be configured in alternate function mode.
- Parameters
-
RCC_MCOSource | specifies the clock source to output. This parameter can be one of the following values:
- RCC_MCOSource_NoClock: No clock selected.
- RCC_MCOSource_HSI14: HSI14 oscillator clock selected.
- RCC_MCOSource_LSI: LSI oscillator clock selected.
- RCC_MCOSource_LSE: LSE oscillator clock selected.
- RCC_MCOSource_SYSCLK: System clock selected.
- RCC_MCOSource_HSI: HSI oscillator clock selected.
- RCC_MCOSource_HSE: HSE oscillator clock selected.
- RCC_MCOSource_PLLCLK_Div2: PLL clock divided by 2 selected.
- RCC_MCOSource_PLLCLK: PLL clock selected.
- RCC_MCOSource_HSI48: HSI48 clock selected.
|
RCC_MCOPrescaler | specifies the prescaler on MCO pin. This parameter can be one of the following values:
- RCC_MCOPrescaler_1: MCO clock is divided by 1.
- RCC_MCOPrescaler_2: MCO clock is divided by 2.
- RCC_MCOPrescaler_4: MCO clock is divided by 4.
- RCC_MCOPrescaler_8: MCO clock is divided by 8.
- RCC_MCOPrescaler_16: MCO clock is divided by 16.
- RCC_MCOPrescaler_32: MCO clock is divided by 32.
- RCC_MCOPrescaler_64: MCO clock is divided by 64.
- RCC_MCOPrescaler_128: MCO clock is divided by 128.
|
- Return values
-
Definition at line 567 of file stm32f30x_rcc.c.
Enables or disables the main PLL.
Enables or disables the PLL.
- Note
- After enabling the main PLL, the application software should wait on PLLRDY flag to be set indicating that PLL clock is stable and can be used as system clock source.
-
The main PLL can not be disabled if it is used as system clock source
-
The main PLL is disabled by hardware when entering STOP and STANDBY modes.
- Parameters
-
NewState | new state of the main PLL. This parameter can be: ENABLE or DISABLE. |
- Return values
-
- Note
- After enabling the PLL, the application software should wait on PLLRDY flag to be set indicating that PLL clock is stable and can be used as system clock source.
-
The PLL can not be disabled if it is used as system clock source
-
The PLL is disabled by hardware when entering STOP and STANDBY modes.
- Parameters
-
NewState | new state of the PLL. This parameter can be: ENABLE or DISABLE. |
- Return values
-
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.
- Note
- This function must be used only when the PLL is disabled.
-
The minimum input clock frequency for PLL is 2 MHz (when using HSE as PLL source).
- Parameters
-
RCC_PLLSource | specifies the PLL entry clock source. This parameter can be one of the following values:
- RCC_PLLSource_HSI_Div2: HSI oscillator clock divided by 2 selected as PLL clock entry
- RCC_PLLSource_PREDIV1: PREDIV1 clock selected as PLL clock source
|
RCC_PLLMul | specifies the PLL multiplication factor, which drive the PLLVCO clock This parameter can be RCC_PLLMul_x where x:[2,16] |
- Return values
-
Definition at line 427 of file stm32f30x_rcc.c.
void RCC_PLLConfig |
( |
uint32_t |
RCC_PLLSource, |
|
|
uint32_t |
PLLM, |
|
|
uint32_t |
PLLN, |
|
|
uint32_t |
PLLP, |
|
|
uint32_t |
PLLQ |
|
) |
| |
Configures the main PLL clock source, multiplication and division factors.
- Note
- This function must be used only when the main PLL is disabled.
- Parameters
-
RCC_PLLSource | specifies the PLL entry clock source. This parameter can be one of the following values:
- RCC_PLLSource_HSI: HSI oscillator clock selected as PLL clock entry
- RCC_PLLSource_HSE: HSE oscillator clock selected as PLL clock entry
|
- Note
- This clock source (RCC_PLLSource) is common for the main PLL and PLLI2S.
- Parameters
-
PLLM | specifies the division factor for PLL VCO input clock This parameter must be a number between 0 and 63. |
- Note
- You have to set the PLLM parameter correctly to ensure that the VCO input frequency ranges from 1 to 2 MHz. It is recommended to select a frequency of 2 MHz to limit PLL jitter.
- Parameters
-
PLLN | specifies the multiplication factor for PLL VCO output clock This parameter must be a number between 192 and 432. |
- Note
- You have to set the PLLN parameter correctly to ensure that the VCO output frequency is between 192 and 432 MHz.
- Parameters
-
PLLP | specifies the division factor for main system clock (SYSCLK) This parameter must be a number in the range {2, 4, 6, or 8}. |
- Note
- You have to set the PLLP parameter correctly to not exceed 168 MHz on the System clock frequency.
- Parameters
-
PLLQ | specifies the division factor for OTG FS, SDIO and RNG clocks This parameter must be a number between 4 and 15. |
- Note
- If the USB OTG FS is used in your application, you have to set the PLLQ parameter correctly to have 48 MHz clock for the USB. However, the SDIO and RNG need a frequency lower than or equal to 48 MHz to work correctly.
- Return values
-
Definition at line 454 of file STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rcc.c.
Enables or disables the PLLI2S.
- Note
- The PLLI2S is disabled by hardware when entering STOP and STANDBY modes.
- Parameters
-
NewState | new state of the PLLI2S. This parameter can be: ENABLE or DISABLE. |
- Return values
-
Definition at line 732 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
void RCC_PLLI2SConfig |
( |
uint32_t |
PLLI2SN, |
|
|
uint32_t |
PLLI2SR |
|
) |
| |
Configures the PLLI2S clock multiplication and division factors.
- Note
- This function must be used only when the PLLI2S is disabled.
-
PLLI2S clock source is common with the main PLL (configured in RCC_PLLConfig function )
- Parameters
-
PLLI2SN | specifies the multiplication factor for PLLI2S VCO output clock This parameter must be a number between 192 and 432. |
- Note
- You have to set the PLLI2SN parameter correctly to ensure that the VCO output frequency is between 192 and 432 MHz.
- Parameters
-
PLLI2SR | specifies the division factor for I2S clock This parameter must be a number between 2 and 7. |
- Note
- You have to set the PLLI2SR parameter correctly to not exceed 192 MHz on the I2S clock frequency.
- Return values
-
Definition at line 503 of file STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rcc.c.
Enables or disables the PLLSAI.
- Note
- This function can be used only for STM32F42xxx/43xxx/446xx/469xx/479xx devices
-
The PLLSAI is disabled by hardware when entering STOP and STANDBY modes.
- Parameters
-
NewState | new state of the PLLSAI. This parameter can be: ENABLE or DISABLE. |
- Return values
-
Definition at line 861 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
void RCC_PREDIV1Config |
( |
uint32_t |
RCC_PREDIV1_Div | ) |
|
Configures the PREDIV1 division factor.
- Note
- This function must be used only when the PLL is disabled.
- Parameters
-
RCC_PREDIV1_Div | specifies the PREDIV1 clock division factor. This parameter can be RCC_PREDIV1_Divx where x:[1,16] |
- Return values
-
Definition at line 466 of file stm32f30x_rcc.c.
Waits for HSE start-up.
- Note
- This functions waits on HSERDY flag to be set and return SUCCESS if this flag is set, otherwise returns ERROR if the timeout is reached and this flag is not set. The timeout value is defined by the constant HSE_STARTUP_TIMEOUT in stm32f4xx.h file. You can tailor it depending on the HSE crystal used in your application.
- Parameters
-
- Return values
-
An | ErrorStatus enumeration value:
- SUCCESS: HSE oscillator is stable and ready to use
- ERROR: HSE oscillator not yet ready
|
- Note
- This function waits on HSERDY flag to be set and return SUCCESS if this flag is set, otherwise returns ERROR if the timeout is reached and this flag is not set. The timeout value is defined by the constant HSE_STARTUP_TIMEOUT in stm32f30x.h file. You can tailor it depending on the HSE crystal used in your application.
- Parameters
-
- Return values
-
An | ErrorStatus enumeration value:
- SUCCESS: HSE oscillator is stable and ready to use
- ERROR: HSE oscillator not yet ready
|
Definition at line 308 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.