47 #define RCC_OFFSET (RCC_BASE - PERIPH_BASE) 52 #define CR_OFFSET (RCC_OFFSET + 0x00) 53 #define HSION_BitNumber 0x00 54 #define CR_HSION_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (HSION_BitNumber * 4)) 57 #define PLLON_BitNumber 0x18 58 #define CR_PLLON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLON_BitNumber * 4)) 62 #define PLL2ON_BitNumber 0x1A 63 #define CR_PLL2ON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLL2ON_BitNumber * 4)) 66 #define PLL3ON_BitNumber 0x1C 67 #define CR_PLL3ON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLL3ON_BitNumber * 4)) 71 #define CSSON_BitNumber 0x13 72 #define CR_CSSON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (CSSON_BitNumber * 4)) 77 #define CFGR_OFFSET (RCC_OFFSET + 0x04) 80 #define USBPRE_BitNumber 0x16 81 #define CFGR_USBPRE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (USBPRE_BitNumber * 4)) 83 #define OTGFSPRE_BitNumber 0x16 84 #define CFGR_OTGFSPRE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (OTGFSPRE_BitNumber * 4)) 90 #define BDCR_OFFSET (RCC_OFFSET + 0x20) 91 #define RTCEN_BitNumber 0x0F 92 #define BDCR_RTCEN_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (RTCEN_BitNumber * 4)) 95 #define BDRST_BitNumber 0x10 96 #define BDCR_BDRST_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (BDRST_BitNumber * 4)) 101 #define CSR_OFFSET (RCC_OFFSET + 0x24) 102 #define LSION_BitNumber 0x00 103 #define CSR_LSION_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (LSION_BitNumber * 4)) 109 #define CFGR2_OFFSET (RCC_OFFSET + 0x2C) 110 #define I2S2SRC_BitNumber 0x11 111 #define CFGR2_I2S2SRC_BB (PERIPH_BB_BASE + (CFGR2_OFFSET * 32) + (I2S2SRC_BitNumber * 4)) 114 #define I2S3SRC_BitNumber 0x12 115 #define CFGR2_I2S3SRC_BB (PERIPH_BB_BASE + (CFGR2_OFFSET * 32) + (I2S3SRC_BitNumber * 4)) 121 #define CR_HSEBYP_Reset ((uint32_t)0xFFFBFFFF) 122 #define CR_HSEBYP_Set ((uint32_t)0x00040000) 123 #define CR_HSEON_Reset ((uint32_t)0xFFFEFFFF) 124 #define CR_HSEON_Set ((uint32_t)0x00010000) 125 #define CR_HSITRIM_Mask ((uint32_t)0xFFFFFF07) 128 #if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) 129 #define CFGR_PLL_Mask ((uint32_t)0xFFC2FFFF) 131 #define CFGR_PLL_Mask ((uint32_t)0xFFC0FFFF) 134 #define CFGR_PLLMull_Mask ((uint32_t)0x003C0000) 135 #define CFGR_PLLSRC_Mask ((uint32_t)0x00010000) 136 #define CFGR_PLLXTPRE_Mask ((uint32_t)0x00020000) 137 #define CFGR_SWS_Mask ((uint32_t)0x0000000C) 138 #define CFGR_SW_Mask ((uint32_t)0xFFFFFFFC) 139 #define CFGR_HPRE_Reset_Mask ((uint32_t)0xFFFFFF0F) 140 #define CFGR_HPRE_Set_Mask ((uint32_t)0x000000F0) 141 #define CFGR_PPRE1_Reset_Mask ((uint32_t)0xFFFFF8FF) 142 #define CFGR_PPRE1_Set_Mask ((uint32_t)0x00000700) 143 #define CFGR_PPRE2_Reset_Mask ((uint32_t)0xFFFFC7FF) 144 #define CFGR_PPRE2_Set_Mask ((uint32_t)0x00003800) 145 #define CFGR_ADCPRE_Reset_Mask ((uint32_t)0xFFFF3FFF) 146 #define CFGR_ADCPRE_Set_Mask ((uint32_t)0x0000C000) 149 #define CSR_RMVF_Set ((uint32_t)0x01000000) 151 #if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) 153 #define CFGR2_PREDIV1SRC ((uint32_t)0x00010000) 154 #define CFGR2_PREDIV1 ((uint32_t)0x0000000F) 157 #define CFGR2_PREDIV2 ((uint32_t)0x000000F0) 158 #define CFGR2_PLL2MUL ((uint32_t)0x00000F00) 159 #define CFGR2_PLL3MUL ((uint32_t)0x0000F000) 163 #define FLAG_Mask ((uint8_t)0x1F) 166 #define CIR_BYTE2_ADDRESS ((uint32_t)0x40021009) 169 #define CIR_BYTE3_ADDRESS ((uint32_t)0x4002100A) 172 #define CFGR_BYTE4_ADDRESS ((uint32_t)0x40021007) 175 #define BDCR_ADDRESS (PERIPH_BASE + BDCR_OFFSET) 193 static __I uint8_t
APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};
221 RCC->CR |= (uint32_t)0x00000001;
225 RCC->CFGR &= (uint32_t)0xF8FF0000;
227 RCC->CFGR &= (uint32_t)0xF0FF0000;
231 RCC->CR &= (uint32_t)0xFEF6FFFF;
234 RCC->CR &= (uint32_t)0xFFFBFFFF;
237 RCC->CFGR &= (uint32_t)0xFF80FFFF;
241 RCC->CR &= (uint32_t)0xEBFFFFFF;
244 RCC->CIR = 0x00FF0000;
247 RCC->CFGR2 = 0x00000000;
248 #elif defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) 250 RCC->CIR = 0x009F0000;
253 RCC->CFGR2 = 0x00000000;
256 RCC->CIR = 0x009F0000;
307 __IO uint32_t StartUpCounter = 0;
344 tmpreg |= (uint32_t)HSICalibrationValue << 3;
391 tmpreg |= RCC_PLLSource | RCC_PLLMul;
410 #if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) 432 assert_param(IS_RCC_PREDIV1_SOURCE(RCC_PREDIV1_Source));
437 tmpreg &= ~(CFGR2_PREDIV1 | CFGR2_PREDIV1SRC);
439 tmpreg |= RCC_PREDIV1_Source | RCC_PREDIV1_Div ;
455 void RCC_PREDIV2Config(uint32_t RCC_PREDIV2_Div)
464 tmpreg &= ~CFGR2_PREDIV2;
466 tmpreg |= RCC_PREDIV2_Div;
480 void RCC_PLL2Config(uint32_t RCC_PLL2Mul)
489 tmpreg &= ~CFGR2_PLL2MUL;
491 tmpreg |= RCC_PLL2Mul;
511 *(
__IO uint32_t *) CR_PLL2ON_BB = (uint32_t)NewState;
524 void RCC_PLL3Config(uint32_t RCC_PLL3Mul)
533 tmpreg &= ~CFGR2_PLL3MUL;
535 tmpreg |= RCC_PLL3Mul;
552 *(
__IO uint32_t *) CR_PLL3ON_BB = (uint32_t)NewState;
574 tmpreg |= RCC_SYSCLKSource;
618 tmpreg |= RCC_SYSCLK;
670 tmpreg |= RCC_HCLK << 3;
747 void RCC_OTGFSCLKConfig(uint32_t RCC_OTGFSCLKSource)
750 assert_param(IS_RCC_OTGFSCLK_SOURCE(RCC_OTGFSCLKSource));
752 *(
__IO uint32_t *) CFGR_OTGFSPRE_BB = RCC_OTGFSCLKSource;
793 void RCC_I2S2CLKConfig(uint32_t RCC_I2S2CLKSource)
798 *(
__IO uint32_t *) CFGR2_I2S2SRC_BB = RCC_I2S2CLKSource;
812 void RCC_I2S3CLKConfig(uint32_t RCC_I2S3CLKSource)
817 *(
__IO uint32_t *) CFGR2_I2S3SRC_BB = RCC_I2S3CLKSource;
885 RCC->BDCR |= RCC_RTCCLKSource;
911 uint32_t tmp = 0, pllmull = 0, pllsource = 0, presc = 0;
914 uint32_t prediv1source = 0, prediv1factor = 0, prediv2factor = 0, pll2mull = 0;
917 #if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) 918 uint32_t prediv1factor = 0;
939 pllmull = ( pllmull >> 18) + 2;
941 if (pllsource == 0x00)
947 #if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) 948 prediv1factor = (
RCC->CFGR2 & CFGR2_PREDIV1) + 1;
964 pllmull = pllmull >> 18;
975 if (pllsource == 0x00)
983 prediv1source =
RCC->CFGR2 & CFGR2_PREDIV1SRC;
984 prediv1factor = (
RCC->CFGR2 & CFGR2_PREDIV1) + 1;
986 if (prediv1source == 0)
994 prediv2factor = ((
RCC->CFGR2 & CFGR2_PREDIV2) >> 4) + 1;
995 pll2mull = ((
RCC->CFGR2 & CFGR2_PLL2MUL) >> 8 ) + 2;
1073 RCC->AHBENR |= RCC_AHBPeriph;
1077 RCC->AHBENR &= ~RCC_AHBPeriph;
1103 RCC->APB2ENR |= RCC_APB2Periph;
1107 RCC->APB2ENR &= ~RCC_APB2Periph;
1134 RCC->APB1ENR |= RCC_APB1Periph;
1138 RCC->APB1ENR &= ~RCC_APB1Periph;
1162 RCC->AHBRSTR |= RCC_AHBPeriph;
1166 RCC->AHBRSTR &= ~RCC_AHBPeriph;
1193 RCC->APB2RSTR |= RCC_APB2Periph;
1197 RCC->APB2RSTR &= ~RCC_APB2Periph;
1224 RCC->APB1RSTR |= RCC_APB1Periph;
1228 RCC->APB1RSTR &= ~RCC_APB1Periph;
1330 uint32_t statusreg = 0;
1336 tmp = RCC_FLAG >> 5;
1339 statusreg =
RCC->CR;
1343 statusreg =
RCC->BDCR;
1347 statusreg =
RCC->CSR;
1352 if ((statusreg & ((uint32_t)1 << tmp)) != (uint32_t)
RESET)
1410 if ((
RCC->CIR & RCC_IT) != (uint32_t)
RESET)
#define IS_RCC_APB1_PERIPH(PERIPH)
#define CFGR_PLLMull_Mask
void RCC_PLLCmd(FunctionalState NewState)
Enables or disables the PLL.
void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState)
Enables or disables the specified RCC interrupts.
void RCC_PCLK1Config(uint32_t RCC_HCLK)
Configures the Low Speed APB clock (PCLK1).
#define IS_RCC_HCLK(HCLK)
ErrorStatus RCC_WaitForHSEStartUp(void)
Waits for HSE start-up.
void RCC_DeInit(void)
Resets the RCC clock configuration to the default reset state.
#define IS_RCC_RTCCLK_SOURCE(SOURCE)
void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul)
Configures the PLL clock source and multiplication factor.
void RCC_LSEConfig(uint8_t RCC_LSE)
Configures the External Low Speed oscillator (LSE).
#define CFGR_PPRE1_Set_Mask
FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG)
Checks whether the specified RCC flag is set or not.
void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource)
Configures the USB clock (USBCLK).
void RCC_ClockSecuritySystemCmd(FunctionalState NewState)
Enables or disables the Clock Security System.
void RCC_ClearITPendingBit(uint8_t RCC_IT)
Clears the RCC's interrupt pending bits.
void assert_param(int val)
#define CFGR_PPRE1_Reset_Mask
#define IS_RCC_CLEAR_IT(IT)
#define IS_FUNCTIONAL_STATE(STATE)
uint32_t ADCCLK_Frequency
#define IS_RCC_USBCLK_SOURCE(SOURCE)
static volatile uint8_t * status
#define HSE_STARTUP_TIMEOUT
Comment the line below if you will not use the peripherals drivers. In this case, these drivers will ...
#define CFGR_ADCPRE_Set_Mask
void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
Forces or releases Low Speed APB (APB1) peripheral reset.
#define IS_RCC_GET_IT(IT)
#define IS_RCC_CALIBRATION_VALUE(VALUE)
void RCC_RTCCLKCmd(FunctionalState NewState)
Enables or disables the RTC clock.
#define CFGR_PPRE2_Reset_Mask
void RCC_ClearFlag(void)
Clears the RCC reset flags.
void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource)
Configures the system clock (SYSCLK).
#define IS_RCC_APB2_PERIPH(PERIPH)
#define CIR_BYTE3_ADDRESS
#define CFGR_PLLXTPRE_Mask
#define HSE_VALUE
Comment the line below if you will not use the peripherals drivers. In this case, these drivers will ...
void RCC_HSICmd(FunctionalState NewState)
Enables or disables the Internal High Speed oscillator (HSI).
#define IS_RCC_PREDIV1(PREDIV1)
void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource)
Configures the RTC clock (RTCCLK).
void RCC_HSEConfig(uint32_t RCC_HSE)
Configures the External High Speed oscillator (HSE).
void RCC_PCLK2Config(uint32_t RCC_HCLK)
Configures the High Speed APB clock (PCLK2).
void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
Forces or releases High Speed APB (APB2) peripheral reset.
static __I uint8_t APBAHBPrescTable[16]
This file contains all the functions prototypes for the RCC firmware library.
void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue)
Adjusts the Internal High Speed oscillator (HSI) calibration value.
void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState)
Enables or disables the AHB peripheral clock.
ITStatus RCC_GetITStatus(uint8_t RCC_IT)
Checks whether the specified RCC interrupt has occurred or not.
void RCC_MCOConfig(uint8_t RCC_MCO)
Selects the clock source to output on MCO pin.
void RCC_HCLKConfig(uint32_t RCC_SYSCLK)
Configures the AHB clock (HCLK).
uint8_t RCC_GetSYSCLKSource(void)
Returns the clock source used as system clock.
void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Div)
Configures the PREDIV1 division factor.
#define IS_RCC_SYSCLK_SOURCE(SOURCE)
#define IS_RCC_PLL_MUL(MUL)
void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
Enables or disables the Low Speed APB (APB1) peripheral clock.
void RCC_GetClocksFreq(RCC_ClocksTypeDef *RCC_Clocks)
Returns the frequencies of different on chip clocks.
#define IS_RCC_FLAG(FLAG)
#define CFGR_PPRE2_Set_Mask
#define IS_RCC_PCLK(PCLK)
void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
Enables or disables the High Speed APB (APB2) peripheral clock.
void RCC_BackupResetCmd(FunctionalState NewState)
Forces or releases the Backup domain reset.
#define IS_RCC_ADCCLK(ADCCLK)
void RCC_ADCCLKConfig(uint32_t RCC_PCLK2)
Configures the ADC clock (ADCCLK).
uint32_t SYSCLK_Frequency
#define CFGR_HPRE_Reset_Mask
#define CFGR_BYTE4_ADDRESS
#define CFGR_HPRE_Set_Mask
#define CIR_BYTE2_ADDRESS
#define IS_RCC_AHB_PERIPH(PERIPH)
void RCC_LSICmd(FunctionalState NewState)
Enables or disables the Internal Low Speed oscillator (LSI).
static __I uint8_t ADCPrescTable[4]
#define IS_RCC_PLL_SOURCE(SOURCE)
#define CFGR_ADCPRE_Reset_Mask
void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState)
Forces or releases AHB peripheral reset.