Peripheral clocks configuration functions. More...
Functions | |
void | RCC_ADCCLKConfig (uint32_t RCC_PLLCLK) |
Configures the ADC clock (ADCCLK). More... | |
void | RCC_AHB1PeriphClockCmd (uint32_t RCC_AHB1Periph, FunctionalState NewState) |
Enables or disables the AHB1 peripheral clock. More... | |
void | RCC_AHB1PeriphClockLPModeCmd (uint32_t RCC_AHB1Periph, FunctionalState NewState) |
Enables or disables the AHB1 peripheral clock during Low Power (Sleep) mode. More... | |
void | RCC_AHB1PeriphResetCmd (uint32_t RCC_AHB1Periph, FunctionalState NewState) |
Forces or releases AHB1 peripheral reset. More... | |
void | RCC_AHB2PeriphClockCmd (uint32_t RCC_AHB2Periph, FunctionalState NewState) |
Enables or disables the AHB2 peripheral clock. More... | |
void | RCC_AHB2PeriphClockLPModeCmd (uint32_t RCC_AHB2Periph, FunctionalState NewState) |
Enables or disables the AHB2 peripheral clock during Low Power (Sleep) mode. More... | |
void | RCC_AHB2PeriphResetCmd (uint32_t RCC_AHB2Periph, FunctionalState NewState) |
Forces or releases AHB2 peripheral reset. More... | |
void | RCC_AHB3PeriphClockCmd (uint32_t RCC_AHB3Periph, FunctionalState NewState) |
Enables or disables the AHB3 peripheral clock. More... | |
void | RCC_AHB3PeriphClockLPModeCmd (uint32_t RCC_AHB3Periph, FunctionalState NewState) |
Enables or disables the AHB3 peripheral clock during Low Power (Sleep) mode. More... | |
void | RCC_AHB3PeriphResetCmd (uint32_t RCC_AHB3Periph, FunctionalState NewState) |
Forces or releases AHB3 peripheral reset. 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_APB1PeriphClockLPModeCmd (uint32_t RCC_APB1Periph, FunctionalState NewState) |
Enables or disables the APB1 peripheral clock during Low Power (Sleep) mode. 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_APB2PeriphClockLPModeCmd (uint32_t RCC_APB2Periph, FunctionalState NewState) |
Enables or disables the APB2 peripheral clock during Low Power (Sleep) mode. 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_HRTIM1CLKConfig (uint32_t RCC_HRTIMCLK) |
Configures the HRTIM1 clock sources(HRTIM1CLK). 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_LSEModeConfig (uint8_t RCC_Mode) |
Configures the External Low Speed oscillator mode (LSE mode). More... | |
void | RCC_LTDCCLKDivConfig (uint32_t RCC_PLLSAIDivR) |
Configures the LTDC clock Divider coming from PLLSAI. 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_SAIPLLI2SClkDivConfig (uint32_t RCC_PLLI2SDivQ) |
Configures the SAI clock Divider coming from PLLI2S. More... | |
void | RCC_SAIPLLSAIClkDivConfig (uint32_t RCC_PLLSAIDivQ) |
Configures the SAI clock Divider coming from PLLSAI. More... | |
void | RCC_TIMCLKConfig (uint32_t RCC_TIMCLK) |
Configures the TIMx clock sources(TIMCLK). More... | |
void | RCC_TIMCLKPresConfig (uint32_t RCC_TIMCLKPrescaler) |
Configures the Timers clocks prescalers selection. 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... | |
Peripheral clocks configuration functions.
=============================================================================== ##### Peripheral clocks configuration functions ##### =============================================================================== [..] This section provide functions allowing to configure the Peripheral clocks. (#) The RTC clock which is derived from the LSI, LSE or HSE clock divided by 2 to 31. (#) After restart from Reset or wakeup from STANDBY, all peripherals are off except internal SRAM, Flash and JTAG. Before to start using a peripheral you have to enable its interface clock. You can do this using RCC_AHBPeriphClockCmd(), RCC_APB2PeriphClockCmd() and RCC_APB1PeriphClockCmd() functions. (#) To reset the peripherals configuration (to the default state after device reset) you can use RCC_AHBPeriphResetCmd(), RCC_APB2PeriphResetCmd() and RCC_APB1PeriphResetCmd() functions. (#) To further reduce power consumption in SLEEP mode the peripheral clocks can be disabled prior to executing the WFI or WFE instructions. You can do this using RCC_AHBPeriphClockLPModeCmd(), RCC_APB2PeriphClockLPModeCmd() and RCC_APB1PeriphClockLPModeCmd() functions.
=============================================================================== ##### Peripheral clocks configuration functions ##### =============================================================================== [..] This section provide functions allowing to configure the Peripheral clocks. (#) The RTC clock which is derived from the LSE, LSI or HSE_Div32 (HSE divided by 32). (#) After restart from Reset or wakeup from STANDBY, all peripherals are off except internal SRAM, Flash and SWD. Before to start using a peripheral you have to enable its interface clock. You can do this using RCC_AHBPeriphClockCmd(), RCC_APB2PeriphClockCmd() and RCC_APB1PeriphClockCmd() functions. (#) To reset the peripherals configuration (to the default state after device reset) you can use RCC_AHBPeriphResetCmd(), RCC_APB2PeriphResetCmd() and RCC_APB1PeriphResetCmd() functions.
void RCC_ADCCLKConfig | ( | uint32_t | RCC_PLLCLK | ) |
Configures the ADC clock (ADCCLK).
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 1235 of file stm32f30x_rcc.c.
void RCC_AHB1PeriphClockCmd | ( | uint32_t | RCC_AHB1Periph, |
FunctionalState | NewState | ||
) |
Enables or disables the AHB1 peripheral clock.
RCC_AHBPeriph | specifies the AHB1 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_AHBPeriph | specifies the AHB1 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 1885 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
void RCC_AHB1PeriphClockLPModeCmd | ( | uint32_t | RCC_AHB1Periph, |
FunctionalState | NewState | ||
) |
Enables or disables the AHB1 peripheral clock during Low Power (Sleep) mode.
RCC_AHBPeriph | specifies the AHB1 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_AHBPeriph | specifies the AHB1 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 2296 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
void RCC_AHB1PeriphResetCmd | ( | uint32_t | RCC_AHB1Periph, |
FunctionalState | NewState | ||
) |
Forces or releases AHB1 peripheral reset.
RCC_AHB1Periph | specifies the AHB1 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_AHB1Periph | specifies the AHB1 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 2094 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
void RCC_AHB2PeriphClockCmd | ( | uint32_t | RCC_AHB2Periph, |
FunctionalState | NewState | ||
) |
Enables or disables the AHB2 peripheral clock.
RCC_AHBPeriph | specifies the AHB2 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 1917 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
void RCC_AHB2PeriphClockLPModeCmd | ( | uint32_t | RCC_AHB2Periph, |
FunctionalState | NewState | ||
) |
Enables or disables the AHB2 peripheral clock during Low Power (Sleep) mode.
RCC_AHBPeriph | specifies the AHB2 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 2328 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
void RCC_AHB2PeriphResetCmd | ( | uint32_t | RCC_AHB2Periph, |
FunctionalState | NewState | ||
) |
Forces or releases AHB2 peripheral reset.
RCC_AHB2Periph | specifies the AHB2 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_AHB2Periph | specifies the AHB2 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 2123 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
void RCC_AHB3PeriphClockCmd | ( | uint32_t | RCC_AHB3Periph, |
FunctionalState | NewState | ||
) |
Enables or disables the AHB3 peripheral clock.
RCC_AHBPeriph | specifies the AHB3 peripheral to gates its clock. This parameter must be: RCC_AHB3Periph_FSMC |
NewState | new state of the specified peripheral clock. This parameter can be: ENABLE or DISABLE. |
None |
Definition at line 1190 of file STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rcc.c.
void RCC_AHB3PeriphClockLPModeCmd | ( | uint32_t | RCC_AHB3Periph, |
FunctionalState | NewState | ||
) |
Enables or disables the AHB3 peripheral clock during Low Power (Sleep) mode.
RCC_AHBPeriph | specifies the AHB3 peripheral to gates its clock. This parameter must be: RCC_AHB3Periph_FSMC |
NewState | new state of the specified peripheral clock. This parameter can be: ENABLE or DISABLE. |
None |
Definition at line 1572 of file STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rcc.c.
void RCC_AHB3PeriphResetCmd | ( | uint32_t | RCC_AHB3Periph, |
FunctionalState | NewState | ||
) |
Forces or releases AHB3 peripheral reset.
RCC_AHB3Periph | specifies the AHB3 peripheral to reset. This parameter must be: RCC_AHB3Periph_FSMC |
NewState | new state of the specified peripheral reset. This parameter can be: ENABLE or DISABLE. |
None |
Definition at line 1378 of file STM32F4xx_StdPeriph_Driver/src/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. 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 1545 of file stm32f30x_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 |
Definition at line 2004 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
void RCC_APB1PeriphClockLPModeCmd | ( | uint32_t | RCC_APB1Periph, |
FunctionalState | NewState | ||
) |
Enables or disables the APB1 peripheral clock during Low Power (Sleep) mode.
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 2415 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 |
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 |
Definition at line 2051 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
void RCC_APB2PeriphClockLPModeCmd | ( | uint32_t | RCC_APB2Periph, |
FunctionalState | NewState | ||
) |
Enables or disables the APB2 peripheral clock during Low Power (Sleep) mode.
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 2462 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 |
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 |
Definition at line 1519 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_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_LSEModeConfig | ( | uint8_t | RCC_Mode | ) |
Configures the External Low Speed oscillator mode (LSE mode).
Mode | specifies the LSE mode. This parameter can be one of the following values:
|
None |
Definition at line 2486 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
void RCC_LTDCCLKDivConfig | ( | uint32_t | RCC_PLLSAIDivR | ) |
Configures the LTDC clock Divider coming from PLLSAI.
RCC_PLLSAIDivR | specifies the PLLSAI division factor for LTDC clock . LTDC clock frequency = f(PLLSAI_R) / RCC_PLLSAIDivR This parameter can be one of the following values:
|
None |
Definition at line 1806 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_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 |
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 |
Definition at line 1470 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
void RCC_SAIPLLI2SClkDivConfig | ( | uint32_t | RCC_PLLI2SDivQ | ) |
Configures the SAI clock Divider coming from PLLI2S.
RCC_PLLI2SDivQ | specifies the PLLI2S division factor for SAI1 clock . This parameter must be a number between 1 and 32. SAI1 clock frequency = f(PLLI2S_Q) / RCC_PLLI2SDivQ |
None |
Definition at line 1738 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.c.
void RCC_SAIPLLSAIClkDivConfig | ( | uint32_t | RCC_PLLSAIDivQ | ) |
Configures the SAI clock Divider coming from PLLSAI.
RCC_PLLSAIDivQ | specifies the PLLSAI division factor for SAI1 clock . This parameter must be a number between 1 and 32. SAI1 clock frequency = f(PLLSAI_Q) / RCC_PLLSAIDivQ |
None |
Definition at line 1770 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_TIMCLKPresConfig | ( | uint32_t | RCC_TIMCLKPrescaler | ) |
Configures the Timers clocks prescalers selection.
RCC_TIMCLKPrescaler | : specifies the Timers clocks prescalers selection This parameter can be one of the following values:
|
None |
RCC_TIMCLKPrescaler | : specifies the Timers clocks prescalers selection This parameter can be one of the following values:
|
None |
Definition at line 1843 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_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 1430 of file stm32f30x_rcc.c.