59 #include "stm32f4xx_rcc.h" 73 #define RCC_OFFSET (RCC_BASE - PERIPH_BASE) 76 #define CR_OFFSET (RCC_OFFSET + 0x00) 77 #define HSION_BitNumber 0x00 78 #define CR_HSION_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (HSION_BitNumber * 4)) 80 #define CSSON_BitNumber 0x13 81 #define CR_CSSON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (CSSON_BitNumber * 4)) 83 #define PLLON_BitNumber 0x18 84 #define CR_PLLON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLON_BitNumber * 4)) 86 #define PLLI2SON_BitNumber 0x1A 87 #define CR_PLLI2SON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLI2SON_BitNumber * 4)) 91 #define CFGR_OFFSET (RCC_OFFSET + 0x08) 92 #define I2SSRC_BitNumber 0x17 93 #define CFGR_I2SSRC_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (I2SSRC_BitNumber * 4)) 97 #define BDCR_OFFSET (RCC_OFFSET + 0x70) 98 #define RTCEN_BitNumber 0x0F 99 #define BDCR_RTCEN_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (RTCEN_BitNumber * 4)) 101 #define BDRST_BitNumber 0x10 102 #define BDCR_BDRST_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (BDRST_BitNumber * 4)) 106 #define CSR_OFFSET (RCC_OFFSET + 0x74) 107 #define LSION_BitNumber 0x00 108 #define CSR_LSION_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (LSION_BitNumber * 4)) 112 #define DCKCFGR_OFFSET (RCC_OFFSET + 0x8C) 113 #define TIMPRE_BitNumber 0x18 114 #define DCKCFGR_TIMPRE_BB (PERIPH_BB_BASE + (DCKCFGR_OFFSET * 32) + (TIMPRE_BitNumber * 4)) 117 #define CFGR_MCO2_RESET_MASK ((uint32_t)0x07FFFFFF) 118 #define CFGR_MCO1_RESET_MASK ((uint32_t)0xF89FFFFF) 121 #define FLAG_MASK ((uint8_t)0x1F) 124 #define CR_BYTE3_ADDRESS ((uint32_t)0x40023802) 127 #define CIR_BYTE2_ADDRESS ((uint32_t)(RCC_BASE + 0x0C + 0x01)) 130 #define CIR_BYTE3_ADDRESS ((uint32_t)(RCC_BASE + 0x0C + 0x02)) 133 #define BDCR_ADDRESS (PERIPH_BASE + BDCR_OFFSET) 137 static __I uint8_t
APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};
208 RCC->CR |= (uint32_t)0x00000001;
211 RCC->CFGR = 0x00000000;
214 RCC->CR &= (uint32_t)0xFAF6FFFF;
217 RCC->PLLCFGR = 0x24003010;
220 RCC->PLLI2SCFGR = 0x20003000;
223 RCC->CR &= (uint32_t)0xFFFBFFFF;
226 RCC->CIR = 0x00000000;
230 RCC->DCKCFGR = 0x00000000;
281 __IO uint32_t startupcounter = 0;
322 tmpreg |= (uint32_t)HSICalibrationValue << 3;
454 void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP, uint32_t PLLQ)
463 RCC->PLLCFGR = PLLM | (PLLN << 6) | (((PLLP >> 1) -1) << 16) | (RCC_PLLSource) |
509 RCC->PLLI2SCFGR = (PLLI2SN << 6) | (PLLI2SR << 28);
561 void RCC_MCO1Config(uint32_t RCC_MCO1Source, uint32_t RCC_MCO1Div)
575 tmpreg |= RCC_MCO1Source | RCC_MCO1Div;
599 void RCC_MCO2Config(uint32_t RCC_MCO2Source, uint32_t RCC_MCO2Div)
613 tmpreg |= RCC_MCO2Source | RCC_MCO2Div;
719 tmpreg |= RCC_SYSCLKSource;
772 tmpreg |= RCC_SYSCLK;
835 tmpreg |= RCC_HCLK << 3;
876 uint32_t tmp = 0, presc = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2;
1001 uint32_t tmpreg = 0;
1006 if ((RCC_RTCCLKSource & 0x00000300) == 0x00000300)
1014 tmpreg |= (RCC_RTCCLKSource & 0xFFFFCFF);
1021 RCC->BDCR |= (RCC_RTCCLKSource & 0x00000FFF);
1138 RCC->AHB1ENR |= RCC_AHB1Periph;
1142 RCC->AHB1ENR &= ~RCC_AHB1Periph;
1170 RCC->AHB2ENR |= RCC_AHB2Periph;
1174 RCC->AHB2ENR &= ~RCC_AHB2Periph;
1198 RCC->AHB3ENR |= RCC_AHB3Periph;
1202 RCC->AHB3ENR &= ~RCC_AHB3Periph;
1250 RCC->APB1ENR |= RCC_APB1Periph;
1254 RCC->APB1ENR &= ~RCC_APB1Periph;
1293 RCC->APB2ENR |= RCC_APB2Periph;
1297 RCC->APB2ENR &= ~RCC_APB2Periph;
1332 RCC->AHB1RSTR |= RCC_AHB1Periph;
1336 RCC->AHB1RSTR &= ~RCC_AHB1Periph;
1361 RCC->AHB2RSTR |= RCC_AHB2Periph;
1365 RCC->AHB2RSTR &= ~RCC_AHB2Periph;
1386 RCC->AHB3RSTR |= RCC_AHB3Periph;
1390 RCC->AHB3RSTR &= ~RCC_AHB3Periph;
1434 RCC->APB1RSTR |= RCC_APB1Periph;
1438 RCC->APB1RSTR &= ~RCC_APB1Periph;
1473 RCC->APB2RSTR |= RCC_APB2Periph;
1477 RCC->APB2RSTR &= ~RCC_APB2Periph;
1519 RCC->AHB1LPENR |= RCC_AHB1Periph;
1523 RCC->AHB1LPENR &= ~RCC_AHB1Periph;
1551 RCC->AHB2LPENR |= RCC_AHB2Periph;
1555 RCC->AHB2LPENR &= ~RCC_AHB2Periph;
1579 RCC->AHB3LPENR |= RCC_AHB3Periph;
1583 RCC->AHB3LPENR &= ~RCC_AHB3Periph;
1631 RCC->APB1LPENR |= RCC_APB1Periph;
1635 RCC->APB1LPENR &= ~RCC_APB1Periph;
1674 RCC->APB2LPENR |= RCC_APB2Periph;
1678 RCC->APB2LPENR &= ~RCC_APB2Periph;
1752 uint32_t statusreg = 0;
1759 tmp = RCC_FLAG >> 5;
1762 statusreg =
RCC->CR;
1766 statusreg =
RCC->BDCR;
1770 statusreg =
RCC->CSR;
1775 if ((statusreg & ((uint32_t)1 << tmp)) != (uint32_t)
RESET)
1821 if ((
RCC->CIR & RCC_IT) != (uint32_t)
RESET)
void RCC_AHB1PeriphClockLPModeCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState)
Enables or disables the AHB1 peripheral clock during Low Power (Sleep) mode.
#define IS_RCC_APB1_PERIPH(PERIPH)
void RCC_MCO2Config(uint32_t RCC_MCO2Source, uint32_t RCC_MCO2Div)
Selects the clock source to output on MCO2 pin(PC9).
void RCC_AHB3PeriphClockLPModeCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState)
Enables or disables the AHB3 peripheral clock during Low Power (Sleep) mode.
#define IS_RCC_PLLQ_VALUE(VALUE)
void RCC_PLLI2SConfig(uint32_t PLLI2SN, uint32_t PLLI2SR)
Configures the PLLI2S clock multiplication and division factors.
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.
void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource)
Configures the RTC clock (RTCCLK).
#define IS_RCC_HCLK(HCLK)
#define CIR_BYTE3_ADDRESS
#define IS_RCC_AHB1_CLOCK_PERIPH(PERIPH)
void RCC_AHB3PeriphClockCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState)
Enables or disables the AHB3 peripheral clock.
#define IS_RCC_AHB1_LPMODE_PERIPH(PERIPH)
#define IS_RCC_MCO2SOURCE(SOURCE)
#define IS_RCC_PLLM_VALUE(VALUE)
#define IS_RCC_RTCCLK_SOURCE(SOURCE)
void RCC_AHB1PeriphResetCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState)
Forces or releases AHB1 peripheral reset.
void RCC_AHB3PeriphResetCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState)
Forces or releases AHB3 peripheral reset.
void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource)
Configures the system clock (SYSCLK).
void assert_param(int val)
void RCC_AHB1PeriphClockCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState)
Enables or disables the AHB1 peripheral clock.
void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
Enables or disables the High Speed APB (APB2) peripheral clock.
#define IS_RCC_MCO2DIV(DIV)
void RCC_BackupResetCmd(FunctionalState NewState)
Forces or releases the Backup domain reset.
#define CFGR_MCO2_RESET_MASK
#define IS_RCC_CLEAR_IT(IT)
#define IS_FUNCTIONAL_STATE(STATE)
static volatile uint8_t * status
#define IS_RCC_PLLN_VALUE(VALUE)
#define HSE_STARTUP_TIMEOUT
Comment the line below if you will not use the peripherals drivers. In this case, these drivers will ...
void RCC_APB1PeriphClockLPModeCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
Enables or disables the APB1 peripheral clock during Low Power (Sleep) mode.
#define IS_RCC_GET_IT(IT)
void RCC_PLLCmd(FunctionalState NewState)
Enables or disables the main PLL.
#define RCC_PLLCFGR_PLLSRC
#define IS_RCC_CALIBRATION_VALUE(VALUE)
ITStatus RCC_GetITStatus(uint8_t RCC_IT)
Checks whether the specified RCC interrupt has occurred or not.
void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
Forces or releases Low Speed APB (APB1) peripheral reset.
void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP, uint32_t PLLQ)
Configures the main PLL clock source, multiplication and division factors.
void RCC_AHB2PeriphClockCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState)
Enables or disables the AHB2 peripheral clock.
#define IS_RCC_PLLP_VALUE(VALUE)
#define IS_RCC_APB2_RESET_PERIPH(PERIPH)
void RCC_LSEConfig(uint8_t RCC_LSE)
Configures the External Low Speed oscillator (LSE).
#define IS_RCC_APB2_PERIPH(PERIPH)
void RCC_I2SCLKConfig(uint32_t RCC_I2SCLKSource)
Configures the I2S clock source (I2SCLK).
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 DCKCFGR_TIMPRE_BB
void RCC_PCLK1Config(uint32_t RCC_HCLK)
Configures the Low Speed APB clock (PCLK1).
void RCC_LSICmd(FunctionalState NewState)
Enables or disables the Internal Low Speed oscillator (LSI).
#define IS_RCC_PLLI2SR_VALUE(VALUE)
static __I uint8_t APBAHBPrescTable[16]
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).
#define IS_RCC_MCO1DIV(DIV)
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.
#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.
void RCC_PLLI2SCmd(FunctionalState NewState)
Enables or disables the PLLI2S.
#define CIR_BYTE2_ADDRESS
void RCC_HSEConfig(uint8_t RCC_HSE)
Configures the External High Speed oscillator (HSE).
void RCC_AHB2PeriphClockLPModeCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState)
Enables or disables the AHB2 peripheral clock during Low Power (Sleep) mode.
#define IS_RCC_I2SCLK_SOURCE(SOURCE)
#define IS_RCC_TIMCLK_PRESCALER(VALUE)
void RCC_ClearITPendingBit(uint8_t RCC_IT)
Clears the RCC's interrupt pending bits.
#define IS_RCC_FLAG(FLAG)
#define IS_RCC_MCO1SOURCE(SOURCE)
#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.
void RCC_APB2PeriphClockLPModeCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
Enables or disables the APB2 peripheral clock during Low Power (Sleep) mode.
uint32_t SYSCLK_Frequency
void RCC_MCO1Config(uint32_t RCC_MCO1Source, uint32_t RCC_MCO1Div)
Selects the clock source to output on MCO1 pin(PA8).
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_AHB3_PERIPH(PERIPH)
#define IS_RCC_AHB2_PERIPH(PERIPH)
void RCC_AHB2PeriphResetCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState)
Forces or releases AHB2 peripheral reset.
void RCC_HCLKConfig(uint32_t RCC_SYSCLK)
Configures the AHB clock (HCLK).
#define CFGR_MCO1_RESET_MASK
#define IS_RCC_PLLI2SN_VALUE(VALUE)
#define IS_RCC_PLL_SOURCE(SOURCE)
void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue)
Adjusts the Internal High Speed oscillator (HSI) calibration value.
#define IS_RCC_AHB1_RESET_PERIPH(PERIPH)
void RCC_TIMCLKPresConfig(uint32_t RCC_TIMCLKPrescaler)
Configures the Timers clocks prescalers selection.