This file contains all the functions prototypes for the RCC firmware library. More...
#include "stm32f30x.h"
Go to the source code of this file.
Classes | |
struct | RCC_ClocksTypeDef |
Macros | |
#define | IS_RCC_ADCCLK(ADCCLK) |
#define | IS_RCC_AHB_PERIPH(PERIPH) ((((PERIPH) & 0xCE81FFA8) == 0x00) && ((PERIPH) != 0x00)) |
#define | IS_RCC_AHB_RST_PERIPH(PERIPH) ((((PERIPH) & 0xCE81FFFF) == 0x00) && ((PERIPH) != 0x00)) |
#define | IS_RCC_APB1_PERIPH(PERIPH) ((((PERIPH) & 0x890137C8) == 0x00) && ((PERIPH) != 0x00)) |
#define | IS_RCC_APB2_PERIPH(PERIPH) ((((PERIPH) & 0xDFF887FE) == 0x00) && ((PERIPH) != 0x00)) |
#define | IS_RCC_CLEAR_IT(IT) ((((IT) & (uint8_t)0x40) == 0x00) && ((IT) != 0x00)) |
#define | IS_RCC_FLAG(FLAG) |
#define | IS_RCC_GET_IT(IT) |
#define | IS_RCC_HCLK(HCLK) |
#define | IS_RCC_HRTIMCLK(HRTIMCLK) (((HRTIMCLK) == RCC_HRTIM1CLK_HCLK) || ((HRTIMCLK) == RCC_HRTIM1CLK_PLLCLK)) |
#define | IS_RCC_HSE(HSE) |
#define | IS_RCC_HSI_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x1F) |
#define | IS_RCC_I2CCLK(I2CCLK) |
#define | IS_RCC_I2SCLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2S2CLKSource_SYSCLK) || ((SOURCE) == RCC_I2S2CLKSource_Ext)) |
#define | IS_RCC_IT(IT) ((((IT) & (uint8_t)0xC0) == 0x00) && ((IT) != 0x00)) |
#define | IS_RCC_LSE(LSE) |
#define | IS_RCC_LSE_DRIVE(DRIVE) |
#define | IS_RCC_MCO_PRESCALER(PRESCALER) |
#define | IS_RCC_MCO_SOURCE(SOURCE) |
#define | IS_RCC_PCLK(PCLK) |
#define | IS_RCC_PLL_MUL(MUL) |
#define | IS_RCC_PLL_SOURCE(SOURCE) |
#define | IS_RCC_PREDIV1(PREDIV1) |
#define | IS_RCC_RTCCLK_SOURCE(SOURCE) |
#define | IS_RCC_SYSCLK_SOURCE(SOURCE) |
#define | IS_RCC_TIMCLK(TIMCLK) |
#define | IS_RCC_USARTCLK(USARTCLK) |
#define | IS_RCC_USBCLK_SOURCE(SOURCE) |
#define | RCC_ADC12PLLCLK_Div1 ((uint32_t)0x00000100) |
#define | RCC_ADC12PLLCLK_Div10 ((uint32_t)0x00000150) |
#define | RCC_ADC12PLLCLK_Div12 ((uint32_t)0x00000160) |
#define | RCC_ADC12PLLCLK_Div128 ((uint32_t)0x000001A0) |
#define | RCC_ADC12PLLCLK_Div16 ((uint32_t)0x00000170) |
#define | RCC_ADC12PLLCLK_Div2 ((uint32_t)0x00000110) |
#define | RCC_ADC12PLLCLK_Div256 ((uint32_t)0x000001B0) |
#define | RCC_ADC12PLLCLK_Div32 ((uint32_t)0x00000180) |
#define | RCC_ADC12PLLCLK_Div4 ((uint32_t)0x00000120) |
#define | RCC_ADC12PLLCLK_Div6 ((uint32_t)0x00000130) |
#define | RCC_ADC12PLLCLK_Div64 ((uint32_t)0x00000190) |
#define | RCC_ADC12PLLCLK_Div8 ((uint32_t)0x00000140) |
#define | RCC_ADC12PLLCLK_OFF ((uint32_t)0x00000000) |
#define | RCC_ADC34PLLCLK_Div1 ((uint32_t)0x10002000) |
#define | RCC_ADC34PLLCLK_Div10 ((uint32_t)0x10002A00) |
#define | RCC_ADC34PLLCLK_Div12 ((uint32_t)0x10002C00) |
#define | RCC_ADC34PLLCLK_Div128 ((uint32_t)0x10003400) |
#define | RCC_ADC34PLLCLK_Div16 ((uint32_t)0x10002E00) |
#define | RCC_ADC34PLLCLK_Div2 ((uint32_t)0x10002200) |
#define | RCC_ADC34PLLCLK_Div256 ((uint32_t)0x10003600) |
#define | RCC_ADC34PLLCLK_Div32 ((uint32_t)0x10003000) |
#define | RCC_ADC34PLLCLK_Div4 ((uint32_t)0x10002400) |
#define | RCC_ADC34PLLCLK_Div6 ((uint32_t)0x10002600) |
#define | RCC_ADC34PLLCLK_Div64 ((uint32_t)0x10003200) |
#define | RCC_ADC34PLLCLK_Div8 ((uint32_t)0x10002800) |
#define | RCC_ADC34PLLCLK_OFF ((uint32_t)0x10000000) |
#define | RCC_AHBPeriph_ADC12 RCC_AHBENR_ADC12EN |
#define | RCC_AHBPeriph_ADC34 RCC_AHBENR_ADC34EN |
#define | RCC_AHBPeriph_CRC RCC_AHBENR_CRCEN |
#define | RCC_AHBPeriph_DMA1 RCC_AHBENR_DMA1EN |
#define | RCC_AHBPeriph_DMA2 RCC_AHBENR_DMA2EN |
#define | RCC_AHBPeriph_FLITF RCC_AHBENR_FLITFEN |
#define | RCC_AHBPeriph_GPIOA RCC_AHBENR_GPIOAEN |
#define | RCC_AHBPeriph_GPIOB RCC_AHBENR_GPIOBEN |
#define | RCC_AHBPeriph_GPIOC RCC_AHBENR_GPIOCEN |
#define | RCC_AHBPeriph_GPIOD RCC_AHBENR_GPIODEN |
#define | RCC_AHBPeriph_GPIOE RCC_AHBENR_GPIOEEN |
#define | RCC_AHBPeriph_GPIOF RCC_AHBENR_GPIOFEN |
#define | RCC_AHBPeriph_SRAM RCC_AHBENR_SRAMEN |
#define | RCC_AHBPeriph_TS RCC_AHBENR_TSEN |
#define | RCC_APB1Periph_CAN1 RCC_APB1ENR_CAN1EN |
#define | RCC_APB1Periph_DAC RCC_APB1Periph_DAC1 |
#define | RCC_APB1Periph_DAC1 RCC_APB1ENR_DAC1EN |
#define | RCC_APB1Periph_DAC2 RCC_APB1ENR_DAC2EN |
#define | RCC_APB1Periph_I2C1 RCC_APB1ENR_I2C1EN |
#define | RCC_APB1Periph_I2C2 RCC_APB1ENR_I2C2EN |
#define | RCC_APB1Periph_I2C3 RCC_APB1ENR_I2C3EN |
#define | RCC_APB1Periph_PWR RCC_APB1ENR_PWREN |
#define | RCC_APB1Periph_SPI2 RCC_APB1ENR_SPI2EN |
#define | RCC_APB1Periph_SPI3 RCC_APB1ENR_SPI3EN |
#define | RCC_APB1Periph_TIM2 RCC_APB1ENR_TIM2EN |
#define | RCC_APB1Periph_TIM3 RCC_APB1ENR_TIM3EN |
#define | RCC_APB1Periph_TIM4 RCC_APB1ENR_TIM4EN |
#define | RCC_APB1Periph_TIM6 RCC_APB1ENR_TIM6EN |
#define | RCC_APB1Periph_TIM7 RCC_APB1ENR_TIM7EN |
#define | RCC_APB1Periph_UART4 RCC_APB1ENR_UART4EN |
#define | RCC_APB1Periph_UART5 RCC_APB1ENR_UART5EN |
#define | RCC_APB1Periph_USART2 RCC_APB1ENR_USART2EN |
#define | RCC_APB1Periph_USART3 RCC_APB1ENR_USART3EN |
#define | RCC_APB1Periph_USB RCC_APB1ENR_USBEN |
#define | RCC_APB1Periph_WWDG RCC_APB1ENR_WWDGEN |
#define | RCC_APB2Periph_HRTIM1 RCC_APB2ENR_HRTIM1 |
#define | RCC_APB2Periph_SPI1 RCC_APB2ENR_SPI1EN |
#define | RCC_APB2Periph_SYSCFG RCC_APB2ENR_SYSCFGEN |
#define | RCC_APB2Periph_TIM1 RCC_APB2ENR_TIM1EN |
#define | RCC_APB2Periph_TIM15 RCC_APB2ENR_TIM15EN |
#define | RCC_APB2Periph_TIM16 RCC_APB2ENR_TIM16EN |
#define | RCC_APB2Periph_TIM17 RCC_APB2ENR_TIM17EN |
#define | RCC_APB2Periph_TIM8 RCC_APB2ENR_TIM8EN |
#define | RCC_APB2Periph_USART1 RCC_APB2ENR_USART1EN |
#define | RCC_FLAG_HSERDY ((uint8_t)0x11) |
#define | RCC_FLAG_HSIRDY ((uint8_t)0x01) |
#define | RCC_FLAG_IWDGRST ((uint8_t)0x5D) |
#define | RCC_FLAG_LPWRRST ((uint8_t)0x5F) |
#define | RCC_FLAG_LSERDY ((uint8_t)0x21) |
#define | RCC_FLAG_LSIRDY ((uint8_t)0x41) |
#define | RCC_FLAG_MCOF ((uint8_t)0x9C) |
#define | RCC_FLAG_OBLRST ((uint8_t)0x59) |
#define | RCC_FLAG_PINRST ((uint8_t)0x5A) |
#define | RCC_FLAG_PLLRDY ((uint8_t)0x19) |
#define | RCC_FLAG_PORRST ((uint8_t)0x5B) |
#define | RCC_FLAG_SFTRST ((uint8_t)0x5C) |
#define | RCC_FLAG_WWDGRST ((uint8_t)0x5E) |
#define | RCC_HCLK_Div1 ((uint32_t)0x00000000) |
#define | RCC_HCLK_Div16 ((uint32_t)0x00000700) |
#define | RCC_HCLK_Div2 ((uint32_t)0x00000400) |
#define | RCC_HCLK_Div4 ((uint32_t)0x00000500) |
#define | RCC_HCLK_Div8 ((uint32_t)0x00000600) |
#define | RCC_HRTIM1CLK_HCLK ((uint32_t)0x00000000) |
#define | RCC_HRTIM1CLK_PLLCLK RCC_CFGR3_HRTIM1SW |
#define | RCC_HSE_Bypass ((uint8_t)0x05) |
#define | RCC_HSE_OFF ((uint8_t)0x00) |
#define | RCC_HSE_ON ((uint8_t)0x01) |
#define | RCC_I2C1CLK_HSI ((uint32_t)0x00000000) |
#define | RCC_I2C1CLK_SYSCLK RCC_CFGR3_I2C1SW |
#define | RCC_I2C2CLK_HSI ((uint32_t)0x10000000) |
#define | RCC_I2C2CLK_SYSCLK ((uint32_t)0x10000020) |
#define | RCC_I2C3CLK_HSI ((uint32_t)0x20000000) |
#define | RCC_I2C3CLK_SYSCLK ((uint32_t)0x20000040) |
#define | RCC_I2S2CLKSource_Ext ((uint8_t)0x01) |
#define | RCC_I2S2CLKSource_SYSCLK ((uint8_t)0x00) |
#define | RCC_IT_CSS ((uint8_t)0x80) |
#define | RCC_IT_HSERDY ((uint8_t)0x08) |
#define | RCC_IT_HSIRDY ((uint8_t)0x04) |
#define | RCC_IT_LSERDY ((uint8_t)0x02) |
#define | RCC_IT_LSIRDY ((uint8_t)0x01) |
#define | RCC_IT_PLLRDY ((uint8_t)0x10) |
#define | RCC_LSE_Bypass ((uint32_t)(RCC_BDCR_LSEON | RCC_BDCR_LSEBYP)) |
#define | RCC_LSE_OFF ((uint32_t)0x00000000) |
#define | RCC_LSE_ON RCC_BDCR_LSEON |
#define | RCC_LSEDrive_High RCC_BDCR_LSEDRV |
#define | RCC_LSEDrive_Low ((uint32_t)0x00000000) |
#define | RCC_LSEDrive_MediumHigh RCC_BDCR_LSEDRV_1 |
#define | RCC_LSEDrive_MediumLow RCC_BDCR_LSEDRV_0 |
#define | RCC_MCOPrescaler_1 RCC_CFGR_MCO_PRE_1 |
#define | RCC_MCOPrescaler_128 RCC_CFGR_MCO_PRE_128 |
#define | RCC_MCOPrescaler_16 RCC_CFGR_MCO_PRE_16 |
#define | RCC_MCOPrescaler_2 RCC_CFGR_MCO_PRE_2 |
#define | RCC_MCOPrescaler_32 RCC_CFGR_MCO_PRE_32 |
#define | RCC_MCOPrescaler_4 RCC_CFGR_MCO_PRE_4 |
#define | RCC_MCOPrescaler_64 RCC_CFGR_MCO_PRE_64 |
#define | RCC_MCOPrescaler_8 RCC_CFGR_MCO_PRE_8 |
#define | RCC_MCOSource_HSE ((uint8_t)0x06) |
#define | RCC_MCOSource_HSI ((uint8_t)0x05) |
#define | RCC_MCOSource_LSE ((uint8_t)0x03) |
#define | RCC_MCOSource_LSI ((uint8_t)0x02) |
#define | RCC_MCOSource_NoClock ((uint8_t)0x00) |
#define | RCC_MCOSource_PLLCLK_Div2 ((uint8_t)0x07) |
#define | RCC_MCOSource_SYSCLK ((uint8_t)0x04) |
#define | RCC_PLLMul_10 RCC_CFGR_PLLMULL10 |
#define | RCC_PLLMul_11 RCC_CFGR_PLLMULL11 |
#define | RCC_PLLMul_12 RCC_CFGR_PLLMULL12 |
#define | RCC_PLLMul_13 RCC_CFGR_PLLMULL13 |
#define | RCC_PLLMul_14 RCC_CFGR_PLLMULL14 |
#define | RCC_PLLMul_15 RCC_CFGR_PLLMULL15 |
#define | RCC_PLLMul_16 RCC_CFGR_PLLMULL16 |
#define | RCC_PLLMul_2 RCC_CFGR_PLLMULL2 |
#define | RCC_PLLMul_3 RCC_CFGR_PLLMULL3 |
#define | RCC_PLLMul_4 RCC_CFGR_PLLMULL4 |
#define | RCC_PLLMul_5 RCC_CFGR_PLLMULL5 |
#define | RCC_PLLMul_6 RCC_CFGR_PLLMULL6 |
#define | RCC_PLLMul_7 RCC_CFGR_PLLMULL7 |
#define | RCC_PLLMul_8 RCC_CFGR_PLLMULL8 |
#define | RCC_PLLMul_9 RCC_CFGR_PLLMULL9 |
#define | RCC_PLLSource_HSI_Div2 RCC_CFGR_PLLSRC_HSI_Div2 |
#define | RCC_PLLSource_PREDIV1 RCC_CFGR_PLLSRC_PREDIV1 |
#define | RCC_PREDIV1_Div1 RCC_CFGR2_PREDIV1_DIV1 |
#define | RCC_PREDIV1_Div10 RCC_CFGR2_PREDIV1_DIV10 |
#define | RCC_PREDIV1_Div11 RCC_CFGR2_PREDIV1_DIV11 |
#define | RCC_PREDIV1_Div12 RCC_CFGR2_PREDIV1_DIV12 |
#define | RCC_PREDIV1_Div13 RCC_CFGR2_PREDIV1_DIV13 |
#define | RCC_PREDIV1_Div14 RCC_CFGR2_PREDIV1_DIV14 |
#define | RCC_PREDIV1_Div15 RCC_CFGR2_PREDIV1_DIV15 |
#define | RCC_PREDIV1_Div16 RCC_CFGR2_PREDIV1_DIV16 |
#define | RCC_PREDIV1_Div2 RCC_CFGR2_PREDIV1_DIV2 |
#define | RCC_PREDIV1_Div3 RCC_CFGR2_PREDIV1_DIV3 |
#define | RCC_PREDIV1_Div4 RCC_CFGR2_PREDIV1_DIV4 |
#define | RCC_PREDIV1_Div5 RCC_CFGR2_PREDIV1_DIV5 |
#define | RCC_PREDIV1_Div6 RCC_CFGR2_PREDIV1_DIV6 |
#define | RCC_PREDIV1_Div7 RCC_CFGR2_PREDIV1_DIV7 |
#define | RCC_PREDIV1_Div8 RCC_CFGR2_PREDIV1_DIV8 |
#define | RCC_PREDIV1_Div9 RCC_CFGR2_PREDIV1_DIV9 |
#define | RCC_RTCCLKSource_HSE_Div32 RCC_BDCR_RTCSEL_HSE |
#define | RCC_RTCCLKSource_LSE RCC_BDCR_RTCSEL_LSE |
#define | RCC_RTCCLKSource_LSI RCC_BDCR_RTCSEL_LSI |
#define | RCC_SYSCLK_Div1 RCC_CFGR_HPRE_DIV1 |
#define | RCC_SYSCLK_Div128 RCC_CFGR_HPRE_DIV128 |
#define | RCC_SYSCLK_Div16 RCC_CFGR_HPRE_DIV16 |
#define | RCC_SYSCLK_Div2 RCC_CFGR_HPRE_DIV2 |
#define | RCC_SYSCLK_Div256 RCC_CFGR_HPRE_DIV256 |
#define | RCC_SYSCLK_Div4 RCC_CFGR_HPRE_DIV4 |
#define | RCC_SYSCLK_Div512 RCC_CFGR_HPRE_DIV512 |
#define | RCC_SYSCLK_Div64 RCC_CFGR_HPRE_DIV64 |
#define | RCC_SYSCLK_Div8 RCC_CFGR_HPRE_DIV8 |
#define | RCC_SYSCLKSource_HSE RCC_CFGR_SW_HSE |
#define | RCC_SYSCLKSource_HSI RCC_CFGR_SW_HSI |
#define | RCC_SYSCLKSource_PLLCLK RCC_CFGR_SW_PLL |
#define | RCC_TIM15CLK_HCLK ((uint32_t)0x20000000) |
#define | RCC_TIM15CLK_PLLCLK ((uint32_t)0x20000400) |
#define | RCC_TIM16CLK_HCLK ((uint32_t)0x30000000) |
#define | RCC_TIM16CLK_PLLCLK ((uint32_t)0x30000800) |
#define | RCC_TIM17CLK_HCLK ((uint32_t)0x40000000) |
#define | RCC_TIM17CLK_PLLCLK ((uint32_t)0x40002000) |
#define | RCC_TIM1CLK_HCLK ((uint32_t)0x00000000) |
#define | RCC_TIM1CLK_PLLCLK RCC_CFGR3_TIM1SW |
#define | RCC_TIM8CLK_HCLK ((uint32_t)0x10000000) |
#define | RCC_TIM8CLK_PLLCLK ((uint32_t)0x10000200) |
#define | RCC_UART4CLK_HSI ((uint32_t)0x40300000) |
#define | RCC_UART4CLK_LSE ((uint32_t)0x40200000) |
#define | RCC_UART4CLK_PCLK ((uint32_t)0x40000000) |
#define | RCC_UART4CLK_SYSCLK ((uint32_t)0x40100000) |
#define | RCC_UART5CLK_HSI ((uint32_t)0x50C00000) |
#define | RCC_UART5CLK_LSE ((uint32_t)0x50800000) |
#define | RCC_UART5CLK_PCLK ((uint32_t)0x50000000) |
#define | RCC_UART5CLK_SYSCLK ((uint32_t)0x50400000) |
#define | RCC_USART1CLK_HSI ((uint32_t)0x10000003) |
#define | RCC_USART1CLK_LSE ((uint32_t)0x10000002) |
#define | RCC_USART1CLK_PCLK ((uint32_t)0x10000000) |
#define | RCC_USART1CLK_SYSCLK ((uint32_t)0x10000001) |
#define | RCC_USART2CLK_HSI ((uint32_t)0x20030000) |
#define | RCC_USART2CLK_LSE ((uint32_t)0x20020000) |
#define | RCC_USART2CLK_PCLK ((uint32_t)0x20000000) |
#define | RCC_USART2CLK_SYSCLK ((uint32_t)0x20010000) |
#define | RCC_USART3CLK_HSI ((uint32_t)0x300C0000) |
#define | RCC_USART3CLK_LSE ((uint32_t)0x30080000) |
#define | RCC_USART3CLK_PCLK ((uint32_t)0x30000000) |
#define | RCC_USART3CLK_SYSCLK ((uint32_t)0x30040000) |
#define | RCC_USBCLKSource_PLLCLK_1Div5 ((uint8_t)0x00) |
#define | RCC_USBCLKSource_PLLCLK_Div1 ((uint8_t)0x01) |
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... | |
This file contains all the functions prototypes for the RCC firmware library.
Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); You may not use this file except in compliance with the License. You may obtain a copy of the License at:
http://www.st.com/software_license_agreement_liberty_v2
Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.
Definition in file stm32f30x_rcc.h.