stm32f30x_rcc.c
Go to the documentation of this file.
1 
57 /* Includes ------------------------------------------------------------------*/
58 #include "stm32f30x_rcc.h"
59 
69 /* Private typedef -----------------------------------------------------------*/
70 /* Private define ------------------------------------------------------------*/
71 /* ------------ RCC registers bit address in the alias region ----------- */
72 #define RCC_OFFSET (RCC_BASE - PERIPH_BASE)
73 
74 /* --- CR Register ---*/
75 
76 /* Alias word address of HSION bit */
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))
80 
81 /* Alias word address of PLLON bit */
82 #define PLLON_BitNumber 0x18
83 #define CR_PLLON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLON_BitNumber * 4))
84 
85 /* Alias word address of CSSON bit */
86 #define CSSON_BitNumber 0x13
87 #define CR_CSSON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (CSSON_BitNumber * 4))
88 
89 /* --- CFGR Register ---*/
90 /* Alias word address of USBPRE bit */
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))
94 /* Alias word address of I2SSRC bit */
95 #define I2SSRC_BitNumber 0x17
96 #define CFGR_I2SSRC_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (I2SSRC_BitNumber * 4))
97 
98 /* --- BDCR Register ---*/
99 
100 /* Alias word address of RTCEN bit */
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))
104 
105 /* Alias word address of BDRST bit */
106 #define BDRST_BitNumber 0x10
107 #define BDCR_BDRST_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (BDRST_BitNumber * 4))
108 
109 /* --- CSR Register ---*/
110 
111 /* Alias word address of LSION bit */
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))
115 
116 /* ---------------------- RCC registers bit mask ------------------------ */
117 /* RCC Flag Mask */
118 #define FLAG_MASK ((uint8_t)0x1F)
119 
120 /* CFGR register byte 3 (Bits[31:23]) base address */
121 #define CFGR_BYTE3_ADDRESS ((uint32_t)0x40021007)
122 
123 /* CIR register byte 2 (Bits[15:8]) base address */
124 #define CIR_BYTE2_ADDRESS ((uint32_t)0x40021009)
125 
126 /* CIR register byte 3 (Bits[23:16]) base address */
127 #define CIR_BYTE3_ADDRESS ((uint32_t)0x4002100A)
128 
129 /* CR register byte 2 (Bits[23:16]) base address */
130 #define CR_BYTE2_ADDRESS ((uint32_t)0x40021002)
131 
132 /* Private macro -------------------------------------------------------------*/
133 /* Private variables ---------------------------------------------------------*/
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 };
136 
137 /* Private function prototypes -----------------------------------------------*/
138 /* Private functions ---------------------------------------------------------*/
139 
189 void RCC_DeInit(void)
190 {
191  /* Set HSION bit */
192  RCC->CR |= (uint32_t)0x00000001;
193 
194  /* Reset SW[1:0], HPRE[3:0], PPRE[2:0] and MCOSEL[2:0] bits */
195  RCC->CFGR &= (uint32_t)0xF8FFC000;
196 
197  /* Reset HSEON, CSSON and PLLON bits */
198  RCC->CR &= (uint32_t)0xFEF6FFFF;
199 
200  /* Reset HSEBYP bit */
201  RCC->CR &= (uint32_t)0xFFFBFFFF;
202 
203  /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */
204  RCC->CFGR &= (uint32_t)0xFF80FFFF;
205 
206  /* Reset PREDIV1[3:0] and ADCPRE[13:4] bits */
207  RCC->CFGR2 &= (uint32_t)0xFFFFC000;
208 
209  /* Reset USARTSW[1:0], I2CSW and TIMSW bits */
210  RCC->CFGR3 &= (uint32_t)0xF00ECCC;
211 
212  /* Disable all interrupts */
213  RCC->CIR = 0x00000000;
214 }
215 
236 void RCC_HSEConfig(uint8_t RCC_HSE)
237 {
238  /* Check the parameters */
239  assert_param(IS_RCC_HSE(RCC_HSE));
240 
241  /* Reset HSEON and HSEBYP bits before configuring the HSE ------------------*/
242  *(__IO uint8_t *) CR_BYTE2_ADDRESS = RCC_HSE_OFF;
243 
244  /* Set the new HSE configuration -------------------------------------------*/
245  *(__IO uint8_t *) CR_BYTE2_ADDRESS = RCC_HSE;
246 
247 }
248 
262 {
263  __IO uint32_t StartUpCounter = 0;
265  FlagStatus HSEStatus = RESET;
266 
267  /* Wait till HSE is ready and if timeout is reached exit */
268  do
269  {
270  HSEStatus = RCC_GetFlagStatus(RCC_FLAG_HSERDY);
271  StartUpCounter++;
272  } while((StartUpCounter != HSE_STARTUP_TIMEOUT) && (HSEStatus == RESET));
273 
275  {
276  status = SUCCESS;
277  }
278  else
279  {
280  status = ERROR;
281  }
282  return (status);
283 }
284 
295 void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue)
296 {
297  uint32_t tmpreg = 0;
298 
299  /* Check the parameters */
300  assert_param(IS_RCC_HSI_CALIBRATION_VALUE(HSICalibrationValue));
301 
302  tmpreg = RCC->CR;
303 
304  /* Clear HSITRIM[4:0] bits */
305  tmpreg &= ~RCC_CR_HSITRIM;
306 
307  /* Set the HSITRIM[4:0] bits according to HSICalibrationValue value */
308  tmpreg |= (uint32_t)HSICalibrationValue << 3;
309 
310  /* Store the new value */
311  RCC->CR = tmpreg;
312 }
313 
329 void RCC_HSICmd(FunctionalState NewState)
330 {
331  /* Check the parameters */
333 
334  *(__IO uint32_t *) CR_HSION_BB = (uint32_t)NewState;
335 }
336 
354 void RCC_LSEConfig(uint32_t RCC_LSE)
355 {
356  /* Check the parameters */
357  assert_param(IS_RCC_LSE(RCC_LSE));
358 
359  /* Reset LSEON and LSEBYP bits before configuring the LSE ------------------*/
360  /* Reset LSEON bit */
361  RCC->BDCR &= ~(RCC_BDCR_LSEON);
362 
363  /* Reset LSEBYP bit */
364  RCC->BDCR &= ~(RCC_BDCR_LSEBYP);
365 
366  /* Configure LSE */
367  RCC->BDCR |= RCC_LSE;
368 }
369 
380 void RCC_LSEDriveConfig(uint32_t RCC_LSEDrive)
381 {
382  /* Check the parameters */
383  assert_param(IS_RCC_LSE_DRIVE(RCC_LSEDrive));
384 
385  /* Clear LSEDRV[1:0] bits */
386  RCC->BDCR &= ~(RCC_BDCR_LSEDRV);
387 
388  /* Set the LSE Drive */
389  RCC->BDCR |= RCC_LSEDrive;
390 }
391 
404 void RCC_LSICmd(FunctionalState NewState)
405 {
406  /* Check the parameters */
408 
409  *(__IO uint32_t *) CSR_LSION_BB = (uint32_t)NewState;
410 }
411 
427 void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul)
428 {
429  /* Check the parameters */
430  assert_param(IS_RCC_PLL_SOURCE(RCC_PLLSource));
431  assert_param(IS_RCC_PLL_MUL(RCC_PLLMul));
432 
433  /* Clear PLL Source [16] and Multiplier [21:18] bits */
434  RCC->CFGR &= ~(RCC_CFGR_PLLMULL | RCC_CFGR_PLLSRC);
435 
436  /* Set the PLL Source and Multiplier */
437  RCC->CFGR |= (uint32_t)(RCC_PLLSource | RCC_PLLMul);
438 }
439 
451 void RCC_PLLCmd(FunctionalState NewState)
452 {
453  /* Check the parameters */
455 
456  *(__IO uint32_t *) CR_PLLON_BB = (uint32_t)NewState;
457 }
458 
466 void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Div)
467 {
468  uint32_t tmpreg = 0;
469 
470  /* Check the parameters */
471  assert_param(IS_RCC_PREDIV1(RCC_PREDIV1_Div));
472 
473  tmpreg = RCC->CFGR2;
474  /* Clear PREDIV1[3:0] bits */
475  tmpreg &= ~(RCC_CFGR2_PREDIV1);
476 
477  /* Set the PREDIV1 division factor */
478  tmpreg |= RCC_PREDIV1_Div;
479 
480  /* Store the new value */
481  RCC->CFGR2 = tmpreg;
482 }
483 
496 {
497  /* Check the parameters */
499 
500  *(__IO uint32_t *) CR_CSSON_BB = (uint32_t)NewState;
501 }
502 
503 #ifdef STM32F303xC
504 
521 void RCC_MCOConfig(uint8_t RCC_MCOSource)
522 {
523  uint32_t tmpreg = 0;
524 
525  /* Check the parameters */
526  assert_param(IS_RCC_MCO_SOURCE(RCC_MCOSource));
527 
528  /* Get CFGR value */
529  tmpreg = RCC->CFGR;
530  /* Clear MCO[3:0] bits */
531  tmpreg &= ~(RCC_CFGR_MCO | RCC_CFGR_PLLNODIV);
532  /* Set the RCC_MCOSource */
533  tmpreg |= RCC_MCOSource<<24;
534  /* Store the new value */
535  RCC->CFGR = tmpreg;
536 }
537 #else
538 
567 void RCC_MCOConfig(uint8_t RCC_MCOSource, uint32_t RCC_MCOPrescaler)
568 {
569  uint32_t tmpreg = 0;
570 
571  /* Check the parameters */
572  assert_param(IS_RCC_MCO_SOURCE(RCC_MCOSource));
573  assert_param(IS_RCC_MCO_PRESCALER(RCC_MCOPrescaler));
574 
575  /* Get CFGR value */
576  tmpreg = RCC->CFGR;
577  /* Clear MCOPRE[2:0] bits */
578  tmpreg &= ~(RCC_CFGR_MCO_PRE | RCC_CFGR_MCO | RCC_CFGR_PLLNODIV);
579  /* Set the RCC_MCOSource and RCC_MCOPrescaler */
580  tmpreg |= (RCC_MCOPrescaler | RCC_MCOSource<<24);
581  /* Store the new value */
582  RCC->CFGR = tmpreg;
583 }
584 #endif /* STM32F303xC */
585 
683 void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource)
684 {
685  uint32_t tmpreg = 0;
686 
687  /* Check the parameters */
688  assert_param(IS_RCC_SYSCLK_SOURCE(RCC_SYSCLKSource));
689 
690  tmpreg = RCC->CFGR;
691 
692  /* Clear SW[1:0] bits */
693  tmpreg &= ~RCC_CFGR_SW;
694 
695  /* Set SW[1:0] bits according to RCC_SYSCLKSource value */
696  tmpreg |= RCC_SYSCLKSource;
697 
698  /* Store the new value */
699  RCC->CFGR = tmpreg;
700 }
701 
711 uint8_t RCC_GetSYSCLKSource(void)
712 {
713  return ((uint8_t)(RCC->CFGR & RCC_CFGR_SWS));
714 }
715 
736 void RCC_HCLKConfig(uint32_t RCC_SYSCLK)
737 {
738  uint32_t tmpreg = 0;
739 
740  /* Check the parameters */
741  assert_param(IS_RCC_HCLK(RCC_SYSCLK));
742 
743  tmpreg = RCC->CFGR;
744 
745  /* Clear HPRE[3:0] bits */
746  tmpreg &= ~RCC_CFGR_HPRE;
747 
748  /* Set HPRE[3:0] bits according to RCC_SYSCLK value */
749  tmpreg |= RCC_SYSCLK;
750 
751  /* Store the new value */
752  RCC->CFGR = tmpreg;
753 }
754 
767 void RCC_PCLK1Config(uint32_t RCC_HCLK)
768 {
769  uint32_t tmpreg = 0;
770 
771  /* Check the parameters */
772  assert_param(IS_RCC_PCLK(RCC_HCLK));
773 
774  tmpreg = RCC->CFGR;
775  /* Clear PPRE1[2:0] bits */
776  tmpreg &= ~RCC_CFGR_PPRE1;
777 
778  /* Set PPRE1[2:0] bits according to RCC_HCLK value */
779  tmpreg |= RCC_HCLK;
780 
781  /* Store the new value */
782  RCC->CFGR = tmpreg;
783 }
784 
797 void RCC_PCLK2Config(uint32_t RCC_HCLK)
798 {
799  uint32_t tmpreg = 0;
800 
801  /* Check the parameters */
802  assert_param(IS_RCC_PCLK(RCC_HCLK));
803 
804  tmpreg = RCC->CFGR;
805  /* Clear PPRE2[2:0] bits */
806  tmpreg &= ~RCC_CFGR_PPRE2;
807  /* Set PPRE2[2:0] bits according to RCC_HCLK value */
808  tmpreg |= RCC_HCLK << 3;
809  /* Store the new value */
810  RCC->CFGR = tmpreg;
811 }
812 
854 void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks)
855 {
856  uint32_t tmp = 0, pllmull = 0, pllsource = 0, prediv1factor = 0, presc = 0, pllclk = 0;
857  uint32_t apb2presc = 0, ahbpresc = 0;
858 
859  /* Get SYSCLK source -------------------------------------------------------*/
860  tmp = RCC->CFGR & RCC_CFGR_SWS;
861 
862  switch (tmp)
863  {
864  case 0x00: /* HSI used as system clock */
865  RCC_Clocks->SYSCLK_Frequency = HSI_VALUE;
866  break;
867  case 0x04: /* HSE used as system clock */
868  RCC_Clocks->SYSCLK_Frequency = HSE_VALUE;
869  break;
870  case 0x08: /* PLL used as system clock */
871  /* Get PLL clock source and multiplication factor ----------------------*/
872  pllmull = RCC->CFGR & RCC_CFGR_PLLMULL;
873  pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
874  pllmull = ( pllmull >> 18) + 2;
875 
876  if (pllsource == 0x00)
877  {
878  /* HSI oscillator clock divided by 2 selected as PLL clock entry */
879  pllclk = (HSI_VALUE >> 1) * pllmull;
880  }
881  else
882  {
883  prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1;
884  /* HSE oscillator clock selected as PREDIV1 clock entry */
885  pllclk = (HSE_VALUE / prediv1factor) * pllmull;
886  }
887  RCC_Clocks->SYSCLK_Frequency = pllclk;
888  break;
889  default: /* HSI used as system clock */
890  RCC_Clocks->SYSCLK_Frequency = HSI_VALUE;
891  break;
892  }
893  /* Compute HCLK, PCLK clocks frequencies -----------------------------------*/
894  /* Get HCLK prescaler */
895  tmp = RCC->CFGR & RCC_CFGR_HPRE;
896  tmp = tmp >> 4;
897  ahbpresc = APBAHBPrescTable[tmp];
898  /* HCLK clock frequency */
899  RCC_Clocks->HCLK_Frequency = RCC_Clocks->SYSCLK_Frequency >> ahbpresc;
900 
901  /* Get PCLK1 prescaler */
902  tmp = RCC->CFGR & RCC_CFGR_PPRE1;
903  tmp = tmp >> 8;
904  presc = APBAHBPrescTable[tmp];
905  /* PCLK1 clock frequency */
906  RCC_Clocks->PCLK1_Frequency = RCC_Clocks->HCLK_Frequency >> presc;
907 
908  /* Get PCLK2 prescaler */
909  tmp = RCC->CFGR & RCC_CFGR_PPRE2;
910  tmp = tmp >> 11;
911  apb2presc = APBAHBPrescTable[tmp];
912  /* PCLK2 clock frequency */
913  RCC_Clocks->PCLK2_Frequency = RCC_Clocks->HCLK_Frequency >> apb2presc;
914 
915  /* Get ADC12CLK prescaler */
916  tmp = RCC->CFGR2 & RCC_CFGR2_ADCPRE12;
917  tmp = tmp >> 4;
918  presc = ADCPrescTable[tmp & 0x0F];
919  if (((tmp & 0x10) != 0) && (presc != 0))
920  {
921  /* ADC12CLK clock frequency is derived from PLL clock */
922  RCC_Clocks->ADC12CLK_Frequency = pllclk / presc;
923  }
924  else
925  {
926  /* ADC12CLK clock frequency is AHB clock */
927  RCC_Clocks->ADC12CLK_Frequency = RCC_Clocks->SYSCLK_Frequency;
928  }
929 
930  /* Get ADC34CLK prescaler */
931  tmp = RCC->CFGR2 & RCC_CFGR2_ADCPRE34;
932  tmp = tmp >> 9;
933  presc = ADCPrescTable[tmp & 0x0F];
934  if (((tmp & 0x10) != 0) && (presc != 0))
935  {
936  /* ADC34CLK clock frequency is derived from PLL clock */
937  RCC_Clocks->ADC34CLK_Frequency = pllclk / presc;
938  }
939  else
940  {
941  /* ADC34CLK clock frequency is AHB clock */
942  RCC_Clocks->ADC34CLK_Frequency = RCC_Clocks->SYSCLK_Frequency;
943  }
944 
945  /* I2C1CLK clock frequency */
946  if((RCC->CFGR3 & RCC_CFGR3_I2C1SW) != RCC_CFGR3_I2C1SW)
947  {
948  /* I2C1 Clock is HSI Osc. */
949  RCC_Clocks->I2C1CLK_Frequency = HSI_VALUE;
950  }
951  else
952  {
953  /* I2C1 Clock is System Clock */
954  RCC_Clocks->I2C1CLK_Frequency = RCC_Clocks->SYSCLK_Frequency;
955  }
956 
957  /* I2C2CLK clock frequency */
958  if((RCC->CFGR3 & RCC_CFGR3_I2C2SW) != RCC_CFGR3_I2C2SW)
959  {
960  /* I2C2 Clock is HSI Osc. */
961  RCC_Clocks->I2C2CLK_Frequency = HSI_VALUE;
962  }
963  else
964  {
965  /* I2C2 Clock is System Clock */
966  RCC_Clocks->I2C2CLK_Frequency = RCC_Clocks->SYSCLK_Frequency;
967  }
968 
969  /* I2C3CLK clock frequency */
970  if((RCC->CFGR3 & RCC_CFGR3_I2C3SW) != RCC_CFGR3_I2C3SW)
971  {
972  /* I2C3 Clock is HSI Osc. */
973  RCC_Clocks->I2C3CLK_Frequency = HSI_VALUE;
974  }
975  else
976  {
977  /* I2C3 Clock is System Clock */
978  RCC_Clocks->I2C3CLK_Frequency = RCC_Clocks->SYSCLK_Frequency;
979  }
980 
981  /* TIM1CLK clock frequency */
982  if(((RCC->CFGR3 & RCC_CFGR3_TIM1SW) == RCC_CFGR3_TIM1SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \
983  && (apb2presc == ahbpresc))
984  {
985  /* TIM1 Clock is 2 * pllclk */
986  RCC_Clocks->TIM1CLK_Frequency = pllclk * 2;
987  }
988  else
989  {
990  /* TIM1 Clock is APB2 clock. */
991  RCC_Clocks->TIM1CLK_Frequency = RCC_Clocks->PCLK2_Frequency;
992  }
993 
994  /* TIM1CLK clock frequency */
995  if(((RCC->CFGR3 & RCC_CFGR3_HRTIM1SW) == RCC_CFGR3_HRTIM1SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \
996  && (apb2presc == ahbpresc))
997  {
998  /* HRTIM1 Clock is 2 * pllclk */
999  RCC_Clocks->HRTIM1CLK_Frequency = pllclk * 2;
1000  }
1001  else
1002  {
1003  /* HRTIM1 Clock is APB2 clock. */
1004  RCC_Clocks->HRTIM1CLK_Frequency = RCC_Clocks->PCLK2_Frequency;
1005  }
1006 
1007  /* TIM8CLK clock frequency */
1008  if(((RCC->CFGR3 & RCC_CFGR3_TIM8SW) == RCC_CFGR3_TIM8SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \
1009  && (apb2presc == ahbpresc))
1010  {
1011  /* TIM8 Clock is 2 * pllclk */
1012  RCC_Clocks->TIM8CLK_Frequency = pllclk * 2;
1013  }
1014  else
1015  {
1016  /* TIM8 Clock is APB2 clock. */
1017  RCC_Clocks->TIM8CLK_Frequency = RCC_Clocks->PCLK2_Frequency;
1018  }
1019 
1020  /* TIM15CLK clock frequency */
1021  if(((RCC->CFGR3 & RCC_CFGR3_TIM15SW) == RCC_CFGR3_TIM15SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \
1022  && (apb2presc == ahbpresc))
1023  {
1024  /* TIM15 Clock is 2 * pllclk */
1025  RCC_Clocks->TIM15CLK_Frequency = pllclk * 2;
1026  }
1027  else
1028  {
1029  /* TIM15 Clock is APB2 clock. */
1030  RCC_Clocks->TIM15CLK_Frequency = RCC_Clocks->PCLK2_Frequency;
1031  }
1032 
1033  /* TIM16CLK clock frequency */
1034  if(((RCC->CFGR3 & RCC_CFGR3_TIM16SW) == RCC_CFGR3_TIM16SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \
1035  && (apb2presc == ahbpresc))
1036  {
1037  /* TIM16 Clock is 2 * pllclk */
1038  RCC_Clocks->TIM16CLK_Frequency = pllclk * 2;
1039  }
1040  else
1041  {
1042  /* TIM16 Clock is APB2 clock. */
1043  RCC_Clocks->TIM16CLK_Frequency = RCC_Clocks->PCLK2_Frequency;
1044  }
1045 
1046  /* TIM17CLK clock frequency */
1047  if(((RCC->CFGR3 & RCC_CFGR3_TIM17SW) == RCC_CFGR3_TIM17SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \
1048  && (apb2presc == ahbpresc))
1049  {
1050  /* TIM17 Clock is 2 * pllclk */
1051  RCC_Clocks->TIM17CLK_Frequency = pllclk * 2;
1052  }
1053  else
1054  {
1055  /* TIM17 Clock is APB2 clock. */
1056  RCC_Clocks->TIM16CLK_Frequency = RCC_Clocks->PCLK2_Frequency;
1057  }
1058 
1059  /* USART1CLK clock frequency */
1060  if((RCC->CFGR3 & RCC_CFGR3_USART1SW) == 0x0)
1061  {
1062 #if defined(STM32F303x8) || defined(STM32F334x8) || defined(STM32F301x8) || defined(STM32F302x8)
1063  /* USART1 Clock is PCLK1 instead of PCLK2 (limitation described in the
1064  STM32F302/01/34 x4/x6/x8 respective erratasheets) */
1065  RCC_Clocks->USART1CLK_Frequency = RCC_Clocks->PCLK1_Frequency;
1066 #else
1067  /* USART Clock is PCLK2 */
1068  RCC_Clocks->USART1CLK_Frequency = RCC_Clocks->PCLK2_Frequency;
1069 #endif
1070  }
1071  else if((RCC->CFGR3 & RCC_CFGR3_USART1SW) == RCC_CFGR3_USART1SW_0)
1072  {
1073  /* USART Clock is System Clock */
1074  RCC_Clocks->USART1CLK_Frequency = RCC_Clocks->SYSCLK_Frequency;
1075  }
1076  else if((RCC->CFGR3 & RCC_CFGR3_USART1SW) == RCC_CFGR3_USART1SW_1)
1077  {
1078  /* USART Clock is LSE Osc. */
1079  RCC_Clocks->USART1CLK_Frequency = LSE_VALUE;
1080  }
1081  else if((RCC->CFGR3 & RCC_CFGR3_USART1SW) == RCC_CFGR3_USART1SW)
1082  {
1083  /* USART Clock is HSI Osc. */
1084  RCC_Clocks->USART1CLK_Frequency = HSI_VALUE;
1085  }
1086 
1087  /* USART2CLK clock frequency */
1088  if((RCC->CFGR3 & RCC_CFGR3_USART2SW) == 0x0)
1089  {
1090  /* USART Clock is PCLK */
1091  RCC_Clocks->USART2CLK_Frequency = RCC_Clocks->PCLK1_Frequency;
1092  }
1093  else if((RCC->CFGR3 & RCC_CFGR3_USART2SW) == RCC_CFGR3_USART2SW_0)
1094  {
1095  /* USART Clock is System Clock */
1096  RCC_Clocks->USART2CLK_Frequency = RCC_Clocks->SYSCLK_Frequency;
1097  }
1098  else if((RCC->CFGR3 & RCC_CFGR3_USART2SW) == RCC_CFGR3_USART2SW_1)
1099  {
1100  /* USART Clock is LSE Osc. */
1101  RCC_Clocks->USART2CLK_Frequency = LSE_VALUE;
1102  }
1103  else if((RCC->CFGR3 & RCC_CFGR3_USART2SW) == RCC_CFGR3_USART2SW)
1104  {
1105  /* USART Clock is HSI Osc. */
1106  RCC_Clocks->USART2CLK_Frequency = HSI_VALUE;
1107  }
1108 
1109  /* USART3CLK clock frequency */
1110  if((RCC->CFGR3 & RCC_CFGR3_USART3SW) == 0x0)
1111  {
1112  /* USART Clock is PCLK */
1113  RCC_Clocks->USART3CLK_Frequency = RCC_Clocks->PCLK1_Frequency;
1114  }
1115  else if((RCC->CFGR3 & RCC_CFGR3_USART3SW) == RCC_CFGR3_USART3SW_0)
1116  {
1117  /* USART Clock is System Clock */
1118  RCC_Clocks->USART3CLK_Frequency = RCC_Clocks->SYSCLK_Frequency;
1119  }
1120  else if((RCC->CFGR3 & RCC_CFGR3_USART3SW) == RCC_CFGR3_USART3SW_1)
1121  {
1122  /* USART Clock is LSE Osc. */
1123  RCC_Clocks->USART3CLK_Frequency = LSE_VALUE;
1124  }
1125  else if((RCC->CFGR3 & RCC_CFGR3_USART3SW) == RCC_CFGR3_USART3SW)
1126  {
1127  /* USART Clock is HSI Osc. */
1128  RCC_Clocks->USART3CLK_Frequency = HSI_VALUE;
1129  }
1130 
1131  /* UART4CLK clock frequency */
1132  if((RCC->CFGR3 & RCC_CFGR3_UART4SW) == 0x0)
1133  {
1134  /* USART Clock is PCLK */
1135  RCC_Clocks->UART4CLK_Frequency = RCC_Clocks->PCLK1_Frequency;
1136  }
1137  else if((RCC->CFGR3 & RCC_CFGR3_UART4SW) == RCC_CFGR3_UART4SW_0)
1138  {
1139  /* USART Clock is System Clock */
1140  RCC_Clocks->UART4CLK_Frequency = RCC_Clocks->SYSCLK_Frequency;
1141  }
1142  else if((RCC->CFGR3 & RCC_CFGR3_UART4SW) == RCC_CFGR3_UART4SW_1)
1143  {
1144  /* USART Clock is LSE Osc. */
1145  RCC_Clocks->UART4CLK_Frequency = LSE_VALUE;
1146  }
1147  else if((RCC->CFGR3 & RCC_CFGR3_UART4SW) == RCC_CFGR3_UART4SW)
1148  {
1149  /* USART Clock is HSI Osc. */
1150  RCC_Clocks->UART4CLK_Frequency = HSI_VALUE;
1151  }
1152 
1153  /* UART5CLK clock frequency */
1154  if((RCC->CFGR3 & RCC_CFGR3_UART5SW) == 0x0)
1155  {
1156  /* USART Clock is PCLK */
1157  RCC_Clocks->UART5CLK_Frequency = RCC_Clocks->PCLK1_Frequency;
1158  }
1159  else if((RCC->CFGR3 & RCC_CFGR3_UART5SW) == RCC_CFGR3_UART5SW_0)
1160  {
1161  /* USART Clock is System Clock */
1162  RCC_Clocks->UART5CLK_Frequency = RCC_Clocks->SYSCLK_Frequency;
1163  }
1164  else if((RCC->CFGR3 & RCC_CFGR3_UART5SW) == RCC_CFGR3_UART5SW_1)
1165  {
1166  /* USART Clock is LSE Osc. */
1167  RCC_Clocks->UART5CLK_Frequency = LSE_VALUE;
1168  }
1169  else if((RCC->CFGR3 & RCC_CFGR3_UART5SW) == RCC_CFGR3_UART5SW)
1170  {
1171  /* USART Clock is HSI Osc. */
1172  RCC_Clocks->UART5CLK_Frequency = HSI_VALUE;
1173  }
1174 }
1175 
1235 void RCC_ADCCLKConfig(uint32_t RCC_PLLCLK)
1236 {
1237  uint32_t tmp = 0;
1238 
1239  /* Check the parameters */
1240  assert_param(IS_RCC_ADCCLK(RCC_PLLCLK));
1241 
1242  tmp = (RCC_PLLCLK >> 28);
1243 
1244  /* Clears ADCPRE34 bits */
1245  if (tmp != 0)
1246  {
1247  RCC->CFGR2 &= ~RCC_CFGR2_ADCPRE34;
1248  }
1249  /* Clears ADCPRE12 bits */
1250  else
1251  {
1252  RCC->CFGR2 &= ~RCC_CFGR2_ADCPRE12;
1253  }
1254  /* Set ADCPRE bits according to RCC_PLLCLK value */
1255  RCC->CFGR2 |= RCC_PLLCLK;
1256 }
1257 
1268 void RCC_I2CCLKConfig(uint32_t RCC_I2CCLK)
1269 {
1270  uint32_t tmp = 0;
1271 
1272  /* Check the parameters */
1273  assert_param(IS_RCC_I2CCLK(RCC_I2CCLK));
1274 
1275  tmp = (RCC_I2CCLK >> 28);
1276 
1277  /* Clear I2CSW bit */
1278  switch (tmp)
1279  {
1280  case 0x00:
1281  RCC->CFGR3 &= ~RCC_CFGR3_I2C1SW;
1282  break;
1283  case 0x01:
1284  RCC->CFGR3 &= ~RCC_CFGR3_I2C2SW;
1285  break;
1286  case 0x02:
1287  RCC->CFGR3 &= ~RCC_CFGR3_I2C3SW;
1288  break;
1289  default:
1290  break;
1291  }
1292 
1293  /* Set I2CSW bits according to RCC_I2CCLK value */
1294  RCC->CFGR3 |= RCC_I2CCLK;
1295 }
1296 
1311 void RCC_TIMCLKConfig(uint32_t RCC_TIMCLK)
1312 {
1313  uint32_t tmp = 0;
1314 
1315  /* Check the parameters */
1316  assert_param(IS_RCC_TIMCLK(RCC_TIMCLK));
1317 
1318  tmp = (RCC_TIMCLK >> 28);
1319 
1320  /* Clear TIMSW bit */
1321 
1322  switch (tmp)
1323  {
1324  case 0x00:
1325  RCC->CFGR3 &= ~RCC_CFGR3_TIM1SW;
1326  break;
1327  case 0x01:
1328  RCC->CFGR3 &= ~RCC_CFGR3_TIM8SW;
1329  break;
1330  case 0x02:
1331  RCC->CFGR3 &= ~RCC_CFGR3_TIM15SW;
1332  break;
1333  case 0x03:
1334  RCC->CFGR3 &= ~RCC_CFGR3_TIM16SW;
1335  break;
1336  case 0x04:
1337  RCC->CFGR3 &= ~RCC_CFGR3_TIM17SW;
1338  break;
1339  default:
1340  break;
1341  }
1342 
1343  /* Set I2CSW bits according to RCC_TIMCLK value */
1344  RCC->CFGR3 |= RCC_TIMCLK;
1345 }
1346 
1361 void RCC_HRTIM1CLKConfig(uint32_t RCC_HRTIMCLK)
1362 {
1363  /* Check the parameters */
1364  assert_param(IS_RCC_HRTIMCLK(RCC_HRTIMCLK));
1365 
1366  /* Clear HRTIMSW bit */
1367  RCC->CFGR3 &= ~RCC_CFGR3_HRTIM1SW;
1368 
1369  /* Set HRTIMSW bits according to RCC_HRTIMCLK value */
1370  RCC->CFGR3 |= RCC_HRTIMCLK;
1371 }
1372 
1385 void RCC_USARTCLKConfig(uint32_t RCC_USARTCLK)
1386 {
1387  uint32_t tmp = 0;
1388 
1389  /* Check the parameters */
1390  assert_param(IS_RCC_USARTCLK(RCC_USARTCLK));
1391 
1392  tmp = (RCC_USARTCLK >> 28);
1393 
1394  /* Clear USARTSW[1:0] bit */
1395  switch (tmp)
1396  {
1397  case 0x01: /* clear USART1SW */
1398  RCC->CFGR3 &= ~RCC_CFGR3_USART1SW;
1399  break;
1400  case 0x02: /* clear USART2SW */
1401  RCC->CFGR3 &= ~RCC_CFGR3_USART2SW;
1402  break;
1403  case 0x03: /* clear USART3SW */
1404  RCC->CFGR3 &= ~RCC_CFGR3_USART3SW;
1405  break;
1406  case 0x04: /* clear UART4SW */
1407  RCC->CFGR3 &= ~RCC_CFGR3_UART4SW;
1408  break;
1409  case 0x05: /* clear UART5SW */
1410  RCC->CFGR3 &= ~RCC_CFGR3_UART5SW;
1411  break;
1412  default:
1413  break;
1414  }
1415 
1416  /* Set USARTSW bits according to RCC_USARTCLK value */
1417  RCC->CFGR3 |= RCC_USARTCLK;
1418 }
1419 
1430 void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource)
1431 {
1432  /* Check the parameters */
1433  assert_param(IS_RCC_USBCLK_SOURCE(RCC_USBCLKSource));
1434 
1435  *(__IO uint32_t *) CFGR_USBPRE_BB = RCC_USBCLKSource;
1436 }
1437 
1461 void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource)
1462 {
1463  /* Check the parameters */
1464  assert_param(IS_RCC_RTCCLK_SOURCE(RCC_RTCCLKSource));
1465 
1466  /* Select the RTC clock source */
1467  RCC->BDCR |= RCC_RTCCLKSource;
1468 }
1469 
1480 void RCC_I2SCLKConfig(uint32_t RCC_I2SCLKSource)
1481 {
1482  /* Check the parameters */
1483  assert_param(IS_RCC_I2SCLK_SOURCE(RCC_I2SCLKSource));
1484 
1485  *(__IO uint32_t *) CFGR_I2SSRC_BB = RCC_I2SCLKSource;
1486 }
1487 
1496 void RCC_RTCCLKCmd(FunctionalState NewState)
1497 {
1498  /* Check the parameters */
1499  assert_param(IS_FUNCTIONAL_STATE(NewState));
1500 
1501  *(__IO uint32_t *) BDCR_RTCEN_BB = (uint32_t)NewState;
1502 }
1503 
1512 void RCC_BackupResetCmd(FunctionalState NewState)
1513 {
1514  /* Check the parameters */
1515  assert_param(IS_FUNCTIONAL_STATE(NewState));
1516 
1517  *(__IO uint32_t *) BDCR_BDRST_BB = (uint32_t)NewState;
1518 }
1519 
1545 void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState)
1546 {
1547  /* Check the parameters */
1548  assert_param(IS_RCC_AHB_PERIPH(RCC_AHBPeriph));
1549  assert_param(IS_FUNCTIONAL_STATE(NewState));
1550 
1551  if (NewState != DISABLE)
1552  {
1553  RCC->AHBENR |= RCC_AHBPeriph;
1554  }
1555  else
1556  {
1557  RCC->AHBENR &= ~RCC_AHBPeriph;
1558  }
1559 }
1560 
1581 void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
1582 {
1583  /* Check the parameters */
1584  assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph));
1585  assert_param(IS_FUNCTIONAL_STATE(NewState));
1586 
1587  if (NewState != DISABLE)
1588  {
1589  RCC->APB2ENR |= RCC_APB2Periph;
1590  }
1591  else
1592  {
1593  RCC->APB2ENR &= ~RCC_APB2Periph;
1594  }
1595 }
1596 
1627 void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
1628 {
1629  /* Check the parameters */
1630  assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph));
1631  assert_param(IS_FUNCTIONAL_STATE(NewState));
1632 
1633  if (NewState != DISABLE)
1634  {
1635  RCC->APB1ENR |= RCC_APB1Periph;
1636  }
1637  else
1638  {
1639  RCC->APB1ENR &= ~RCC_APB1Periph;
1640  }
1641 }
1642 
1660 void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState)
1661 {
1662  /* Check the parameters */
1663  assert_param(IS_RCC_AHB_RST_PERIPH(RCC_AHBPeriph));
1664  assert_param(IS_FUNCTIONAL_STATE(NewState));
1665 
1666  if (NewState != DISABLE)
1667  {
1668  RCC->AHBRSTR |= RCC_AHBPeriph;
1669  }
1670  else
1671  {
1672  RCC->AHBRSTR &= ~RCC_AHBPeriph;
1673  }
1674 }
1675 
1693 void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
1694 {
1695  /* Check the parameters */
1696  assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph));
1697  assert_param(IS_FUNCTIONAL_STATE(NewState));
1698 
1699  if (NewState != DISABLE)
1700  {
1701  RCC->APB2RSTR |= RCC_APB2Periph;
1702  }
1703  else
1704  {
1705  RCC->APB2RSTR &= ~RCC_APB2Periph;
1706  }
1707 }
1708 
1736 void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
1737 {
1738  /* Check the parameters */
1739  assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph));
1740  assert_param(IS_FUNCTIONAL_STATE(NewState));
1741 
1742  if (NewState != DISABLE)
1743  {
1744  RCC->APB1RSTR |= RCC_APB1Periph;
1745  }
1746  else
1747  {
1748  RCC->APB1RSTR &= ~RCC_APB1Periph;
1749  }
1750 }
1751 
1787 void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState)
1788 {
1789  /* Check the parameters */
1790  assert_param(IS_RCC_IT(RCC_IT));
1791  assert_param(IS_FUNCTIONAL_STATE(NewState));
1792 
1793  if (NewState != DISABLE)
1794  {
1795  /* Perform Byte access to RCC_CIR[13:8] bits to enable the selected interrupts */
1796  *(__IO uint8_t *) CIR_BYTE2_ADDRESS |= RCC_IT;
1797  }
1798  else
1799  {
1800  /* Perform Byte access to RCC_CIR[13:8] bits to disable the selected interrupts */
1801  *(__IO uint8_t *) CIR_BYTE2_ADDRESS &= (uint8_t)~RCC_IT;
1802  }
1803 }
1804 
1824 FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG)
1825 {
1826  uint32_t tmp = 0;
1827  uint32_t statusreg = 0;
1828  FlagStatus bitstatus = RESET;
1829 
1830  /* Check the parameters */
1831  assert_param(IS_RCC_FLAG(RCC_FLAG));
1832 
1833  /* Get the RCC register index */
1834  tmp = RCC_FLAG >> 5;
1835 
1836  if (tmp == 0) /* The flag to check is in CR register */
1837  {
1838  statusreg = RCC->CR;
1839  }
1840  else if (tmp == 1) /* The flag to check is in BDCR register */
1841  {
1842  statusreg = RCC->BDCR;
1843  }
1844  else if (tmp == 4) /* The flag to check is in CFGR register */
1845  {
1846  statusreg = RCC->CFGR;
1847  }
1848  else /* The flag to check is in CSR register */
1849  {
1850  statusreg = RCC->CSR;
1851  }
1852 
1853  /* Get the flag position */
1854  tmp = RCC_FLAG & FLAG_MASK;
1855 
1856  if ((statusreg & ((uint32_t)1 << tmp)) != (uint32_t)RESET)
1857  {
1858  bitstatus = SET;
1859  }
1860  else
1861  {
1862  bitstatus = RESET;
1863  }
1864  /* Return the flag status */
1865  return bitstatus;
1866 }
1867 
1875 void RCC_ClearFlag(void)
1876 {
1877  /* Set RMVF bit to clear the reset flags */
1878  RCC->CSR |= RCC_CSR_RMVF;
1879 }
1880 
1893 ITStatus RCC_GetITStatus(uint8_t RCC_IT)
1894 {
1895  ITStatus bitstatus = RESET;
1896 
1897  /* Check the parameters */
1898  assert_param(IS_RCC_GET_IT(RCC_IT));
1899 
1900  /* Check the status of the specified RCC interrupt */
1901  if ((RCC->CIR & RCC_IT) != (uint32_t)RESET)
1902  {
1903  bitstatus = SET;
1904  }
1905  else
1906  {
1907  bitstatus = RESET;
1908  }
1909  /* Return the RCC_IT status */
1910  return bitstatus;
1911 }
1912 
1925 void RCC_ClearITPendingBit(uint8_t RCC_IT)
1926 {
1927  /* Check the parameters */
1928  assert_param(IS_RCC_CLEAR_IT(RCC_IT));
1929 
1930  /* Perform Byte access to RCC_CIR[23:16] bits to clear the selected interrupt
1931  pending bits */
1932  *(__IO uint8_t *) CIR_BYTE3_ADDRESS = RCC_IT;
1933 }
1934 
1951 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
FlagStatus
Definition: stm32f4xx.h:706
void RCC_ADCCLKConfig(uint32_t RCC_PLLCLK)
Configures the ADC clock (ADCCLK).
#define CR_BYTE2_ADDRESS
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
Definition: stm32f30x_rcc.h:62
FunctionalState
Definition: stm32f4xx.h:708
uint32_t USART3CLK_Frequency
Definition: stm32f30x_rcc.h:66
void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource)
Configures the RTC clock (RTCCLK).
#define RCC_CFGR_PLLMULL
Definition: stm32f10x.h:1774
#define CIR_BYTE3_ADDRESS
#define CSR_LSION_BB
#define RCC_CFGR_MCO
Definition: stm32f10x.h:1872
#define RCC_CFGR_PPRE2
Definition: stm32f4xx.h:8691
#define RCC_CFGR_HPRE
Definition: stm32f4xx.h:8656
#define RCC_CSR_RMVF
Definition: stm32f4xx.h:9100
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.
#define CFGR_I2SSRC_BB
Definition: stm32f30x_rcc.c:96
uint32_t I2C3CLK_Frequency
Definition: stm32f30x_rcc.h:60
uint32_t TIM16CLK_Frequency
Definition: stm32f30x_rcc.h:70
#define IS_RCC_HRTIMCLK(HRTIMCLK)
#define CR_PLLON_BB
Definition: stm32f30x_rcc.c:83
void RCC_BackupResetCmd(FunctionalState NewState)
Forces or releases the Backup domain reset.
#define IS_FUNCTIONAL_STATE(STATE)
Definition: stm32f4xx.h:709
#define __I
Definition: core_cm0.h:195
#define IS_RCC_USBCLK_SOURCE(SOURCE)
uint32_t TIM15CLK_Frequency
Definition: stm32f30x_rcc.h:69
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
void RCC_PLLCmd(FunctionalState NewState)
Enables or disables the main PLL.
Definition: stm32f4xx.h:706
uint32_t USART2CLK_Frequency
Definition: stm32f30x_rcc.h:65
ITStatus RCC_GetITStatus(uint8_t RCC_IT)
Checks whether the specified RCC interrupt has occurred or not.
#define HSI_VALUE
Definition: stm32f4xx.h:150
uint32_t UART4CLK_Frequency
Definition: stm32f30x_rcc.h:67
enum FlagStatus ITStatus
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.
#define __IO
Definition: core_cm0.h:198
#define RCC_BDCR_LSEBYP
Definition: stm32f4xx.h:9087
void RCC_I2CCLKConfig(uint32_t RCC_I2CCLK)
Configures the I2C clock (I2CCLK).
uint32_t USART1CLK_Frequency
Definition: stm32f30x_rcc.h:64
void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource)
Configures the USB clock (USBCLK).
#define CR_CSSON_BB
Definition: stm32f30x_rcc.c:87
#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 ...
Definition: stm32f10x.h:119
#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
Definition: stm32f30x_rcc.h:71
void RCC_LSICmd(FunctionalState NewState)
Enables or disables the Internal Low Speed oscillator (LSI).
#define IS_RCC_HSI_CALIBRATION_VALUE(VALUE)
#define RCC
Definition: stm32f4xx.h:2122
#define BDCR_BDRST_BB
uint32_t I2C2CLK_Frequency
Definition: stm32f30x_rcc.h:59
#define CR_HSION_BB
Definition: stm32f30x_rcc.c:79
uint32_t I2C1CLK_Frequency
Definition: stm32f30x_rcc.h:58
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
Definition: stm32f30x_rcc.h:57
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 RCC_CFGR_PLLSRC
Definition: stm32f10x.h:1769
void RCC_PCLK2Config(uint32_t RCC_HCLK)
Configures the High Speed APB clock (PCLK2).
ErrorStatus
Definition: stm32f4xx.h:711
#define RCC_CFGR_SWS
Definition: stm32f4xx.h:8644
uint32_t TIM1CLK_Frequency
Definition: stm32f30x_rcc.h:61
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 RCC_CFGR_PPRE1
Definition: stm32f4xx.h:8679
#define RCC_CFGR_SW
Definition: stm32f4xx.h:8632
#define IS_RCC_PLL_MUL(MUL)
#define CIR_BYTE2_ADDRESS
uint32_t ADC12CLK_Frequency
Definition: stm32f30x_rcc.h:56
void RCC_HSEConfig(uint8_t RCC_HSE)
Configures the External High Speed oscillator (HSE).
uint32_t UART5CLK_Frequency
Definition: stm32f30x_rcc.h:68
#define IS_RCC_MCO_SOURCE(SOURCE)
#define IS_RCC_I2SCLK_SOURCE(SOURCE)
#define FLAG_MASK
void RCC_ClearITPendingBit(uint8_t RCC_IT)
Clears the RCC&#39;s interrupt pending bits.
#define RCC_CR_HSITRIM
Definition: stm32f4xx.h:8561
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 CFGR_USBPRE_BB
Definition: stm32f30x_rcc.c:93
#define IS_RCC_ADCCLK(ADCCLK)
#define BDCR_RTCEN_BB
void RCC_HRTIM1CLKConfig(uint32_t RCC_HRTIMCLK)
Configures the HRTIM1 clock sources(HRTIM1CLK).
void RCC_GetClocksFreq(RCC_ClocksTypeDef *RCC_Clocks)
Returns the frequencies of different on chip clocks; SYSCLK, HCLK, PCLK1 and PCLK2.
#define RCC_BDCR_LSEON
Definition: stm32f4xx.h:9085
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)
void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul)
Configures the PLL clock source and multiplication factor.
uint32_t TIM8CLK_Frequency
Definition: stm32f30x_rcc.h:63
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)


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