Modules | Functions
Collaboration diagram for RCC_Private_Functions:

Modules

 Internal and external clocks, PLL, CSS and MCO configuration functions
 Internal and external clocks, PLL, CSS and MCO configuration functions.
 
 System AHB and APB busses clocks configuration functions
 System, AHB and APB busses clocks configuration functions.
 
 Peripheral clocks configuration functions
 Peripheral clocks configuration functions.
 
 Interrupts and flags management functions
 Interrupts and flags management functions.
 

Functions

void RCC_ADCCLKConfig (uint32_t RCC_PCLK2)
 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_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. 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. 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_HSEConfig (uint32_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_ITConfig (uint8_t RCC_IT, FunctionalState NewState)
 Enables or disables the specified RCC interrupts. More...
 
void RCC_LSEConfig (uint8_t RCC_LSE)
 Configures the External Low Speed oscillator (LSE). More...
 
void RCC_LSICmd (FunctionalState NewState)
 Enables or disables the Internal Low Speed oscillator (LSI). More...
 
void RCC_MCOConfig (uint8_t RCC_MCO)
 Selects the clock source to output on MCO pin. 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 PLL. More...
 
void RCC_PLLConfig (uint32_t RCC_PLLSource, uint32_t RCC_PLLMul)
 Configures the PLL clock source and multiplication 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_USBCLKConfig (uint32_t RCC_USBCLKSource)
 Configures the USB clock (USBCLK). More...
 
ErrorStatus RCC_WaitForHSEStartUp (void)
 Waits for HSE start-up. More...
 

Detailed Description

Function Documentation

void RCC_ADCCLKConfig ( uint32_t  RCC_PCLK2)

Configures the ADC clock (ADCCLK).

Parameters
RCC_PCLK2defines the ADC clock divider. This clock is derived from the APB2 clock (PCLK2). This parameter can be one of the following values:
  • RCC_PCLK2_Div2: ADC clock = PCLK2/2
  • RCC_PCLK2_Div4: ADC clock = PCLK2/4
  • RCC_PCLK2_Div6: ADC clock = PCLK2/6
  • RCC_PCLK2_Div8: ADC clock = PCLK2/8
Return 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.

Parameters
HSICalibrationValuespecifies the calibration trimming value. This parameter must be a number between 0 and 0x1F.
Return values
None

Definition at line 335 of file stm32f10x_rcc.c.

void RCC_AHBPeriphClockCmd ( uint32_t  RCC_AHBPeriph,
FunctionalState  NewState 
)

Enables or disables the AHB peripheral clock.

Parameters
RCC_AHBPeriphspecifies the AHB peripheral to gates its clock.

For STM32_Connectivity_line_devices, this parameter can be any combination of the following values:

  • RCC_AHBPeriph_DMA1
  • RCC_AHBPeriph_DMA2
  • RCC_AHBPeriph_SRAM
  • RCC_AHBPeriph_FLITF
  • RCC_AHBPeriph_CRC
  • RCC_AHBPeriph_OTG_FS
  • RCC_AHBPeriph_ETH_MAC
  • RCC_AHBPeriph_ETH_MAC_Tx
  • RCC_AHBPeriph_ETH_MAC_Rx

For other_STM32_devices, this parameter can be any combination of the following values:

  • RCC_AHBPeriph_DMA1
  • RCC_AHBPeriph_DMA2
  • RCC_AHBPeriph_SRAM
  • RCC_AHBPeriph_FLITF
  • RCC_AHBPeriph_CRC
  • RCC_AHBPeriph_FSMC
  • RCC_AHBPeriph_SDIO
Note
SRAM and FLITF clock can be disabled only during sleep mode.
Parameters
NewStatenew state of the specified peripheral clock. This parameter can be: ENABLE or DISABLE.
Return values
None

Definition at line 1065 of file stm32f10x_rcc.c.

void RCC_APB1PeriphClockCmd ( uint32_t  RCC_APB1Periph,
FunctionalState  NewState 
)

Enables or disables the Low Speed APB (APB1) peripheral clock.

Parameters
RCC_APB1Periphspecifies the APB1 peripheral to gates its clock. This parameter can be any combination of the following values:
  • RCC_APB1Periph_TIM2, RCC_APB1Periph_TIM3, RCC_APB1Periph_TIM4, RCC_APB1Periph_TIM5, RCC_APB1Periph_TIM6, RCC_APB1Periph_TIM7, RCC_APB1Periph_WWDG, RCC_APB1Periph_SPI2, RCC_APB1Periph_SPI3, RCC_APB1Periph_USART2, RCC_APB1Periph_USART3, RCC_APB1Periph_USART4, RCC_APB1Periph_USART5, RCC_APB1Periph_I2C1, RCC_APB1Periph_I2C2, RCC_APB1Periph_USB, RCC_APB1Periph_CAN1, RCC_APB1Periph_BKP, RCC_APB1Periph_PWR, RCC_APB1Periph_DAC, RCC_APB1Periph_CEC, RCC_APB1Periph_TIM12, RCC_APB1Periph_TIM13, RCC_APB1Periph_TIM14
NewStatenew state of the specified peripheral clock. This parameter can be: ENABLE or DISABLE.
Return values
None

Definition at line 1127 of file stm32f10x_rcc.c.

void RCC_APB1PeriphResetCmd ( uint32_t  RCC_APB1Periph,
FunctionalState  NewState 
)

Forces or releases Low Speed APB (APB1) peripheral reset.

Parameters
RCC_APB1Periphspecifies the APB1 peripheral to reset. This parameter can be any combination of the following values:
  • RCC_APB1Periph_TIM2, RCC_APB1Periph_TIM3, RCC_APB1Periph_TIM4, RCC_APB1Periph_TIM5, RCC_APB1Periph_TIM6, RCC_APB1Periph_TIM7, RCC_APB1Periph_WWDG, RCC_APB1Periph_SPI2, RCC_APB1Periph_SPI3, RCC_APB1Periph_USART2, RCC_APB1Periph_USART3, RCC_APB1Periph_USART4, RCC_APB1Periph_USART5, RCC_APB1Periph_I2C1, RCC_APB1Periph_I2C2, RCC_APB1Periph_USB, RCC_APB1Periph_CAN1, RCC_APB1Periph_BKP, RCC_APB1Periph_PWR, RCC_APB1Periph_DAC, RCC_APB1Periph_CEC, RCC_APB1Periph_TIM12, RCC_APB1Periph_TIM13, RCC_APB1Periph_TIM14
NewStatenew state of the specified peripheral clock. This parameter can be: ENABLE or DISABLE.
Return values
None

Definition at line 1217 of file stm32f10x_rcc.c.

void RCC_APB2PeriphClockCmd ( uint32_t  RCC_APB2Periph,
FunctionalState  NewState 
)

Enables or disables the High Speed APB (APB2) peripheral clock.

Parameters
RCC_APB2Periphspecifies the APB2 peripheral to gates its clock. This parameter can be any combination of the following values:
  • RCC_APB2Periph_AFIO, RCC_APB2Periph_GPIOA, RCC_APB2Periph_GPIOB, RCC_APB2Periph_GPIOC, RCC_APB2Periph_GPIOD, RCC_APB2Periph_GPIOE, RCC_APB2Periph_GPIOF, RCC_APB2Periph_GPIOG, RCC_APB2Periph_ADC1, RCC_APB2Periph_ADC2, RCC_APB2Periph_TIM1, RCC_APB2Periph_SPI1, RCC_APB2Periph_TIM8, RCC_APB2Periph_USART1, RCC_APB2Periph_ADC3, RCC_APB2Periph_TIM15, RCC_APB2Periph_TIM16, RCC_APB2Periph_TIM17, RCC_APB2Periph_TIM9, RCC_APB2Periph_TIM10, RCC_APB2Periph_TIM11
NewStatenew state of the specified peripheral clock. This parameter can be: ENABLE or DISABLE.
Return values
None

Definition at line 1096 of file stm32f10x_rcc.c.

void RCC_APB2PeriphResetCmd ( uint32_t  RCC_APB2Periph,
FunctionalState  NewState 
)

Forces or releases High Speed APB (APB2) peripheral reset.

Parameters
RCC_APB2Periphspecifies the APB2 peripheral to reset. This parameter can be any combination of the following values:
  • RCC_APB2Periph_AFIO, RCC_APB2Periph_GPIOA, RCC_APB2Periph_GPIOB, RCC_APB2Periph_GPIOC, RCC_APB2Periph_GPIOD, RCC_APB2Periph_GPIOE, RCC_APB2Periph_GPIOF, RCC_APB2Periph_GPIOG, RCC_APB2Periph_ADC1, RCC_APB2Periph_ADC2, RCC_APB2Periph_TIM1, RCC_APB2Periph_SPI1, RCC_APB2Periph_TIM8, RCC_APB2Periph_USART1, RCC_APB2Periph_ADC3, RCC_APB2Periph_TIM15, RCC_APB2Periph_TIM16, RCC_APB2Periph_TIM17, RCC_APB2Periph_TIM9, RCC_APB2Periph_TIM10, RCC_APB2Periph_TIM11
NewStatenew state of the specified peripheral reset. This parameter can be: ENABLE or DISABLE.
Return values
None

Definition at line 1186 of file stm32f10x_rcc.c.

void RCC_BackupResetCmd ( FunctionalState  NewState)

Forces or releases the Backup domain reset.

Parameters
NewStatenew state of the Backup domain reset. This parameter can be: ENABLE or DISABLE.
Return values
None

Definition at line 1238 of file stm32f10x_rcc.c.

void RCC_ClearFlag ( void  )

Clears the RCC reset flags.

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.

Note
The reset flags are: RCC_FLAG_PINRST, RCC_FLAG_PORRST, RCC_FLAG_SFTRST, RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST, RCC_FLAG_LPWRRST
Parameters
None
Return values
None

Definition at line 1372 of file stm32f10x_rcc.c.

void RCC_ClearITPendingBit ( uint8_t  RCC_IT)

Clears the RCC's interrupt pending bits.

Parameters
RCC_ITspecifies the interrupt pending bit to clear.

For STM32_Connectivity_line_devices, this parameter can be any combination of the following values:

  • RCC_IT_LSIRDY: LSI ready interrupt
  • RCC_IT_LSERDY: LSE ready interrupt
  • RCC_IT_HSIRDY: HSI ready interrupt
  • RCC_IT_HSERDY: HSE ready interrupt
  • RCC_IT_PLLRDY: PLL ready interrupt
  • RCC_IT_PLL2RDY: PLL2 ready interrupt
  • RCC_IT_PLL3RDY: PLL3 ready interrupt
  • RCC_IT_CSS: Clock Security System interrupt

For other_STM32_devices, this parameter can be any combination of the following values:

  • RCC_IT_LSIRDY: LSI ready interrupt
  • RCC_IT_LSERDY: LSE ready interrupt
  • RCC_IT_HSIRDY: HSI ready interrupt
  • RCC_IT_HSERDY: HSE ready interrupt
  • RCC_IT_PLLRDY: PLL ready interrupt
  • RCC_IT_CSS: Clock Security System interrupt
    Return values
    None

Definition at line 1449 of file stm32f10x_rcc.c.

void RCC_ClockSecuritySystemCmd ( FunctionalState  NewState)

Enables or disables the Clock Security System.

Parameters
NewStatenew state of the Clock Security System.. This parameter can be: ENABLE or DISABLE.
Return values
None

Definition at line 1251 of file stm32f10x_rcc.c.

void RCC_DeInit ( void  )

Resets the RCC clock configuration to the default reset state.

Parameters
None
Return values
None

Definition at line 218 of file stm32f10x_rcc.c.

void RCC_GetClocksFreq ( RCC_ClocksTypeDef RCC_Clocks)

Returns the frequencies of different on chip clocks.

Returns the frequencies of different on chip clocks; SYSCLK, HCLK, PCLK1 and PCLK2.

Parameters
RCC_Clockspointer to a RCC_ClocksTypeDef structure which will hold the clocks frequencies.
Note
The result of this function could be not correct when using fractional value for HSE crystal.
Return values
None

Definition at line 909 of file stm32f10x_rcc.c.

FlagStatus RCC_GetFlagStatus ( uint8_t  RCC_FLAG)

Checks whether the specified RCC flag is set or not.

Parameters
RCC_FLAGspecifies the flag to check.

For STM32_Connectivity_line_devices, this parameter can be one of the following values:

  • RCC_FLAG_HSIRDY: HSI oscillator clock ready
  • RCC_FLAG_HSERDY: HSE oscillator clock ready
  • RCC_FLAG_PLLRDY: PLL clock ready
  • RCC_FLAG_PLL2RDY: PLL2 clock ready
  • RCC_FLAG_PLL3RDY: PLL3 clock ready
  • RCC_FLAG_LSERDY: LSE oscillator clock ready
  • RCC_FLAG_LSIRDY: LSI oscillator clock ready
  • RCC_FLAG_PINRST: Pin reset
  • RCC_FLAG_PORRST: POR/PDR reset
  • RCC_FLAG_SFTRST: Software reset
  • RCC_FLAG_IWDGRST: Independent Watchdog reset
  • RCC_FLAG_WWDGRST: Window Watchdog reset
  • RCC_FLAG_LPWRRST: Low Power reset

For other_STM32_devices, this parameter can be one of the following values:

  • RCC_FLAG_HSIRDY: HSI oscillator clock ready
  • RCC_FLAG_HSERDY: HSE oscillator clock ready
  • RCC_FLAG_PLLRDY: PLL clock ready
  • RCC_FLAG_LSERDY: LSE oscillator clock ready
  • RCC_FLAG_LSIRDY: LSI oscillator clock ready
  • RCC_FLAG_PINRST: Pin reset
  • RCC_FLAG_PORRST: POR/PDR reset
  • RCC_FLAG_SFTRST: Software reset
  • RCC_FLAG_IWDGRST: Independent Watchdog reset
  • RCC_FLAG_WWDGRST: Window Watchdog reset
  • RCC_FLAG_LPWRRST: Low Power reset
Return values
Thenew state of RCC_FLAG (SET or RESET).

Definition at line 1327 of file stm32f10x_rcc.c.

ITStatus RCC_GetITStatus ( uint8_t  RCC_IT)

Checks whether the specified RCC interrupt has occurred or not.

Parameters
RCC_ITspecifies the RCC interrupt source to check.

For STM32_Connectivity_line_devices, this parameter can be one of the following values:

  • RCC_IT_LSIRDY: LSI ready interrupt
  • RCC_IT_LSERDY: LSE ready interrupt
  • RCC_IT_HSIRDY: HSI ready interrupt
  • RCC_IT_HSERDY: HSE ready interrupt
  • RCC_IT_PLLRDY: PLL ready interrupt
  • RCC_IT_PLL2RDY: PLL2 ready interrupt
  • RCC_IT_PLL3RDY: PLL3 ready interrupt
  • RCC_IT_CSS: Clock Security System interrupt

For other_STM32_devices, this parameter can be one of the following values:

  • RCC_IT_LSIRDY: LSI ready interrupt
  • RCC_IT_LSERDY: LSE ready interrupt
  • RCC_IT_HSIRDY: HSI ready interrupt
  • RCC_IT_HSERDY: HSE ready interrupt
  • RCC_IT_PLLRDY: PLL ready interrupt
  • RCC_IT_CSS: Clock Security System interrupt
Return values
Thenew state of RCC_IT (SET or RESET).

Definition at line 1403 of file stm32f10x_rcc.c.

uint8_t RCC_GetSYSCLKSource ( void  )

Returns the clock source used as system clock.

Parameters
None
Return values
Theclock source used as system clock. The returned value can be one of the following:
  • 0x00: HSI used as system clock
  • 0x04: HSE used as system clock
  • 0x08: PLL used as system clock

Definition at line 588 of file stm32f10x_rcc.c.

void RCC_HCLKConfig ( uint32_t  RCC_SYSCLK)

Configures the AHB clock (HCLK).

Parameters
RCC_SYSCLKdefines the AHB clock divider. This clock is derived from the system clock (SYSCLK). This parameter can be one of the following values:
  • RCC_SYSCLK_Div1: AHB clock = SYSCLK
  • RCC_SYSCLK_Div2: AHB clock = SYSCLK/2
  • RCC_SYSCLK_Div4: AHB clock = SYSCLK/4
  • RCC_SYSCLK_Div8: AHB clock = SYSCLK/8
  • RCC_SYSCLK_Div16: AHB clock = SYSCLK/16
  • RCC_SYSCLK_Div64: AHB clock = SYSCLK/64
  • RCC_SYSCLK_Div128: AHB clock = SYSCLK/128
  • RCC_SYSCLK_Div256: AHB clock = SYSCLK/256
  • RCC_SYSCLK_Div512: AHB clock = SYSCLK/512
Return values
None

Definition at line 609 of file stm32f10x_rcc.c.

void RCC_HSEConfig ( uint32_t  RCC_HSE)

Configures the External High Speed oscillator (HSE).

Note
HSE can not be stopped if it is used directly or through the PLL as system clock.
Parameters
RCC_HSEspecifies the new state of the HSE. This parameter can be one of the following values:
  • RCC_HSE_OFF: HSE oscillator OFF
  • RCC_HSE_ON: HSE oscillator ON
  • RCC_HSE_Bypass: HSE oscillator bypassed with external clock
Return values
None

Definition at line 271 of file stm32f10x_rcc.c.

void RCC_HSICmd ( FunctionalState  NewState)

Enables or disables the Internal High Speed oscillator (HSI).

Note
HSI can not be stopped if it is used directly or through the PLL as system clock.
Parameters
NewStatenew state of the HSI. This parameter can be: ENABLE or DISABLE.
Return values
None

Definition at line 355 of file stm32f10x_rcc.c.

void RCC_ITConfig ( uint8_t  RCC_IT,
FunctionalState  NewState 
)

Enables or disables the specified RCC interrupts.

Parameters
RCC_ITspecifies the RCC interrupt sources to be enabled or disabled.

For STM32_Connectivity_line_devices, this parameter can be any combination of the following values

  • RCC_IT_LSIRDY: LSI ready interrupt
  • RCC_IT_LSERDY: LSE ready interrupt
  • RCC_IT_HSIRDY: HSI ready interrupt
  • RCC_IT_HSERDY: HSE ready interrupt
  • RCC_IT_PLLRDY: PLL ready interrupt
  • RCC_IT_PLL2RDY: PLL2 ready interrupt
  • RCC_IT_PLL3RDY: PLL3 ready interrupt

For other_STM32_devices, this parameter can be any combination of the following values

  • RCC_IT_LSIRDY: LSI ready interrupt
  • RCC_IT_LSERDY: LSE ready interrupt
  • RCC_IT_HSIRDY: HSI ready interrupt
  • RCC_IT_HSERDY: HSE ready interrupt
  • RCC_IT_PLLRDY: PLL ready interrupt
Parameters
NewStatenew state of the specified RCC interrupts. This parameter can be: ENABLE or DISABLE.
Return values
None

Definition at line 701 of file stm32f10x_rcc.c.

void RCC_LSEConfig ( uint8_t  RCC_LSE)

Configures the External Low Speed oscillator (LSE).

Parameters
RCC_LSEspecifies the new state of the LSE. This parameter can be one of the following values:
  • RCC_LSE_OFF: LSE oscillator OFF
  • RCC_LSE_ON: LSE oscillator ON
  • RCC_LSE_Bypass: LSE oscillator bypassed with external clock
Return values
None

Definition at line 830 of file stm32f10x_rcc.c.

void RCC_LSICmd ( FunctionalState  NewState)

Enables or disables the Internal Low Speed oscillator (LSI).

Note
LSI can not be disabled if the IWDG is running.
Parameters
NewStatenew state of the LSI. This parameter can be: ENABLE or DISABLE.
Return values
None

Definition at line 863 of file stm32f10x_rcc.c.

void RCC_MCOConfig ( uint8_t  RCC_MCO)

Selects the clock source to output on MCO pin.

Parameters
RCC_MCOspecifies the clock source to output.

For STM32_Connectivity_line_devices, this parameter can be one of the following values:

  • RCC_MCO_NoClock: No clock selected
  • RCC_MCO_SYSCLK: System clock selected
  • RCC_MCO_HSI: HSI oscillator clock selected
  • RCC_MCO_HSE: HSE oscillator clock selected
  • RCC_MCO_PLLCLK_Div2: PLL clock divided by 2 selected
  • RCC_MCO_PLL2CLK: PLL2 clock selected
  • RCC_MCO_PLL3CLK_Div2: PLL3 clock divided by 2 selected
  • RCC_MCO_XT1: External 3-25 MHz oscillator clock selected
  • RCC_MCO_PLL3CLK: PLL3 clock selected

For other_STM32_devices, this parameter can be one of the following values:

  • RCC_MCO_NoClock: No clock selected
  • RCC_MCO_SYSCLK: System clock selected
  • RCC_MCO_HSI: HSI oscillator clock selected
  • RCC_MCO_HSE: HSE oscillator clock selected
  • RCC_MCO_PLLCLK_Div2: PLL clock divided by 2 selected
Return values
None

Definition at line 1283 of file stm32f10x_rcc.c.

void RCC_PCLK1Config ( uint32_t  RCC_HCLK)

Configures the Low Speed APB clock (PCLK1).

Parameters
RCC_HCLKdefines the APB1 clock divider. This clock is derived from the AHB clock (HCLK). This parameter can be one of the following values:
  • RCC_HCLK_Div1: APB1 clock = HCLK
  • RCC_HCLK_Div2: APB1 clock = HCLK/2
  • RCC_HCLK_Div4: APB1 clock = HCLK/4
  • RCC_HCLK_Div8: APB1 clock = HCLK/8
  • RCC_HCLK_Div16: APB1 clock = HCLK/16
Return values
None

Definition at line 635 of file stm32f10x_rcc.c.

void RCC_PCLK2Config ( uint32_t  RCC_HCLK)

Configures the High Speed APB clock (PCLK2).

Parameters
RCC_HCLKdefines the APB2 clock divider. This clock is derived from the AHB clock (HCLK). This parameter can be one of the following values:
  • RCC_HCLK_Div1: APB2 clock = HCLK
  • RCC_HCLK_Div2: APB2 clock = HCLK/2
  • RCC_HCLK_Div4: APB2 clock = HCLK/4
  • RCC_HCLK_Div8: APB2 clock = HCLK/8
  • RCC_HCLK_Div16: APB2 clock = HCLK/16
Return values
None

Definition at line 661 of file stm32f10x_rcc.c.

void RCC_PLLCmd ( FunctionalState  NewState)

Enables or disables the PLL.

Enables or disables the main PLL.

Note
The PLL can not be disabled if it is used as system clock.
Parameters
NewStatenew state of the PLL. This parameter can be: ENABLE or DISABLE.
Return values
None

Definition at line 402 of file stm32f10x_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.
Parameters
RCC_PLLSourcespecifies 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_PLLSource_HSI_Div2: HSI oscillator clock divided by 2 selected as PLL clock entry
  • RCC_PLLSource_PREDIV1: PREDIV1 clock selected as PLL clock entry For other_STM32_devices, 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_HSE_Div1: HSE oscillator clock selected as PLL clock entry
  • RCC_PLLSource_HSE_Div2: HSE oscillator clock divided by 2 selected as PLL clock entry
RCC_PLLMulspecifies 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]
Return values
None

