72 #define RCC_OFFSET (RCC_BASE - PERIPH_BASE) 77 #define CR_OFFSET (RCC_OFFSET + 0x00) 78 #define HSION_BitNumber 0x00 79 #define CR_HSION_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (HSION_BitNumber * 4)) 82 #define PLLON_BitNumber 0x18 83 #define CR_PLLON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLON_BitNumber * 4)) 86 #define CSSON_BitNumber 0x13 87 #define CR_CSSON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (CSSON_BitNumber * 4)) 91 #define CFGR_OFFSET (RCC_OFFSET + 0x04) 92 #define USBPRE_BitNumber 0x16 93 #define CFGR_USBPRE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (USBPRE_BitNumber * 4)) 95 #define I2SSRC_BitNumber 0x17 96 #define CFGR_I2SSRC_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (I2SSRC_BitNumber * 4)) 101 #define BDCR_OFFSET (RCC_OFFSET + 0x20) 102 #define RTCEN_BitNumber 0x0F 103 #define BDCR_RTCEN_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (RTCEN_BitNumber * 4)) 106 #define BDRST_BitNumber 0x10 107 #define BDCR_BDRST_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (BDRST_BitNumber * 4)) 112 #define CSR_OFFSET (RCC_OFFSET + 0x24) 113 #define LSION_BitNumber 0x00 114 #define CSR_LSION_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (LSION_BitNumber * 4)) 118 #define FLAG_MASK ((uint8_t)0x1F) 121 #define CFGR_BYTE3_ADDRESS ((uint32_t)0x40021007) 124 #define CIR_BYTE2_ADDRESS ((uint32_t)0x40021009) 127 #define CIR_BYTE3_ADDRESS ((uint32_t)0x4002100A) 130 #define CR_BYTE2_ADDRESS ((uint32_t)0x40021002) 134 static __I uint8_t
APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};
135 static __I uint16_t
ADCPrescTable[16] = {1, 2, 4, 6, 8, 10, 12, 16, 32, 64, 128, 256, 0, 0, 0, 0 };
192 RCC->CR |= (uint32_t)0x00000001;
195 RCC->CFGR &= (uint32_t)0xF8FFC000;
198 RCC->CR &= (uint32_t)0xFEF6FFFF;
201 RCC->CR &= (uint32_t)0xFFFBFFFF;
204 RCC->CFGR &= (uint32_t)0xFF80FFFF;
207 RCC->CFGR2 &= (uint32_t)0xFFFFC000;
210 RCC->CFGR3 &= (uint32_t)0xF00ECCC;
213 RCC->CIR = 0x00000000;
263 __IO uint32_t StartUpCounter = 0;
308 tmpreg |= (uint32_t)HSICalibrationValue << 3;
367 RCC->BDCR |= RCC_LSE;
386 RCC->BDCR &= ~(RCC_BDCR_LSEDRV);
389 RCC->BDCR |= RCC_LSEDrive;
437 RCC->CFGR |= (uint32_t)(RCC_PLLSource | RCC_PLLMul);
475 tmpreg &= ~(RCC_CFGR2_PREDIV1);
478 tmpreg |= RCC_PREDIV1_Div;
533 tmpreg |= RCC_MCOSource<<24;
578 tmpreg &= ~(RCC_CFGR_MCO_PRE |
RCC_CFGR_MCO | RCC_CFGR_PLLNODIV);
580 tmpreg |= (RCC_MCOPrescaler | RCC_MCOSource<<24);
696 tmpreg |= RCC_SYSCLKSource;
749 tmpreg |= RCC_SYSCLK;
808 tmpreg |= RCC_HCLK << 3;
856 uint32_t tmp = 0, pllmull = 0, pllsource = 0, prediv1factor = 0, presc = 0, pllclk = 0;
857 uint32_t apb2presc = 0, ahbpresc = 0;
874 pllmull = ( pllmull >> 18) + 2;
876 if (pllsource == 0x00)
883 prediv1factor = (
RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1;
885 pllclk = (
HSE_VALUE / prediv1factor) * pllmull;
916 tmp =
RCC->CFGR2 & RCC_CFGR2_ADCPRE12;
919 if (((tmp & 0x10) != 0) && (presc != 0))
931 tmp =
RCC->CFGR2 & RCC_CFGR2_ADCPRE34;
934 if (((tmp & 0x10) != 0) && (presc != 0))
946 if((
RCC->CFGR3 & RCC_CFGR3_I2C1SW) != RCC_CFGR3_I2C1SW)
958 if((
RCC->CFGR3 & RCC_CFGR3_I2C2SW) != RCC_CFGR3_I2C2SW)
970 if((
RCC->CFGR3 & RCC_CFGR3_I2C3SW) != RCC_CFGR3_I2C3SW)
982 if(((
RCC->CFGR3 & RCC_CFGR3_TIM1SW) == RCC_CFGR3_TIM1SW)&& (RCC_Clocks->
SYSCLK_Frequency == pllclk) \
983 && (apb2presc == ahbpresc))
995 if(((
RCC->CFGR3 & RCC_CFGR3_HRTIM1SW) == RCC_CFGR3_HRTIM1SW)&& (RCC_Clocks->
SYSCLK_Frequency == pllclk) \
996 && (apb2presc == ahbpresc))
1008 if(((
RCC->CFGR3 & RCC_CFGR3_TIM8SW) == RCC_CFGR3_TIM8SW)&& (RCC_Clocks->
SYSCLK_Frequency == pllclk) \
1009 && (apb2presc == ahbpresc))
1021 if(((
RCC->CFGR3 & RCC_CFGR3_TIM15SW) == RCC_CFGR3_TIM15SW)&& (RCC_Clocks->
SYSCLK_Frequency == pllclk) \
1022 && (apb2presc == ahbpresc))
1034 if(((
RCC->CFGR3 & RCC_CFGR3_TIM16SW) == RCC_CFGR3_TIM16SW)&& (RCC_Clocks->
SYSCLK_Frequency == pllclk) \
1035 && (apb2presc == ahbpresc))
1047 if(((
RCC->CFGR3 & RCC_CFGR3_TIM17SW) == RCC_CFGR3_TIM17SW)&& (RCC_Clocks->
SYSCLK_Frequency == pllclk) \
1048 && (apb2presc == ahbpresc))
1060 if((
RCC->CFGR3 & RCC_CFGR3_USART1SW) == 0x0)
1062 #if defined(STM32F303x8) || defined(STM32F334x8) || defined(STM32F301x8) || defined(STM32F302x8) 1071 else if((
RCC->CFGR3 & RCC_CFGR3_USART1SW) == RCC_CFGR3_USART1SW_0)
1076 else if((
RCC->CFGR3 & RCC_CFGR3_USART1SW) == RCC_CFGR3_USART1SW_1)
1081 else if((
RCC->CFGR3 & RCC_CFGR3_USART1SW) == RCC_CFGR3_USART1SW)
1088 if((
RCC->CFGR3 & RCC_CFGR3_USART2SW) == 0x0)
1093 else if((
RCC->CFGR3 & RCC_CFGR3_USART2SW) == RCC_CFGR3_USART2SW_0)
1098 else if((
RCC->CFGR3 & RCC_CFGR3_USART2SW) == RCC_CFGR3_USART2SW_1)
1103 else if((
RCC->CFGR3 & RCC_CFGR3_USART2SW) == RCC_CFGR3_USART2SW)
1110 if((
RCC->CFGR3 & RCC_CFGR3_USART3SW) == 0x0)
1115 else if((
RCC->CFGR3 & RCC_CFGR3_USART3SW) == RCC_CFGR3_USART3SW_0)
1120 else if((
RCC->CFGR3 & RCC_CFGR3_USART3SW) == RCC_CFGR3_USART3SW_1)
1125 else if((
RCC->CFGR3 & RCC_CFGR3_USART3SW) == RCC_CFGR3_USART3SW)
1132 if((
RCC->CFGR3 & RCC_CFGR3_UART4SW) == 0x0)
1137 else if((
RCC->CFGR3 & RCC_CFGR3_UART4SW) == RCC_CFGR3_UART4SW_0)
1142 else if((
RCC->CFGR3 & RCC_CFGR3_UART4SW) == RCC_CFGR3_UART4SW_1)
1147 else if((
RCC->CFGR3 & RCC_CFGR3_UART4SW) == RCC_CFGR3_UART4SW)
1154 if((
RCC->CFGR3 & RCC_CFGR3_UART5SW) == 0x0)
1159 else if((
RCC->CFGR3 & RCC_CFGR3_UART5SW) == RCC_CFGR3_UART5SW_0)
1164 else if((
RCC->CFGR3 & RCC_CFGR3_UART5SW) == RCC_CFGR3_UART5SW_1)
1169 else if((
RCC->CFGR3 & RCC_CFGR3_UART5SW) == RCC_CFGR3_UART5SW)
1242 tmp = (RCC_PLLCLK >> 28);
1247 RCC->CFGR2 &= ~RCC_CFGR2_ADCPRE34;
1252 RCC->CFGR2 &= ~RCC_CFGR2_ADCPRE12;
1255 RCC->CFGR2 |= RCC_PLLCLK;
1275 tmp = (RCC_I2CCLK >> 28);
1281 RCC->CFGR3 &= ~RCC_CFGR3_I2C1SW;
1284 RCC->CFGR3 &= ~RCC_CFGR3_I2C2SW;
1287 RCC->CFGR3 &= ~RCC_CFGR3_I2C3SW;
1294 RCC->CFGR3 |= RCC_I2CCLK;
1318 tmp = (RCC_TIMCLK >> 28);
1325 RCC->CFGR3 &= ~RCC_CFGR3_TIM1SW;
1328 RCC->CFGR3 &= ~RCC_CFGR3_TIM8SW;
1331 RCC->CFGR3 &= ~RCC_CFGR3_TIM15SW;
1334 RCC->CFGR3 &= ~RCC_CFGR3_TIM16SW;
1337 RCC->CFGR3 &= ~RCC_CFGR3_TIM17SW;
1344 RCC->CFGR3 |= RCC_TIMCLK;
1367 RCC->CFGR3 &= ~RCC_CFGR3_HRTIM1SW;
1370 RCC->CFGR3 |= RCC_HRTIMCLK;
1392 tmp = (RCC_USARTCLK >> 28);
1398 RCC->CFGR3 &= ~RCC_CFGR3_USART1SW;
1401 RCC->CFGR3 &= ~RCC_CFGR3_USART2SW;
1404 RCC->CFGR3 &= ~RCC_CFGR3_USART3SW;
1407 RCC->CFGR3 &= ~RCC_CFGR3_UART4SW;
1410 RCC->CFGR3 &= ~RCC_CFGR3_UART5SW;
1417 RCC->CFGR3 |= RCC_USARTCLK;
1467 RCC->BDCR |= RCC_RTCCLKSource;
1553 RCC->AHBENR |= RCC_AHBPeriph;
1557 RCC->AHBENR &= ~RCC_AHBPeriph;
1589 RCC->APB2ENR |= RCC_APB2Periph;
1593 RCC->APB2ENR &= ~RCC_APB2Periph;
1635 RCC->APB1ENR |= RCC_APB1Periph;
1639 RCC->APB1ENR &= ~RCC_APB1Periph;
1668 RCC->AHBRSTR |= RCC_AHBPeriph;
1672 RCC->AHBRSTR &= ~RCC_AHBPeriph;
1701 RCC->APB2RSTR |= RCC_APB2Periph;
1705 RCC->APB2RSTR &= ~RCC_APB2Periph;
1744 RCC->APB1RSTR |= RCC_APB1Periph;
1748 RCC->APB1RSTR &= ~RCC_APB1Periph;
1827 uint32_t statusreg = 0;
1834 tmp = RCC_FLAG >> 5;
1838 statusreg =
RCC->CR;
1842 statusreg =
RCC->BDCR;
1846 statusreg =
RCC->CFGR;
1850 statusreg =
RCC->CSR;
1856 if ((statusreg & ((uint32_t)1 << tmp)) != (uint32_t)
RESET)
1901 if ((
RCC->CIR & RCC_IT) != (uint32_t)
RESET)
#define IS_RCC_APB1_PERIPH(PERIPH)
void RCC_ADCCLKConfig(uint32_t RCC_PLLCLK)
Configures the ADC clock (ADCCLK).
void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Div)
Configures the PREDIV1 division factor.
void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
Enables or disables the Low Speed APB (APB1) peripheral clock.
ErrorStatus RCC_WaitForHSEStartUp(void)
Waits for HSE start-up.
uint32_t HRTIM1CLK_Frequency
uint32_t USART3CLK_Frequency
void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource)
Configures the RTC clock (RTCCLK).
#define IS_RCC_HCLK(HCLK)
#define CIR_BYTE3_ADDRESS
#define IS_RCC_RTCCLK_SOURCE(SOURCE)
static __I uint16_t ADCPrescTable[16]
void RCC_TIMCLKConfig(uint32_t RCC_TIMCLK)
Configures the TIMx clock sources(TIMCLK).
void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource)
Configures the system clock (SYSCLK).
#define IS_RCC_USARTCLK(USARTCLK)
void assert_param(int val)
void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
Enables or disables the High Speed APB (APB2) peripheral clock.
uint32_t I2C3CLK_Frequency
uint32_t TIM16CLK_Frequency
#define IS_RCC_HRTIMCLK(HRTIMCLK)
void RCC_BackupResetCmd(FunctionalState NewState)
Forces or releases the Backup domain reset.
#define IS_RCC_CLEAR_IT(IT)
#define IS_FUNCTIONAL_STATE(STATE)
#define IS_RCC_USBCLK_SOURCE(SOURCE)
uint32_t TIM15CLK_Frequency
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 IS_RCC_GET_IT(IT)
void RCC_PLLCmd(FunctionalState NewState)
Enables or disables the main PLL.
uint32_t USART2CLK_Frequency
ITStatus RCC_GetITStatus(uint8_t RCC_IT)
Checks whether the specified RCC interrupt has occurred or not.
uint32_t UART4CLK_Frequency
void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
Forces or releases Low Speed APB (APB1) peripheral reset.
#define IS_RCC_AHB_RST_PERIPH(PERIPH)
This file contains all the functions prototypes for the RCC firmware library.
void RCC_I2CCLKConfig(uint32_t RCC_I2CCLK)
Configures the I2C clock (I2CCLK).
uint32_t USART1CLK_Frequency
#define IS_RCC_APB2_PERIPH(PERIPH)
void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource)
Configures the USB clock (USBCLK).
#define IS_RCC_LSE_DRIVE(DRIVE)
void RCC_RTCCLKCmd(FunctionalState NewState)
Enables or disables the RTC clock.
#define HSE_VALUE
Comment the line below if you will not use the peripherals drivers. In this case, these drivers will ...
#define IS_RCC_PREDIV1(PREDIV1)
void RCC_PCLK1Config(uint32_t RCC_HCLK)
Configures the Low Speed APB clock (PCLK1).
void RCC_I2SCLKConfig(uint32_t RCC_I2SCLKSource)
Configures the I2S clock source (I2SCLK).
uint32_t TIM17CLK_Frequency
void RCC_LSICmd(FunctionalState NewState)
Enables or disables the Internal Low Speed oscillator (LSI).
#define IS_RCC_HSI_CALIBRATION_VALUE(VALUE)
uint32_t I2C2CLK_Frequency
uint32_t I2C1CLK_Frequency
void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState)
Forces or releases AHB peripheral reset.
static __I uint8_t APBAHBPrescTable[16]
uint32_t ADC34CLK_Frequency
void RCC_DeInit(void)
Resets the RCC clock configuration to the default reset state.
void RCC_HSICmd(FunctionalState NewState)
Enables or disables the Internal High Speed oscillator (HSI).
void RCC_PCLK2Config(uint32_t RCC_HCLK)
Configures the High Speed APB clock (PCLK2).
uint32_t TIM1CLK_Frequency
void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
Forces or releases High Speed APB (APB2) peripheral reset.
void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState)
Enables or disables the AHB peripheral clock.
#define IS_RCC_SYSCLK_SOURCE(SOURCE)
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.
void RCC_ClockSecuritySystemCmd(FunctionalState NewState)
Enables or disables the Clock Security System.
#define IS_RCC_PLL_MUL(MUL)
#define CIR_BYTE2_ADDRESS
uint32_t ADC12CLK_Frequency
void RCC_HSEConfig(uint8_t RCC_HSE)
Configures the External High Speed oscillator (HSE).
uint32_t UART5CLK_Frequency
#define IS_RCC_MCO_SOURCE(SOURCE)
#define IS_RCC_I2SCLK_SOURCE(SOURCE)
void RCC_ClearITPendingBit(uint8_t RCC_IT)
Clears the RCC's interrupt pending bits.
#define IS_RCC_FLAG(FLAG)
#define IS_RCC_PCLK(PCLK)
FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG)
Checks whether the specified RCC flag is set or not.
void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState)
Enables or disables the specified RCC interrupts.
#define IS_RCC_ADCCLK(ADCCLK)
void RCC_HRTIM1CLKConfig(uint32_t RCC_HRTIMCLK)
Configures the HRTIM1 clock sources(HRTIM1CLK).
uint32_t SYSCLK_Frequency
void RCC_GetClocksFreq(RCC_ClocksTypeDef *RCC_Clocks)
Returns the frequencies of different on chip clocks; SYSCLK, HCLK, PCLK1 and PCLK2.
uint8_t RCC_GetSYSCLKSource(void)
Returns the clock source used as system clock.
#define IS_RCC_I2CCLK(I2CCLK)
void RCC_LSEDriveConfig(uint32_t RCC_LSEDrive)
Configures the External Low Speed oscillator (LSE) drive capability.
void RCC_LSEConfig(uint32_t RCC_LSE)
Configures the External Low Speed oscillator (LSE).
void RCC_HCLKConfig(uint32_t RCC_SYSCLK)
Configures the AHB clock (HCLK).
#define IS_RCC_AHB_PERIPH(PERIPH)
#define IS_RCC_PLL_SOURCE(SOURCE)
void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul)
Configures the PLL clock source and multiplication factor.
uint32_t TIM8CLK_Frequency
void RCC_USARTCLKConfig(uint32_t RCC_USARTCLK)
Configures the USART clock (USARTCLK).
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.
#define IS_RCC_MCO_PRESCALER(PRESCALER)
void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue)
Adjusts the Internal High Speed oscillator (HSI) calibration value.
#define IS_RCC_TIMCLK(TIMCLK)