stm32f10x_rcc.c
Go to the documentation of this file.
1 
22 /* Includes ------------------------------------------------------------------*/
23 #include "stm32f10x_rcc.h"
24 
46 /* ------------ RCC registers bit address in the alias region ----------- */
47 #define RCC_OFFSET (RCC_BASE - PERIPH_BASE)
48 
49 /* --- CR Register ---*/
50 
51 /* Alias word address of HSION bit */
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))
55 
56 /* Alias word address of PLLON bit */
57 #define PLLON_BitNumber 0x18
58 #define CR_PLLON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLON_BitNumber * 4))
59 
60 #ifdef STM32F10X_CL
61  /* Alias word address of PLL2ON bit */
62  #define PLL2ON_BitNumber 0x1A
63  #define CR_PLL2ON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLL2ON_BitNumber * 4))
64 
65  /* Alias word address of PLL3ON bit */
66  #define PLL3ON_BitNumber 0x1C
67  #define CR_PLL3ON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLL3ON_BitNumber * 4))
68 #endif /* STM32F10X_CL */
69 
70 /* Alias word address of CSSON bit */
71 #define CSSON_BitNumber 0x13
72 #define CR_CSSON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (CSSON_BitNumber * 4))
73 
74 /* --- CFGR Register ---*/
75 
76 /* Alias word address of USBPRE bit */
77 #define CFGR_OFFSET (RCC_OFFSET + 0x04)
78 
79 #ifndef STM32F10X_CL
80  #define USBPRE_BitNumber 0x16
81  #define CFGR_USBPRE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (USBPRE_BitNumber * 4))
82 #else
83  #define OTGFSPRE_BitNumber 0x16
84  #define CFGR_OTGFSPRE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (OTGFSPRE_BitNumber * 4))
85 #endif /* STM32F10X_CL */
86 
87 /* --- BDCR Register ---*/
88 
89 /* Alias word address of RTCEN bit */
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))
93 
94 /* Alias word address of BDRST bit */
95 #define BDRST_BitNumber 0x10
96 #define BDCR_BDRST_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (BDRST_BitNumber * 4))
97 
98 /* --- CSR Register ---*/
99 
100 /* Alias word address of LSION bit */
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))
104 
105 #ifdef STM32F10X_CL
106 /* --- CFGR2 Register ---*/
107 
108  /* Alias word address of I2S2SRC bit */
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))
112 
113  /* Alias word address of I2S3SRC bit */
114  #define I2S3SRC_BitNumber 0x12
115  #define CFGR2_I2S3SRC_BB (PERIPH_BB_BASE + (CFGR2_OFFSET * 32) + (I2S3SRC_BitNumber * 4))
116 #endif /* STM32F10X_CL */
117 
118 /* ---------------------- RCC registers bit mask ------------------------ */
119 
120 /* CR register bit mask */
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)
126 
127 /* CFGR register bit mask */
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)
130 #else
131  #define CFGR_PLL_Mask ((uint32_t)0xFFC0FFFF)
132 #endif /* STM32F10X_CL */
133 
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)
147 
148 /* CSR register bit mask */
149 #define CSR_RMVF_Set ((uint32_t)0x01000000)
150 
151 #if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL)
152 /* CFGR2 register bit mask */
153  #define CFGR2_PREDIV1SRC ((uint32_t)0x00010000)
154  #define CFGR2_PREDIV1 ((uint32_t)0x0000000F)
155 #endif
156 #ifdef STM32F10X_CL
157  #define CFGR2_PREDIV2 ((uint32_t)0x000000F0)
158  #define CFGR2_PLL2MUL ((uint32_t)0x00000F00)
159  #define CFGR2_PLL3MUL ((uint32_t)0x0000F000)
160 #endif /* STM32F10X_CL */
161 
162 /* RCC Flag Mask */
163 #define FLAG_Mask ((uint8_t)0x1F)
164 
165 /* CIR register byte 2 (Bits[15:8]) base address */
166 #define CIR_BYTE2_ADDRESS ((uint32_t)0x40021009)
167 
168 /* CIR register byte 3 (Bits[23:16]) base address */
169 #define CIR_BYTE3_ADDRESS ((uint32_t)0x4002100A)
170 
171 /* CFGR register byte 4 (Bits[31:24]) base address */
172 #define CFGR_BYTE4_ADDRESS ((uint32_t)0x40021007)
173 
174 /* BDCR register base address */
175 #define BDCR_ADDRESS (PERIPH_BASE + BDCR_OFFSET)
176 
193 static __I uint8_t APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};
194 static __I uint8_t ADCPrescTable[4] = {2, 4, 6, 8};
195 extern uint32_t hse_value;
196 
218 void RCC_DeInit(void)
219 {
220  /* Set HSION bit */
221  RCC->CR |= (uint32_t)0x00000001;
222 
223  /* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */
224 #ifndef STM32F10X_CL
225  RCC->CFGR &= (uint32_t)0xF8FF0000;
226 #else
227  RCC->CFGR &= (uint32_t)0xF0FF0000;
228 #endif /* STM32F10X_CL */
229 
230  /* Reset HSEON, CSSON and PLLON bits */
231  RCC->CR &= (uint32_t)0xFEF6FFFF;
232 
233  /* Reset HSEBYP bit */
234  RCC->CR &= (uint32_t)0xFFFBFFFF;
235 
236  /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE/OTGFSPRE bits */
237  RCC->CFGR &= (uint32_t)0xFF80FFFF;
238 
239 #ifdef STM32F10X_CL
240  /* Reset PLL2ON and PLL3ON bits */
241  RCC->CR &= (uint32_t)0xEBFFFFFF;
242 
243  /* Disable all interrupts and clear pending bits */
244  RCC->CIR = 0x00FF0000;
245 
246  /* Reset CFGR2 register */
247  RCC->CFGR2 = 0x00000000;
248 #elif defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL)
249  /* Disable all interrupts and clear pending bits */
250  RCC->CIR = 0x009F0000;
251 
252  /* Reset CFGR2 register */
253  RCC->CFGR2 = 0x00000000;
254 #else
255  /* Disable all interrupts and clear pending bits */
256  RCC->CIR = 0x009F0000;
257 #endif /* STM32F10X_CL */
258 
259 }
260 
271 void RCC_HSEConfig(uint32_t RCC_HSE)
272 {
273  /* Check the parameters */
274  assert_param(IS_RCC_HSE(RCC_HSE));
275  /* Reset HSEON and HSEBYP bits before configuring the HSE ------------------*/
276  /* Reset HSEON bit */
277  RCC->CR &= CR_HSEON_Reset;
278  /* Reset HSEBYP bit */
279  RCC->CR &= CR_HSEBYP_Reset;
280  /* Configure HSE (RCC_HSE_OFF is already covered by the code section above) */
281  switch(RCC_HSE)
282  {
283  case RCC_HSE_ON:
284  /* Set HSEON bit */
285  RCC->CR |= CR_HSEON_Set;
286  break;
287 
288  case RCC_HSE_Bypass:
289  /* Set HSEBYP and HSEON bits */
290  RCC->CR |= CR_HSEBYP_Set | CR_HSEON_Set;
291  break;
292 
293  default:
294  break;
295  }
296 }
297 
306 {
307  __IO uint32_t StartUpCounter = 0;
309  FlagStatus HSEStatus = RESET;
310 
311  /* Wait till HSE is ready and if Time out is reached exit */
312  do
313  {
314  HSEStatus = RCC_GetFlagStatus(RCC_FLAG_HSERDY);
315  StartUpCounter++;
316  } while((StartUpCounter != HSE_STARTUP_TIMEOUT) && (HSEStatus == RESET));
317 
319  {
320  status = SUCCESS;
321  }
322  else
323  {
324  status = ERROR;
325  }
326  return (status);
327 }
328 
335 void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue)
336 {
337  uint32_t tmpreg = 0;
338  /* Check the parameters */
339  assert_param(IS_RCC_CALIBRATION_VALUE(HSICalibrationValue));
340  tmpreg = RCC->CR;
341  /* Clear HSITRIM[4:0] bits */
342  tmpreg &= CR_HSITRIM_Mask;
343  /* Set the HSITRIM[4:0] bits according to HSICalibrationValue value */
344  tmpreg |= (uint32_t)HSICalibrationValue << 3;
345  /* Store the new value */
346  RCC->CR = tmpreg;
347 }
348 
356 {
357  /* Check the parameters */
359  *(__IO uint32_t *) CR_HSION_BB = (uint32_t)NewState;
360 }
361 
379 void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul)
380 {
381  uint32_t tmpreg = 0;
382 
383  /* Check the parameters */
384  assert_param(IS_RCC_PLL_SOURCE(RCC_PLLSource));
385  assert_param(IS_RCC_PLL_MUL(RCC_PLLMul));
386 
387  tmpreg = RCC->CFGR;
388  /* Clear PLLSRC, PLLXTPRE and PLLMUL[3:0] bits */
389  tmpreg &= CFGR_PLL_Mask;
390  /* Set the PLL configuration bits */
391  tmpreg |= RCC_PLLSource | RCC_PLLMul;
392  /* Store the new value */
393  RCC->CFGR = tmpreg;
394 }
395 
403 {
404  /* Check the parameters */
406 
407  *(__IO uint32_t *) CR_PLLON_BB = (uint32_t)NewState;
408 }
409 
410 #if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL)
411 
427 void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Source, uint32_t RCC_PREDIV1_Div)
428 {
429  uint32_t tmpreg = 0;
430 
431  /* Check the parameters */
432  assert_param(IS_RCC_PREDIV1_SOURCE(RCC_PREDIV1_Source));
433  assert_param(IS_RCC_PREDIV1(RCC_PREDIV1_Div));
434 
435  tmpreg = RCC->CFGR2;
436  /* Clear PREDIV1[3:0] and PREDIV1SRC bits */
437  tmpreg &= ~(CFGR2_PREDIV1 | CFGR2_PREDIV1SRC);
438  /* Set the PREDIV1 clock source and division factor */
439  tmpreg |= RCC_PREDIV1_Source | RCC_PREDIV1_Div ;
440  /* Store the new value */
441  RCC->CFGR2 = tmpreg;
442 }
443 #endif
444 
445 #ifdef STM32F10X_CL
446 
455 void RCC_PREDIV2Config(uint32_t RCC_PREDIV2_Div)
456 {
457  uint32_t tmpreg = 0;
458 
459  /* Check the parameters */
460  assert_param(IS_RCC_PREDIV2(RCC_PREDIV2_Div));
461 
462  tmpreg = RCC->CFGR2;
463  /* Clear PREDIV2[3:0] bits */
464  tmpreg &= ~CFGR2_PREDIV2;
465  /* Set the PREDIV2 division factor */
466  tmpreg |= RCC_PREDIV2_Div;
467  /* Store the new value */
468  RCC->CFGR2 = tmpreg;
469 }
470 
480 void RCC_PLL2Config(uint32_t RCC_PLL2Mul)
481 {
482  uint32_t tmpreg = 0;
483 
484  /* Check the parameters */
485  assert_param(IS_RCC_PLL2_MUL(RCC_PLL2Mul));
486 
487  tmpreg = RCC->CFGR2;
488  /* Clear PLL2Mul[3:0] bits */
489  tmpreg &= ~CFGR2_PLL2MUL;
490  /* Set the PLL2 configuration bits */
491  tmpreg |= RCC_PLL2Mul;
492  /* Store the new value */
493  RCC->CFGR2 = tmpreg;
494 }
495 
496 
506 void RCC_PLL2Cmd(FunctionalState NewState)
507 {
508  /* Check the parameters */
510 
511  *(__IO uint32_t *) CR_PLL2ON_BB = (uint32_t)NewState;
512 }
513 
514 
524 void RCC_PLL3Config(uint32_t RCC_PLL3Mul)
525 {
526  uint32_t tmpreg = 0;
527 
528  /* Check the parameters */
529  assert_param(IS_RCC_PLL3_MUL(RCC_PLL3Mul));
530 
531  tmpreg = RCC->CFGR2;
532  /* Clear PLL3Mul[3:0] bits */
533  tmpreg &= ~CFGR2_PLL3MUL;
534  /* Set the PLL3 configuration bits */
535  tmpreg |= RCC_PLL3Mul;
536  /* Store the new value */
537  RCC->CFGR2 = tmpreg;
538 }
539 
540 
547 void RCC_PLL3Cmd(FunctionalState NewState)
548 {
549  /* Check the parameters */
550 
552  *(__IO uint32_t *) CR_PLL3ON_BB = (uint32_t)NewState;
553 }
554 #endif /* STM32F10X_CL */
555 
565 void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource)
566 {
567  uint32_t tmpreg = 0;
568  /* Check the parameters */
569  assert_param(IS_RCC_SYSCLK_SOURCE(RCC_SYSCLKSource));
570  tmpreg = RCC->CFGR;
571  /* Clear SW[1:0] bits */
572  tmpreg &= CFGR_SW_Mask;
573  /* Set SW[1:0] bits according to RCC_SYSCLKSource value */
574  tmpreg |= RCC_SYSCLKSource;
575  /* Store the new value */
576  RCC->CFGR = tmpreg;
577 }
578 
588 uint8_t RCC_GetSYSCLKSource(void)
589 {
590  return ((uint8_t)(RCC->CFGR & CFGR_SWS_Mask));
591 }
592 
609 void RCC_HCLKConfig(uint32_t RCC_SYSCLK)
610 {
611  uint32_t tmpreg = 0;
612  /* Check the parameters */
613  assert_param(IS_RCC_HCLK(RCC_SYSCLK));
614  tmpreg = RCC->CFGR;
615  /* Clear HPRE[3:0] bits */
616  tmpreg &= CFGR_HPRE_Reset_Mask;
617  /* Set HPRE[3:0] bits according to RCC_SYSCLK value */
618  tmpreg |= RCC_SYSCLK;
619  /* Store the new value */
620  RCC->CFGR = tmpreg;
621 }
622 
635 void RCC_PCLK1Config(uint32_t RCC_HCLK)
636 {
637  uint32_t tmpreg = 0;
638  /* Check the parameters */
639  assert_param(IS_RCC_PCLK(RCC_HCLK));
640  tmpreg = RCC->CFGR;
641  /* Clear PPRE1[2:0] bits */
642  tmpreg &= CFGR_PPRE1_Reset_Mask;
643  /* Set PPRE1[2:0] bits according to RCC_HCLK value */
644  tmpreg |= RCC_HCLK;
645  /* Store the new value */
646  RCC->CFGR = tmpreg;
647 }
648 
661 void RCC_PCLK2Config(uint32_t RCC_HCLK)
662 {
663  uint32_t tmpreg = 0;
664  /* Check the parameters */
665  assert_param(IS_RCC_PCLK(RCC_HCLK));
666  tmpreg = RCC->CFGR;
667  /* Clear PPRE2[2:0] bits */
668  tmpreg &= CFGR_PPRE2_Reset_Mask;
669  /* Set PPRE2[2:0] bits according to RCC_HCLK value */
670  tmpreg |= RCC_HCLK << 3;
671  /* Store the new value */
672  RCC->CFGR = tmpreg;
673 }
674 
701 void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState)
702 {
703  /* Check the parameters */
704  assert_param(IS_RCC_IT(RCC_IT));
706  if (NewState != DISABLE)
707  {
708  /* Perform Byte access to RCC_CIR bits to enable the selected interrupts */
709  *(__IO uint8_t *) CIR_BYTE2_ADDRESS |= RCC_IT;
710  }
711  else
712  {
713  /* Perform Byte access to RCC_CIR bits to disable the selected interrupts */
714  *(__IO uint8_t *) CIR_BYTE2_ADDRESS &= (uint8_t)~RCC_IT;
715  }
716 }
717 
718 #ifndef STM32F10X_CL
719 
729 void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource)
730 {
731  /* Check the parameters */
732  assert_param(IS_RCC_USBCLK_SOURCE(RCC_USBCLKSource));
733 
734  *(__IO uint32_t *) CFGR_USBPRE_BB = RCC_USBCLKSource;
735 }
736 #else
737 
747 void RCC_OTGFSCLKConfig(uint32_t RCC_OTGFSCLKSource)
748 {
749  /* Check the parameters */
750  assert_param(IS_RCC_OTGFSCLK_SOURCE(RCC_OTGFSCLKSource));
751 
752  *(__IO uint32_t *) CFGR_OTGFSPRE_BB = RCC_OTGFSCLKSource;
753 }
754 #endif /* STM32F10X_CL */
755 
767 void RCC_ADCCLKConfig(uint32_t RCC_PCLK2)
768 {
769  uint32_t tmpreg = 0;
770  /* Check the parameters */
771  assert_param(IS_RCC_ADCCLK(RCC_PCLK2));
772  tmpreg = RCC->CFGR;
773  /* Clear ADCPRE[1:0] bits */
774  tmpreg &= CFGR_ADCPRE_Reset_Mask;
775  /* Set ADCPRE[1:0] bits according to RCC_PCLK2 value */
776  tmpreg |= RCC_PCLK2;
777  /* Store the new value */
778  RCC->CFGR = tmpreg;
779 }
780 
781 #ifdef STM32F10X_CL
782 
793 void RCC_I2S2CLKConfig(uint32_t RCC_I2S2CLKSource)
794 {
795  /* Check the parameters */
796  assert_param(IS_RCC_I2S2CLK_SOURCE(RCC_I2S2CLKSource));
797 
798  *(__IO uint32_t *) CFGR2_I2S2SRC_BB = RCC_I2S2CLKSource;
799 }
800 
812 void RCC_I2S3CLKConfig(uint32_t RCC_I2S3CLKSource)
813 {
814  /* Check the parameters */
815  assert_param(IS_RCC_I2S3CLK_SOURCE(RCC_I2S3CLKSource));
816 
817  *(__IO uint32_t *) CFGR2_I2S3SRC_BB = RCC_I2S3CLKSource;
818 }
819 #endif /* STM32F10X_CL */
820 
830 void RCC_LSEConfig(uint8_t RCC_LSE)
831 {
832  /* Check the parameters */
833  assert_param(IS_RCC_LSE(RCC_LSE));
834  /* Reset LSEON and LSEBYP bits before configuring the LSE ------------------*/
835  /* Reset LSEON bit */
836  *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_OFF;
837  /* Reset LSEBYP bit */
838  *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_OFF;
839  /* Configure LSE (RCC_LSE_OFF is already covered by the code section above) */
840  switch(RCC_LSE)
841  {
842  case RCC_LSE_ON:
843  /* Set LSEON bit */
844  *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_ON;
845  break;
846 
847  case RCC_LSE_Bypass:
848  /* Set LSEBYP and LSEON bits */
849  *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_Bypass | RCC_LSE_ON;
850  break;
851 
852  default:
853  break;
854  }
855 }
856 
864 {
865  /* Check the parameters */
867  *(__IO uint32_t *) CSR_LSION_BB = (uint32_t)NewState;
868 }
869 
880 void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource)
881 {
882  /* Check the parameters */
883  assert_param(IS_RCC_RTCCLK_SOURCE(RCC_RTCCLKSource));
884  /* Select the RTC clock source */
885  RCC->BDCR |= RCC_RTCCLKSource;
886 }
887 
895 {
896  /* Check the parameters */
898  *(__IO uint32_t *) BDCR_RTCEN_BB = (uint32_t)NewState;
899 }
900 
910 {
911  uint32_t tmp = 0, pllmull = 0, pllsource = 0, presc = 0;
912 
913 #ifdef STM32F10X_CL
914  uint32_t prediv1source = 0, prediv1factor = 0, prediv2factor = 0, pll2mull = 0;
915 #endif /* STM32F10X_CL */
916 
917 #if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL)
918  uint32_t prediv1factor = 0;
919 #endif
920 
921  /* Get SYSCLK source -------------------------------------------------------*/
922  tmp = RCC->CFGR & CFGR_SWS_Mask;
923 
924  switch (tmp)
925  {
926  case 0x00: /* HSI used as system clock */
927  RCC_Clocks->SYSCLK_Frequency = HSI_VALUE;
928  break;
929  case 0x04: /* HSE used as system clock */
930  RCC_Clocks->SYSCLK_Frequency = hse_value;
931  break;
932  case 0x08: /* PLL used as system clock */
933 
934  /* Get PLL clock source and multiplication factor ----------------------*/
935  pllmull = RCC->CFGR & CFGR_PLLMull_Mask;
936  pllsource = RCC->CFGR & CFGR_PLLSRC_Mask;
937 
938 #ifndef STM32F10X_CL
939  pllmull = ( pllmull >> 18) + 2;
940 
941  if (pllsource == 0x00)
942  {/* HSI oscillator clock divided by 2 selected as PLL clock entry */
943  RCC_Clocks->SYSCLK_Frequency = (HSI_VALUE >> 1) * pllmull;
944  }
945  else
946  {
947  #if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL)
948  prediv1factor = (RCC->CFGR2 & CFGR2_PREDIV1) + 1;
949  /* HSE oscillator clock selected as PREDIV1 clock entry */
950  RCC_Clocks->SYSCLK_Frequency = (HSE_VALUE / prediv1factor) * pllmull;
951  #else
952  /* HSE selected as PLL clock entry */
953  if ((RCC->CFGR & CFGR_PLLXTPRE_Mask) != (uint32_t)RESET)
954  {/* HSE oscillator clock divided by 2 */
955  RCC_Clocks->SYSCLK_Frequency = (hse_value >> 1) * pllmull;
956  }
957  else
958  {
959  RCC_Clocks->SYSCLK_Frequency = hse_value * pllmull;
960  }
961  #endif
962  }
963 #else
964  pllmull = pllmull >> 18;
965 
966  if (pllmull != 0x0D)
967  {
968  pllmull += 2;
969  }
970  else
971  { /* PLL multiplication factor = PLL input clock * 6.5 */
972  pllmull = 13 / 2;
973  }
974 
975  if (pllsource == 0x00)
976  {/* HSI oscillator clock divided by 2 selected as PLL clock entry */
977  RCC_Clocks->SYSCLK_Frequency = (hse_value >> 1) * pllmull;
978  }
979  else
980  {/* PREDIV1 selected as PLL clock entry */
981 
982  /* Get PREDIV1 clock source and division factor */
983  prediv1source = RCC->CFGR2 & CFGR2_PREDIV1SRC;
984  prediv1factor = (RCC->CFGR2 & CFGR2_PREDIV1) + 1;
985 
986  if (prediv1source == 0)
987  { /* HSE oscillator clock selected as PREDIV1 clock entry */
988  RCC_Clocks->SYSCLK_Frequency = (hse_value / prediv1factor) * pllmull;
989  }
990  else
991  {/* PLL2 clock selected as PREDIV1 clock entry */
992 
993  /* Get PREDIV2 division factor and PLL2 multiplication factor */
994  prediv2factor = ((RCC->CFGR2 & CFGR2_PREDIV2) >> 4) + 1;
995  pll2mull = ((RCC->CFGR2 & CFGR2_PLL2MUL) >> 8 ) + 2;
996  RCC_Clocks->SYSCLK_Frequency = (((hse_value / prediv2factor) * pll2mull) / prediv1factor) * pllmull;
997  }
998  }
999 #endif /* STM32F10X_CL */
1000  break;
1001 
1002  default:
1003  RCC_Clocks->SYSCLK_Frequency = HSI_VALUE;
1004  break;
1005  }
1006 
1007  /* Compute HCLK, PCLK1, PCLK2 and ADCCLK clocks frequencies ----------------*/
1008  /* Get HCLK prescaler */
1009  tmp = RCC->CFGR & CFGR_HPRE_Set_Mask;
1010  tmp = tmp >> 4;
1011  presc = APBAHBPrescTable[tmp];
1012  /* HCLK clock frequency */
1013  RCC_Clocks->HCLK_Frequency = RCC_Clocks->SYSCLK_Frequency >> presc;
1014  /* Get PCLK1 prescaler */
1015  tmp = RCC->CFGR & CFGR_PPRE1_Set_Mask;
1016  tmp = tmp >> 8;
1017  presc = APBAHBPrescTable[tmp];
1018  /* PCLK1 clock frequency */
1019  RCC_Clocks->PCLK1_Frequency = RCC_Clocks->HCLK_Frequency >> presc;
1020  /* Get PCLK2 prescaler */
1021  tmp = RCC->CFGR & CFGR_PPRE2_Set_Mask;
1022  tmp = tmp >> 11;
1023  presc = APBAHBPrescTable[tmp];
1024  /* PCLK2 clock frequency */
1025  RCC_Clocks->PCLK2_Frequency = RCC_Clocks->HCLK_Frequency >> presc;
1026  /* Get ADCCLK prescaler */
1027  tmp = RCC->CFGR & CFGR_ADCPRE_Set_Mask;
1028  tmp = tmp >> 14;
1029  presc = ADCPrescTable[tmp];
1030  /* ADCCLK clock frequency */
1031  RCC_Clocks->ADCCLK_Frequency = RCC_Clocks->PCLK2_Frequency / presc;
1032 }
1033 
1065 void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState)
1066 {
1067  /* Check the parameters */
1068  assert_param(IS_RCC_AHB_PERIPH(RCC_AHBPeriph));
1069  assert_param(IS_FUNCTIONAL_STATE(NewState));
1070 
1071  if (NewState != DISABLE)
1072  {
1073  RCC->AHBENR |= RCC_AHBPeriph;
1074  }
1075  else
1076  {
1077  RCC->AHBENR &= ~RCC_AHBPeriph;
1078  }
1079 }
1080 
1096 void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
1097 {
1098  /* Check the parameters */
1099  assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph));
1100  assert_param(IS_FUNCTIONAL_STATE(NewState));
1101  if (NewState != DISABLE)
1102  {
1103  RCC->APB2ENR |= RCC_APB2Periph;
1104  }
1105  else
1106  {
1107  RCC->APB2ENR &= ~RCC_APB2Periph;
1108  }
1109 }
1110 
1127 void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
1128 {
1129  /* Check the parameters */
1130  assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph));
1131  assert_param(IS_FUNCTIONAL_STATE(NewState));
1132  if (NewState != DISABLE)
1133  {
1134  RCC->APB1ENR |= RCC_APB1Periph;
1135  }
1136  else
1137  {
1138  RCC->APB1ENR &= ~RCC_APB1Periph;
1139  }
1140 }
1141 
1142 #ifdef STM32F10X_CL
1143 
1154 void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState)
1155 {
1156  /* Check the parameters */
1157  assert_param(IS_RCC_AHB_PERIPH_RESET(RCC_AHBPeriph));
1158  assert_param(IS_FUNCTIONAL_STATE(NewState));
1159 
1160  if (NewState != DISABLE)
1161  {
1162  RCC->AHBRSTR |= RCC_AHBPeriph;
1163  }
1164  else
1165  {
1166  RCC->AHBRSTR &= ~RCC_AHBPeriph;
1167  }
1168 }
1169 #endif /* STM32F10X_CL */
1170 
1186 void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
1187 {
1188  /* Check the parameters */
1189  assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph));
1190  assert_param(IS_FUNCTIONAL_STATE(NewState));
1191  if (NewState != DISABLE)
1192  {
1193  RCC->APB2RSTR |= RCC_APB2Periph;
1194  }
1195  else
1196  {
1197  RCC->APB2RSTR &= ~RCC_APB2Periph;
1198  }
1199 }
1200 
1217 void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
1218 {
1219  /* Check the parameters */
1220  assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph));
1221  assert_param(IS_FUNCTIONAL_STATE(NewState));
1222  if (NewState != DISABLE)
1223  {
1224  RCC->APB1RSTR |= RCC_APB1Periph;
1225  }
1226  else
1227  {
1228  RCC->APB1RSTR &= ~RCC_APB1Periph;
1229  }
1230 }
1231 
1239 {
1240  /* Check the parameters */
1241  assert_param(IS_FUNCTIONAL_STATE(NewState));
1242  *(__IO uint32_t *) BDCR_BDRST_BB = (uint32_t)NewState;
1243 }
1244 
1252 {
1253  /* Check the parameters */
1254  assert_param(IS_FUNCTIONAL_STATE(NewState));
1255  *(__IO uint32_t *) CR_CSSON_BB = (uint32_t)NewState;
1256 }
1257 
1283 void RCC_MCOConfig(uint8_t RCC_MCO)
1284 {
1285  /* Check the parameters */
1286  assert_param(IS_RCC_MCO(RCC_MCO));
1287 
1288  /* Perform Byte access to MCO bits to select the MCO source */
1289  *(__IO uint8_t *) CFGR_BYTE4_ADDRESS = RCC_MCO;
1290 }
1291 
1328 {
1329  uint32_t tmp = 0;
1330  uint32_t statusreg = 0;
1331  FlagStatus bitstatus = RESET;
1332  /* Check the parameters */
1333  assert_param(IS_RCC_FLAG(RCC_FLAG));
1334 
1335  /* Get the RCC register index */
1336  tmp = RCC_FLAG >> 5;
1337  if (tmp == 1) /* The flag to check is in CR register */
1338  {
1339  statusreg = RCC->CR;
1340  }
1341  else if (tmp == 2) /* The flag to check is in BDCR register */
1342  {
1343  statusreg = RCC->BDCR;
1344  }
1345  else /* The flag to check is in CSR register */
1346  {
1347  statusreg = RCC->CSR;
1348  }
1349 
1350  /* Get the flag position */
1351  tmp = RCC_FLAG & FLAG_Mask;
1352  if ((statusreg & ((uint32_t)1 << tmp)) != (uint32_t)RESET)
1353  {
1354  bitstatus = SET;
1355  }
1356  else
1357  {
1358  bitstatus = RESET;
1359  }
1360 
1361  /* Return the flag status */
1362  return bitstatus;
1363 }
1364 
1372 void RCC_ClearFlag(void)
1373 {
1374  /* Set RMVF bit to clear the reset flags */
1375  RCC->CSR |= CSR_RMVF_Set;
1376 }
1377 
1403 ITStatus RCC_GetITStatus(uint8_t RCC_IT)
1404 {
1405  ITStatus bitstatus = RESET;
1406  /* Check the parameters */
1407  assert_param(IS_RCC_GET_IT(RCC_IT));
1408 
1409  /* Check the status of the specified RCC interrupt */
1410  if ((RCC->CIR & RCC_IT) != (uint32_t)RESET)
1411  {
1412  bitstatus = SET;
1413  }
1414  else
1415  {
1416  bitstatus = RESET;
1417  }
1418 
1419  /* Return the RCC_IT status */
1420  return bitstatus;
1421 }
1422 
1449 void RCC_ClearITPendingBit(uint8_t RCC_IT)
1450 {
1451  /* Check the parameters */
1452  assert_param(IS_RCC_CLEAR_IT(RCC_IT));
1453 
1454  /* Perform Byte access to RCC_CIR[23:16] bits to clear the selected interrupt
1455  pending bits */
1456  *(__IO uint8_t *) CIR_BYTE3_ADDRESS = RCC_IT;
1457 }
1458 
1471 /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
FlagStatus
Definition: stm32f4xx.h:706
#define CFGR_PLLMull_Mask
void RCC_PLLCmd(FunctionalState NewState)
Enables or disables the PLL.
#define CR_HSITRIM_Mask
void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState)
Enables or disables the specified RCC interrupts.
FunctionalState
Definition: stm32f4xx.h:708
void RCC_PCLK1Config(uint32_t RCC_HCLK)
Configures the Low Speed APB clock (PCLK1).
ErrorStatus RCC_WaitForHSEStartUp(void)
Waits for HSE start-up.
void RCC_DeInit(void)
Resets the RCC clock configuration to the default reset state.
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.
#define CR_HSEBYP_Set
void RCC_ClearITPendingBit(uint8_t RCC_IT)
Clears the RCC&#39;s interrupt pending bits.
void assert_param(int val)
#define CFGR_PPRE1_Reset_Mask
#define IS_FUNCTIONAL_STATE(STATE)
Definition: stm32f4xx.h:709
uint32_t ADCCLK_Frequency
Definition: stm32f10x_rcc.h:52
#define __I
Definition: core_cm0.h:195
#define IS_RCC_USBCLK_SOURCE(SOURCE)
static volatile uint8_t * status
Definition: drv_i2c.c:102
#define HSE_STARTUP_TIMEOUT
Comment the line below if you will not use the peripherals drivers. In this case, these drivers will ...
Definition: stm32f4xx.h:146
#define BDCR_ADDRESS
#define CFGR_ADCPRE_Set_Mask
void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
Forces or releases Low Speed APB (APB1) peripheral reset.
#define CSR_LSION_BB
#define CFGR_SWS_Mask
Definition: stm32f4xx.h:706
#define HSI_VALUE
Definition: stm32f4xx.h:150
#define FLAG_Mask
enum FlagStatus ITStatus
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.
#define CFGR_PLLSRC_Mask
#define __IO
Definition: core_cm0.h:198
void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource)
Configures the system clock (SYSCLK).
#define CR_HSEBYP_Reset
uint32_t hse_value
#define BDCR_RTCEN_BB
Definition: stm32f10x_rcc.c:92
#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 ...
Definition: stm32f10x.h:119
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).
#define CR_HSEON_Set
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).
#define RCC
Definition: stm32f4xx.h:2122
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.
#define CR_HSEON_Reset
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.
#define CFGR_SW_Mask
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).
ErrorStatus
Definition: stm32f4xx.h:711
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 CFGR_USBPRE_BB
Definition: stm32f10x_rcc.c:81
#define CR_HSION_BB
Definition: stm32f10x_rcc.c:54
#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 CR_CSSON_BB
Definition: stm32f10x_rcc.c:72
#define CFGR_PPRE2_Set_Mask
#define CR_PLLON_BB
Definition: stm32f10x_rcc.c:58
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).
#define BDCR_BDRST_BB
Definition: stm32f10x_rcc.c:96
#define CFGR_HPRE_Reset_Mask
#define IS_RCC_MCO(MCO)
#define CSR_RMVF_Set
#define CFGR_BYTE4_ADDRESS
#define CFGR_HPRE_Set_Mask
#define CFGR_PLL_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 CFGR_ADCPRE_Reset_Mask
void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState)
Forces or releases AHB peripheral reset.


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