Definition at line 379 of file stm32f10x_rcc.c.

void RCC_RTCCLKCmd ( FunctionalState  NewState)

Enables or disables the RTC clock.

Note
This function must be used only after the RTC clock was selected using the RCC_RTCCLKConfig function.
Parameters
NewStatenew state of the RTC clock. This parameter can be: ENABLE or DISABLE.
Return values
None

Definition at line 894 of file stm32f10x_rcc.c.

void RCC_RTCCLKConfig ( uint32_t  RCC_RTCCLKSource)

Configures the RTC clock (RTCCLK).

Note
Once the RTC clock is selected it can't be changed unless the Backup domain is reset.
Parameters
RCC_RTCCLKSourcespecifies the RTC clock source. This parameter can be one of the following values:
  • RCC_RTCCLKSource_LSE: LSE selected as RTC clock
  • RCC_RTCCLKSource_LSI: LSI selected as RTC clock
  • RCC_RTCCLKSource_HSE_Div128: HSE clock divided by 128 selected as RTC clock
Return values
None

Definition at line 880 of file stm32f10x_rcc.c.

void RCC_SYSCLKConfig ( uint32_t  RCC_SYSCLKSource)

Configures the system clock (SYSCLK).

Parameters
RCC_SYSCLKSourcespecifies the clock source used as system clock. This parameter can be one of the following values:
  • RCC_SYSCLKSource_HSI: HSI selected as system clock
  • RCC_SYSCLKSource_HSE: HSE selected as system clock
  • RCC_SYSCLKSource_PLLCLK: PLL selected as system clock
Return values
None

Definition at line 565 of file stm32f10x_rcc.c.

void RCC_USBCLKConfig ( uint32_t  RCC_USBCLKSource)

Configures the USB clock (USBCLK).

Parameters
RCC_USBCLKSourcespecifies the USB clock source. This clock is derived from the PLL output. This parameter can be one of the following values:
  • RCC_USBCLKSource_PLLCLK_1Div5: PLL clock divided by 1,5 selected as USB clock source
  • RCC_USBCLKSource_PLLCLK_Div1: PLL clock selected as USB clock source
Return values
None

Definition at line 729 of file stm32f10x_rcc.c.

ErrorStatus RCC_WaitForHSEStartUp ( void  )

Waits for HSE start-up.

Parameters
None
Return values
AnErrorStatus enumuration value:
  • SUCCESS: HSE oscillator is stable and ready to use
  • ERROR: HSE oscillator not yet ready

Definition at line 305 of file stm32f10x_rcc.c.



rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:54