stm32f469/stm32f469i-disco/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c
Go to the documentation of this file.
1 
68 /* Includes ------------------------------------------------------------------*/
69 #include "stm32f4xx_hal.h"
70 
80 #ifdef HAL_RCC_MODULE_ENABLED
81 
82 /* Private typedef -----------------------------------------------------------*/
83 /* Private define ------------------------------------------------------------*/
88 /* Private macro -------------------------------------------------------------*/
89 #define __MCO1_CLK_ENABLE() __HAL_RCC_GPIOA_CLK_ENABLE()
90 #define MCO1_GPIO_PORT GPIOA
91 #define MCO1_PIN GPIO_PIN_8
92 
93 #define __MCO2_CLK_ENABLE() __HAL_RCC_GPIOC_CLK_ENABLE()
94 #define MCO2_GPIO_PORT GPIOC
95 #define MCO2_PIN GPIO_PIN_9
96 
100 /* Private variables ---------------------------------------------------------*/
107 /* Private function prototypes -----------------------------------------------*/
108 /* Private functions ---------------------------------------------------------*/
109 
203 {
204  return HAL_OK;
205 }
206 
221 __weak HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct)
222 {
223  uint32_t tickstart, pll_config;
224 
225  /* Check Null pointer */
226  if(RCC_OscInitStruct == NULL)
227  {
228  return HAL_ERROR;
229  }
230 
231  /* Check the parameters */
233  /*------------------------------- HSE Configuration ------------------------*/
234  if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSE) == RCC_OSCILLATORTYPE_HSE)
235  {
236  /* Check the parameters */
237  assert_param(IS_RCC_HSE(RCC_OscInitStruct->HSEState));
238  /* When the HSE is used as system clock or clock source for PLL in these cases HSE will not disabled */
241  {
242  if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) && (RCC_OscInitStruct->HSEState == RCC_HSE_OFF))
243  {
244  return HAL_ERROR;
245  }
246  }
247  else
248  {
249  /* Set the new HSE configuration ---------------------------------------*/
250  __HAL_RCC_HSE_CONFIG(RCC_OscInitStruct->HSEState);
251 
252  /* Check the HSE State */
253  if((RCC_OscInitStruct->HSEState) != RCC_HSE_OFF)
254  {
255  /* Get Start Tick */
256  tickstart = HAL_GetTick();
257 
258  /* Wait till HSE is ready */
260  {
261  if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE)
262  {
263  return HAL_TIMEOUT;
264  }
265  }
266  }
267  else
268  {
269  /* Get Start Tick */
270  tickstart = HAL_GetTick();
271 
272  /* Wait till HSE is bypassed or disabled */
274  {
275  if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE)
276  {
277  return HAL_TIMEOUT;
278  }
279  }
280  }
281  }
282  }
283  /*----------------------------- HSI Configuration --------------------------*/
284  if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI) == RCC_OSCILLATORTYPE_HSI)
285  {
286  /* Check the parameters */
287  assert_param(IS_RCC_HSI(RCC_OscInitStruct->HSIState));
289 
290  /* Check if HSI is used as system clock or as PLL source when PLL is selected as system clock */
293  {
294  /* When HSI is used as system clock it will not disabled */
295  if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) && (RCC_OscInitStruct->HSIState != RCC_HSI_ON))
296  {
297  return HAL_ERROR;
298  }
299  /* Otherwise, just the calibration is allowed */
300  else
301  {
302  /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/
304  }
305  }
306  else
307  {
308  /* Check the HSI State */
309  if((RCC_OscInitStruct->HSIState)!= RCC_HSI_OFF)
310  {
311  /* Enable the Internal High Speed oscillator (HSI). */
313 
314  /* Get Start Tick*/
315  tickstart = HAL_GetTick();
316 
317  /* Wait till HSI is ready */
319  {
320  if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE)
321  {
322  return HAL_TIMEOUT;
323  }
324  }
325 
326  /* Adjusts the Internal High Speed oscillator (HSI) calibration value. */
328  }
329  else
330  {
331  /* Disable the Internal High Speed oscillator (HSI). */
333 
334  /* Get Start Tick*/
335  tickstart = HAL_GetTick();
336 
337  /* Wait till HSI is ready */
339  {
340  if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE)
341  {
342  return HAL_TIMEOUT;
343  }
344  }
345  }
346  }
347  }
348  /*------------------------------ LSI Configuration -------------------------*/
349  if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSI) == RCC_OSCILLATORTYPE_LSI)
350  {
351  /* Check the parameters */
352  assert_param(IS_RCC_LSI(RCC_OscInitStruct->LSIState));
353 
354  /* Check the LSI State */
355  if((RCC_OscInitStruct->LSIState)!= RCC_LSI_OFF)
356  {
357  /* Enable the Internal Low Speed oscillator (LSI). */
359 
360  /* Get Start Tick*/
361  tickstart = HAL_GetTick();
362 
363  /* Wait till LSI is ready */
365  {
366  if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE)
367  {
368  return HAL_TIMEOUT;
369  }
370  }
371  }
372  else
373  {
374  /* Disable the Internal Low Speed oscillator (LSI). */
376 
377  /* Get Start Tick */
378  tickstart = HAL_GetTick();
379 
380  /* Wait till LSI is ready */
382  {
383  if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE)
384  {
385  return HAL_TIMEOUT;
386  }
387  }
388  }
389  }
390  /*------------------------------ LSE Configuration -------------------------*/
391  if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSE) == RCC_OSCILLATORTYPE_LSE)
392  {
393  FlagStatus pwrclkchanged = RESET;
394 
395  /* Check the parameters */
396  assert_param(IS_RCC_LSE(RCC_OscInitStruct->LSEState));
397 
398  /* Update LSE configuration in Backup Domain control register */
399  /* Requires to enable write access to Backup Domain of necessary */
401  {
403  pwrclkchanged = SET;
404  }
405 
406  if(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP))
407  {
408  /* Enable write access to Backup domain */
409  SET_BIT(PWR->CR, PWR_CR_DBP);
410 
411  /* Wait for Backup domain Write protection disable */
412  tickstart = HAL_GetTick();
413 
414  while(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP))
415  {
416  if((HAL_GetTick() - tickstart) > RCC_DBP_TIMEOUT_VALUE)
417  {
418  return HAL_TIMEOUT;
419  }
420  }
421  }
422 
423  /* Set the new LSE configuration -----------------------------------------*/
424  __HAL_RCC_LSE_CONFIG(RCC_OscInitStruct->LSEState);
425  /* Check the LSE State */
426  if((RCC_OscInitStruct->LSEState) != RCC_LSE_OFF)
427  {
428  /* Get Start Tick*/
429  tickstart = HAL_GetTick();
430 
431  /* Wait till LSE is ready */
433  {
434  if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE)
435  {
436  return HAL_TIMEOUT;
437  }
438  }
439  }
440  else
441  {
442  /* Get Start Tick */
443  tickstart = HAL_GetTick();
444 
445  /* Wait till LSE is ready */
447  {
448  if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE)
449  {
450  return HAL_TIMEOUT;
451  }
452  }
453  }
454 
455  /* Restore clock configuration if changed */
456  if(pwrclkchanged == SET)
457  {
459  }
460  }
461  /*-------------------------------- PLL Configuration -----------------------*/
462  /* Check the parameters */
463  assert_param(IS_RCC_PLL(RCC_OscInitStruct->PLL.PLLState));
464  if ((RCC_OscInitStruct->PLL.PLLState) != RCC_PLL_NONE)
465  {
466  /* Check if the PLL is used as system clock or not */
468  {
469  if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_ON)
470  {
471  /* Check the parameters */
472  assert_param(IS_RCC_PLLSOURCE(RCC_OscInitStruct->PLL.PLLSource));
473  assert_param(IS_RCC_PLLM_VALUE(RCC_OscInitStruct->PLL.PLLM));
474  assert_param(IS_RCC_PLLN_VALUE(RCC_OscInitStruct->PLL.PLLN));
475  assert_param(IS_RCC_PLLP_VALUE(RCC_OscInitStruct->PLL.PLLP));
476  assert_param(IS_RCC_PLLQ_VALUE(RCC_OscInitStruct->PLL.PLLQ));
477 
478  /* Disable the main PLL. */
480 
481  /* Get Start Tick */
482  tickstart = HAL_GetTick();
483 
484  /* Wait till PLL is ready */
486  {
487  if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE)
488  {
489  return HAL_TIMEOUT;
490  }
491  }
492 
493  /* Configure the main PLL clock source, multiplication and division factors. */
494  WRITE_REG(RCC->PLLCFGR, (RCC_OscInitStruct->PLL.PLLSource | \
495  RCC_OscInitStruct->PLL.PLLM | \
496  (RCC_OscInitStruct->PLL.PLLN << RCC_PLLCFGR_PLLN_Pos) | \
497  (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U) << RCC_PLLCFGR_PLLP_Pos) | \
498  (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos)));
499  /* Enable the main PLL. */
501 
502  /* Get Start Tick */
503  tickstart = HAL_GetTick();
504 
505  /* Wait till PLL is ready */
507  {
508  if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE)
509  {
510  return HAL_TIMEOUT;
511  }
512  }
513  }
514  else
515  {
516  /* Disable the main PLL. */
518 
519  /* Get Start Tick */
520  tickstart = HAL_GetTick();
521 
522  /* Wait till PLL is ready */
524  {
525  if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE)
526  {
527  return HAL_TIMEOUT;
528  }
529  }
530  }
531  }
532  else
533  {
534  /* Check if there is a request to disable the PLL used as System clock source */
535  if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF)
536  {
537  return HAL_ERROR;
538  }
539  else
540  {
541  /* Do not return HAL_ERROR if request repeats the current configuration */
542  pll_config = RCC->PLLCFGR;
543  if((READ_BIT(pll_config, RCC_PLLCFGR_PLLSRC) != RCC_OscInitStruct->PLL.PLLSource) ||
544  (READ_BIT(pll_config, RCC_PLLCFGR_PLLM) != RCC_OscInitStruct->PLL.PLLM) ||
545  (READ_BIT(pll_config, RCC_PLLCFGR_PLLN) != RCC_OscInitStruct->PLL.PLLN) ||
546  (READ_BIT(pll_config, RCC_PLLCFGR_PLLP) != RCC_OscInitStruct->PLL.PLLP) ||
547  (READ_BIT(pll_config, RCC_PLLCFGR_PLLQ) != RCC_OscInitStruct->PLL.PLLQ))
548  {
549  return HAL_ERROR;
550  }
551  }
552  }
553  }
554  return HAL_OK;
555 }
556 
582 HAL_StatusTypeDef HAL_RCC_ClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t FLatency)
583 {
584  uint32_t tickstart;
585 
586  /* Check Null pointer */
587  if(RCC_ClkInitStruct == NULL)
588  {
589  return HAL_ERROR;
590  }
591 
592  /* Check the parameters */
593  assert_param(IS_RCC_CLOCKTYPE(RCC_ClkInitStruct->ClockType));
594  assert_param(IS_FLASH_LATENCY(FLatency));
595 
596  /* To correctly read data from FLASH memory, the number of wait states (LATENCY)
597  must be correctly programmed according to the frequency of the CPU clock
598  (HCLK) and the supply voltage of the device. */
599 
600  /* Increasing the number of wait states because of higher CPU frequency */
601  if(FLatency > __HAL_FLASH_GET_LATENCY())
602  {
603  /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */
604  __HAL_FLASH_SET_LATENCY(FLatency);
605 
606  /* Check that the new number of wait states is taken into account to access the Flash
607  memory by reading the FLASH_ACR register */
608  if(__HAL_FLASH_GET_LATENCY() != FLatency)
609  {
610  return HAL_ERROR;
611  }
612  }
613 
614  /*-------------------------- HCLK Configuration --------------------------*/
615  if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_HCLK) == RCC_CLOCKTYPE_HCLK)
616  {
617  /* Set the highest APBx dividers in order to ensure that we do not go through
618  a non-spec phase whatever we decrease or increase HCLK. */
619  if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1)
620  {
622  }
623 
624  if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2)
625  {
627  }
628 
629  assert_param(IS_RCC_HCLK(RCC_ClkInitStruct->AHBCLKDivider));
630  MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, RCC_ClkInitStruct->AHBCLKDivider);
631  }
632 
633  /*------------------------- SYSCLK Configuration ---------------------------*/
634  if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_SYSCLK) == RCC_CLOCKTYPE_SYSCLK)
635  {
636  assert_param(IS_RCC_SYSCLKSOURCE(RCC_ClkInitStruct->SYSCLKSource));
637 
638  /* HSE is selected as System Clock Source */
639  if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_HSE)
640  {
641  /* Check the HSE ready flag */
643  {
644  return HAL_ERROR;
645  }
646  }
647  /* PLL is selected as System Clock Source */
648  else if((RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_PLLCLK) ||
649  (RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_PLLRCLK))
650  {
651  /* Check the PLL ready flag */
653  {
654  return HAL_ERROR;
655  }
656  }
657  /* HSI is selected as System Clock Source */
658  else
659  {
660  /* Check the HSI ready flag */
662  {
663  return HAL_ERROR;
664  }
665  }
666 
667  __HAL_RCC_SYSCLK_CONFIG(RCC_ClkInitStruct->SYSCLKSource);
668 
669  /* Get Start Tick */
670  tickstart = HAL_GetTick();
671 
672  while (__HAL_RCC_GET_SYSCLK_SOURCE() != (RCC_ClkInitStruct->SYSCLKSource << RCC_CFGR_SWS_Pos))
673  {
674  if ((HAL_GetTick() - tickstart) > CLOCKSWITCH_TIMEOUT_VALUE)
675  {
676  return HAL_TIMEOUT;
677  }
678  }
679  }
680 
681  /* Decreasing the number of wait states because of lower CPU frequency */
682  if(FLatency < __HAL_FLASH_GET_LATENCY())
683  {
684  /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */
685  __HAL_FLASH_SET_LATENCY(FLatency);
686 
687  /* Check that the new number of wait states is taken into account to access the Flash
688  memory by reading the FLASH_ACR register */
689  if(__HAL_FLASH_GET_LATENCY() != FLatency)
690  {
691  return HAL_ERROR;
692  }
693  }
694 
695  /*-------------------------- PCLK1 Configuration ---------------------------*/
696  if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1)
697  {
698  assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB1CLKDivider));
699  MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, RCC_ClkInitStruct->APB1CLKDivider);
700  }
701 
702  /*-------------------------- PCLK2 Configuration ---------------------------*/
703  if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2)
704  {
705  assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB2CLKDivider));
706  MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, ((RCC_ClkInitStruct->APB2CLKDivider) << 3U));
707  }
708 
709  /* Update the SystemCoreClock global variable */
711 
712  /* Configure the source of time base considering new system clocks settings */
714 
715  return HAL_OK;
716 }
717 
766 void HAL_RCC_MCOConfig(uint32_t RCC_MCOx, uint32_t RCC_MCOSource, uint32_t RCC_MCODiv)
767 {
768  GPIO_InitTypeDef GPIO_InitStruct;
769  /* Check the parameters */
770  assert_param(IS_RCC_MCO(RCC_MCOx));
771  assert_param(IS_RCC_MCODIV(RCC_MCODiv));
772  /* RCC_MCO1 */
773  if(RCC_MCOx == RCC_MCO1)
774  {
775  assert_param(IS_RCC_MCO1SOURCE(RCC_MCOSource));
776 
777  /* MCO1 Clock Enable */
778  __MCO1_CLK_ENABLE();
779 
780  /* Configure the MCO1 pin in alternate function mode */
781  GPIO_InitStruct.Pin = MCO1_PIN;
782  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
783  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
784  GPIO_InitStruct.Pull = GPIO_NOPULL;
785  GPIO_InitStruct.Alternate = GPIO_AF0_MCO;
786  HAL_GPIO_Init(MCO1_GPIO_PORT, &GPIO_InitStruct);
787 
788  /* Mask MCO1 and MCO1PRE[2:0] bits then Select MCO1 clock source and prescaler */
789  MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO1 | RCC_CFGR_MCO1PRE), (RCC_MCOSource | RCC_MCODiv));
790 
791  /* This RCC MCO1 enable feature is available only on STM32F410xx devices */
792 #if defined(RCC_CFGR_MCO1EN)
793  __HAL_RCC_MCO1_ENABLE();
794 #endif /* RCC_CFGR_MCO1EN */
795  }
796 #if defined(RCC_CFGR_MCO2)
797  else
798  {
799  assert_param(IS_RCC_MCO2SOURCE(RCC_MCOSource));
800 
801  /* MCO2 Clock Enable */
802  __MCO2_CLK_ENABLE();
803 
804  /* Configure the MCO2 pin in alternate function mode */
805  GPIO_InitStruct.Pin = MCO2_PIN;
806  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
807  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
808  GPIO_InitStruct.Pull = GPIO_NOPULL;
809  GPIO_InitStruct.Alternate = GPIO_AF0_MCO;
810  HAL_GPIO_Init(MCO2_GPIO_PORT, &GPIO_InitStruct);
811 
812  /* Mask MCO2 and MCO2PRE[2:0] bits then Select MCO2 clock source and prescaler */
813  MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO2 | RCC_CFGR_MCO2PRE), (RCC_MCOSource | (RCC_MCODiv << 3U)));
814 
815  /* This RCC MCO2 enable feature is available only on STM32F410Rx devices */
816 #if defined(RCC_CFGR_MCO2EN)
817  __HAL_RCC_MCO2_ENABLE();
818 #endif /* RCC_CFGR_MCO2EN */
819  }
820 #endif /* RCC_CFGR_MCO2 */
821 }
822 
832 void HAL_RCC_EnableCSS(void)
833 {
834  *(__IO uint32_t *) RCC_CR_CSSON_BB = (uint32_t)ENABLE;
835 }
836 
841 void HAL_RCC_DisableCSS(void)
842 {
843  *(__IO uint32_t *) RCC_CR_CSSON_BB = (uint32_t)DISABLE;
844 }
845 
876 __weak uint32_t HAL_RCC_GetSysClockFreq(void)
877 {
878  uint32_t pllm = 0U, pllvco = 0U, pllp = 0U;
879  uint32_t sysclockfreq = 0U;
880 
881  /* Get SYSCLK source -------------------------------------------------------*/
882  switch (RCC->CFGR & RCC_CFGR_SWS)
883  {
884  case RCC_CFGR_SWS_HSI: /* HSI used as system clock source */
885  {
886  sysclockfreq = HSI_VALUE;
887  break;
888  }
889  case RCC_CFGR_SWS_HSE: /* HSE used as system clock source */
890  {
891  sysclockfreq = HSE_VALUE;
892  break;
893  }
894  case RCC_CFGR_SWS_PLL: /* PLL used as system clock source */
895  {
896  /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN
897  SYSCLK = PLL_VCO / PLLP */
898  pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
900  {
901  /* HSE used as PLL clock source */
902  pllvco = (uint32_t) ((((uint64_t) HSE_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm);
903  }
904  else
905  {
906  /* HSI used as PLL clock source */
907  pllvco = (uint32_t) ((((uint64_t) HSI_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm);
908  }
909  pllp = ((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >> RCC_PLLCFGR_PLLP_Pos) + 1U) *2U);
910 
911  sysclockfreq = pllvco/pllp;
912  break;
913  }
914  default:
915  {
916  sysclockfreq = HSI_VALUE;
917  break;
918  }
919  }
920  return sysclockfreq;
921 }
922 
932 uint32_t HAL_RCC_GetHCLKFreq(void)
933 {
934  return SystemCoreClock;
935 }
936 
943 uint32_t HAL_RCC_GetPCLK1Freq(void)
944 {
945  /* Get HCLK source and Compute PCLK1 frequency ---------------------------*/
947 }
948 
955 uint32_t HAL_RCC_GetPCLK2Freq(void)
956 {
957  /* Get HCLK source and Compute PCLK2 frequency ---------------------------*/
959 }
960 
968 __weak void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct)
969 {
970  /* Set all possible values for the Oscillator type parameter ---------------*/
972 
973  /* Get the HSE configuration -----------------------------------------------*/
974  if((RCC->CR &RCC_CR_HSEBYP) == RCC_CR_HSEBYP)
975  {
976  RCC_OscInitStruct->HSEState = RCC_HSE_BYPASS;
977  }
978  else if((RCC->CR &RCC_CR_HSEON) == RCC_CR_HSEON)
979  {
980  RCC_OscInitStruct->HSEState = RCC_HSE_ON;
981  }
982  else
983  {
984  RCC_OscInitStruct->HSEState = RCC_HSE_OFF;
985  }
986 
987  /* Get the HSI configuration -----------------------------------------------*/
988  if((RCC->CR &RCC_CR_HSION) == RCC_CR_HSION)
989  {
990  RCC_OscInitStruct->HSIState = RCC_HSI_ON;
991  }
992  else
993  {
994  RCC_OscInitStruct->HSIState = RCC_HSI_OFF;
995  }
996 
997  RCC_OscInitStruct->HSICalibrationValue = (uint32_t)((RCC->CR &RCC_CR_HSITRIM) >> RCC_CR_HSITRIM_Pos);
998 
999  /* Get the LSE configuration -----------------------------------------------*/
1000  if((RCC->BDCR &RCC_BDCR_LSEBYP) == RCC_BDCR_LSEBYP)
1001  {
1002  RCC_OscInitStruct->LSEState = RCC_LSE_BYPASS;
1003  }
1004  else if((RCC->BDCR &RCC_BDCR_LSEON) == RCC_BDCR_LSEON)
1005  {
1006  RCC_OscInitStruct->LSEState = RCC_LSE_ON;
1007  }
1008  else
1009  {
1010  RCC_OscInitStruct->LSEState = RCC_LSE_OFF;
1011  }
1012 
1013  /* Get the LSI configuration -----------------------------------------------*/
1014  if((RCC->CSR &RCC_CSR_LSION) == RCC_CSR_LSION)
1015  {
1016  RCC_OscInitStruct->LSIState = RCC_LSI_ON;
1017  }
1018  else
1019  {
1020  RCC_OscInitStruct->LSIState = RCC_LSI_OFF;
1021  }
1022 
1023  /* Get the PLL configuration -----------------------------------------------*/
1024  if((RCC->CR &RCC_CR_PLLON) == RCC_CR_PLLON)
1025  {
1026  RCC_OscInitStruct->PLL.PLLState = RCC_PLL_ON;
1027  }
1028  else
1029  {
1030  RCC_OscInitStruct->PLL.PLLState = RCC_PLL_OFF;
1031  }
1032  RCC_OscInitStruct->PLL.PLLSource = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC);
1033  RCC_OscInitStruct->PLL.PLLM = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM);
1034  RCC_OscInitStruct->PLL.PLLN = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos);
1035  RCC_OscInitStruct->PLL.PLLP = (uint32_t)((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) + RCC_PLLCFGR_PLLP_0) << 1U) >> RCC_PLLCFGR_PLLP_Pos);
1036  RCC_OscInitStruct->PLL.PLLQ = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLQ) >> RCC_PLLCFGR_PLLQ_Pos);
1037 }
1038 
1047 void HAL_RCC_GetClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t *pFLatency)
1048 {
1049  /* Set all possible values for the Clock type parameter --------------------*/
1051 
1052  /* Get the SYSCLK configuration --------------------------------------------*/
1053  RCC_ClkInitStruct->SYSCLKSource = (uint32_t)(RCC->CFGR & RCC_CFGR_SW);
1054 
1055  /* Get the HCLK configuration ----------------------------------------------*/
1056  RCC_ClkInitStruct->AHBCLKDivider = (uint32_t)(RCC->CFGR & RCC_CFGR_HPRE);
1057 
1058  /* Get the APB1 configuration ----------------------------------------------*/
1059  RCC_ClkInitStruct->APB1CLKDivider = (uint32_t)(RCC->CFGR & RCC_CFGR_PPRE1);
1060 
1061  /* Get the APB2 configuration ----------------------------------------------*/
1062  RCC_ClkInitStruct->APB2CLKDivider = (uint32_t)((RCC->CFGR & RCC_CFGR_PPRE2) >> 3U);
1063 
1064  /* Get the Flash Wait State (Latency) configuration ------------------------*/
1065  *pFLatency = (uint32_t)(FLASH->ACR & FLASH_ACR_LATENCY);
1066 }
1067 
1073 void HAL_RCC_NMI_IRQHandler(void)
1074 {
1075  /* Check RCC CSSF flag */
1077  {
1078  /* RCC Clock Security System interrupt user callback */
1080 
1081  /* Clear RCC CSS pending bit */
1083  }
1084 }
1085 
1090 __weak void HAL_RCC_CSSCallback(void)
1091 {
1092  /* NOTE : This function Should not be modified, when the callback is needed,
1093  the HAL_RCC_CSSCallback could be implemented in the user file
1094  */
1095 }
1096 
1105 #endif /* HAL_RCC_MODULE_ENABLED */
1106 
1114 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
assert_param
#define assert_param(expr)
Include module's header file.
Definition: stm32f407/stm32f407g-disc1/Inc/stm32f4xx_hal_conf.h:353
RCC_PLLInitTypeDef::PLLQ
uint32_t PLLQ
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h:65
__HAL_RCC_HSE_CONFIG
#define __HAL_RCC_HSE_CONFIG(__STATE__)
Macro to configure the External High Speed oscillator (HSE).
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:895
__IO
#define __IO
Definition: imxrt1050/imxrt1050-evkb/CMSIS/core_cm7.h:237
GPIO_MODE_AF_PP
#define GPIO_MODE_AF_PP
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:122
HAL_StatusTypeDef
HAL_StatusTypeDef
HAL Status structures definition
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h:40
RCC_PLLCFGR_PLLP_Pos
#define RCC_PLLCFGR_PLLP_Pos
Definition: stm32f407xx.h:9508
RCC_CFGR_PPRE1_Pos
#define RCC_CFGR_PPRE1_Pos
Definition: stm32f407xx.h:9574
RCC_PLLSOURCE_HSI
#define RCC_PLLSOURCE_HSI
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:181
HAL_IS_BIT_CLR
#define HAL_IS_BIT_CLR(REG, BIT)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h:64
RCC_PLLInitTypeDef::PLLState
uint32_t PLLState
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h:49
DISABLE
@ DISABLE
Definition: stm32f407/stm32f407g-disc1/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h:193
PWR
#define PWR
Definition: stm32f407xx.h:1083
HSI_TIMEOUT_VALUE
#define HSI_TIMEOUT_VALUE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1339
IS_RCC_PLLSOURCE
#define IS_RCC_PLLSOURCE(SOURCE)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1373
RCC_LSE_OFF
#define RCC_LSE_OFF
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:130
RCC_HCLK_DIV16
#define RCC_HCLK_DIV16
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:247
NULL
#define NULL
Definition: porcupine/demo/c/dr_libs/tests/external/miniaudio/extras/speex_resampler/thirdparty/resample.c:92
HAL_RCC_GetOscConfig
void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct)
GPIO_InitTypeDef
GPIO Init structure definition
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:47
RCC_PLL_ON
#define RCC_PLL_ON
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:162
HAL_RCC_CSSCallback
void HAL_RCC_CSSCallback(void)
__HAL_RCC_PWR_CLK_DISABLE
#define __HAL_RCC_PWR_CLK_DISABLE()
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:526
RCC_FLAG_HSERDY
#define RCC_FLAG_HSERDY
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:350
RCC_CFGR_PPRE2
#define RCC_CFGR_PPRE2
Definition: stm32f407xx.h:9590
RCC_ClkInitTypeDef
RCC System, AHB and APB busses clock configuration structure definition.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:77
GPIO_AF0_MCO
#define GPIO_AF0_MCO
Definition: stm32h735/stm32h735g-dk/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_gpio_ex.h:54
RCC_PLLInitTypeDef::PLLP
uint32_t PLLP
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h:62
HSE_TIMEOUT_VALUE
#define HSE_TIMEOUT_VALUE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1338
__HAL_RCC_LSE_CONFIG
#define __HAL_RCC_LSE_CONFIG(__STATE__)
Macro to configure the External Low Speed oscillator (LSE).
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:938
RCC_OscInitTypeDef
RCC Internal/External Oscillator (HSE, HSI, LSE and LSI) configuration structure definition.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:51
__HAL_RCC_HSI_DISABLE
#define __HAL_RCC_HSI_DISABLE()
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:837
GPIO_InitTypeDef::Alternate
uint32_t Alternate
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:61
PLL_TIMEOUT_VALUE
#define PLL_TIMEOUT_VALUE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h:6854
RCC_OscInitTypeDef::HSICalibrationValue
uint32_t HSICalibrationValue
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:65
RCC_FLAG_LSERDY
#define RCC_FLAG_LSERDY
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:355
IS_RCC_CLOCKTYPE
#define IS_RCC_CLOCKTYPE(CLK)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1426
IS_RCC_OSCILLATORTYPE
#define IS_RCC_OSCILLATORTYPE(OSCILLATOR)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1359
RCC_CFGR_SWS_PLL
#define RCC_CFGR_SWS_PLL
Definition: stm32f407xx.h:9552
RCC_ClkInitTypeDef::APB2CLKDivider
uint32_t APB2CLKDivider
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:91
RCC_PLLInitTypeDef::PLLM
uint32_t PLLM
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h:55
RCC_CFGR_MCO1
#define RCC_CFGR_MCO1
Definition: stm32f407xx.h:9614
RCC_FLAG_HSIRDY
#define RCC_FLAG_HSIRDY
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:349
RCC_IT_CSS
#define RCC_IT_CSS
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:334
RCC_CFGR_SWS_Pos
#define RCC_CFGR_SWS_Pos
Definition: stm32f407xx.h:9544
RCC_PLLCFGR_PLLSRC_HSI
#define RCC_PLLCFGR_PLLSRC_HSI
Definition: stm32f407xx.h:9520
RCC_OscInitTypeDef::LSEState
uint32_t LSEState
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:59
HAL_RCC_GetPCLK2Freq
uint32_t HAL_RCC_GetPCLK2Freq(void)
RCC_BDCR_LSEBYP
#define RCC_BDCR_LSEBYP
Definition: stm32f407xx.h:10281
IS_RCC_MCO2SOURCE
#define IS_RCC_MCO2SOURCE(SOURCE)
Definition: stm32f7xx_hal_rcc.h:1258
HAL_RCC_GetClockConfig
void HAL_RCC_GetClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t *pFLatency)
HAL_ERROR
@ HAL_ERROR
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h:43
HAL_GetTick
uint32_t HAL_GetTick(void)
Provides a tick value in millisecond.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:323
RCC_CFGR_MCO2PRE
#define RCC_CFGR_MCO2PRE
Definition: stm32f407xx.h:9631
RCC_CR_HSEON
#define RCC_CR_HSEON
Definition: stm32f407xx.h:9456
RCC_FLAG_PLLRDY
#define RCC_FLAG_PLLRDY
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:351
__HAL_RCC_GET_PLL_OSCSOURCE
#define __HAL_RCC_GET_PLL_OSCSOURCE()
Macro to get the oscillator used as PLL clock source.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1096
RCC_PLLCFGR_PLLSRC_HSE
#define RCC_PLLCFGR_PLLSRC_HSE
Definition: stm32f407xx.h:9519
uwTickPrio
uint32_t uwTickPrio
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:95
HAL_RCC_NMI_IRQHandler
void HAL_RCC_NMI_IRQHandler(void)
ENABLE
@ ENABLE
Definition: stm32f407/stm32f407g-disc1/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h:194
RCC_CFGR_HPRE
#define RCC_CFGR_HPRE
Definition: stm32f407xx.h:9557
__HAL_RCC_PLL_DISABLE
#define __HAL_RCC_PLL_DISABLE()
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1038
IS_RCC_PLLQ_VALUE
#define IS_RCC_PLLQ_VALUE(VALUE)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1418
__HAL_FLASH_SET_LATENCY
#define __HAL_FLASH_SET_LATENCY(__LATENCY__)
Set the FLASH Latency.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h:178
RCC_SYSCLKSOURCE_PLLCLK
#define RCC_SYSCLKSOURCE_PLLCLK
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:205
RCC_PLLCFGR_PLLSRC
#define RCC_PLLCFGR_PLLSRC
Definition: stm32f407xx.h:9516
HAL_RCC_DeInit
HAL_StatusTypeDef HAL_RCC_DeInit(void)
HAL_OK
@ HAL_OK
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h:42
IS_RCC_MCO1SOURCE
#define IS_RCC_MCO1SOURCE(SOURCE)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1434
RCC_HSE_OFF
#define RCC_HSE_OFF
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:120
RCC_PLLCFGR_PLLP_0
#define RCC_PLLCFGR_PLLP_0
Definition: stm32f407xx.h:9511
HAL_GPIO_Init
void HAL_GPIO_Init(GPIO_TypeDef *GPIOx, GPIO_InitTypeDef *GPIO_Init)
RCC_CFGR_MCO2
#define RCC_CFGR_MCO2
Definition: stm32f407xx.h:9638
IS_RCC_CALIBRATION_VALUE
#define IS_RCC_CALIBRATION_VALUE(VALUE)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1440
RCC_PLL_NONE
#define RCC_PLL_NONE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:160
RCC_CLOCKTYPE_PCLK1
#define RCC_CLOCKTYPE_PCLK1
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:192
RCC_OscInitTypeDef::HSIState
uint32_t HSIState
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:62
RCC_PLLCFGR_PLLM
#define RCC_PLLCFGR_PLLM
Definition: stm32f407xx.h:9487
GPIO_InitTypeDef::Mode
uint32_t Mode
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:52
RCC_PLLCFGR_PLLQ
#define RCC_PLLCFGR_PLLQ
Definition: stm32f407xx.h:9524
RCC_CFGR_SWS
#define RCC_CFGR_SWS
Definition: stm32f407xx.h:9546
RCC_CFGR_PPRE1
#define RCC_CFGR_PPRE1
Definition: stm32f407xx.h:9576
__HAL_RCC_GET_IT
#define __HAL_RCC_GET_IT(__INTERRUPT__)
Check the RCC's interrupt has occurred or not.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1204
FLASH_ACR_LATENCY
#define FLASH_ACR_LATENCY
Definition: stm32f407xx.h:6678
HSI_VALUE
#define HSI_VALUE
Internal High Speed oscillator (HSI) value. This value is used by the RCC HAL module to compute the s...
Definition: stm32f407/stm32f407g-disc1/Inc/stm32f4xx_hal_conf.h:82
GPIO_InitTypeDef::Pull
uint32_t Pull
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:55
__HAL_FLASH_GET_LATENCY
#define __HAL_FLASH_GET_LATENCY()
Get the FLASH Latency.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h:185
GPIO_NOPULL
#define GPIO_NOPULL
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:154
RCC_CR_CSSON_BB
#define RCC_CR_CSSON_BB
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1303
IS_RCC_MCO
#define IS_RCC_MCO(MCOx)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1432
RCC_CFGR_SW
#define RCC_CFGR_SW
Definition: stm32f407xx.h:9535
RCC_HSE_BYPASS
#define RCC_HSE_BYPASS
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:122
RCC_PLLInitTypeDef::PLLSource
uint32_t PLLSource
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h:52
HAL_RCC_ClockConfig
HAL_StatusTypeDef HAL_RCC_ClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t FLatency)
RCC_ClkInitTypeDef::AHBCLKDivider
uint32_t AHBCLKDivider
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:85
RCC_SYSCLKSOURCE_PLLRCLK
#define RCC_SYSCLKSOURCE_PLLRCLK
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:206
SystemCoreClock
uint32_t SystemCoreClock
Definition: system_MIMXRT1052.c:69
__HAL_RCC_CLEAR_IT
#define __HAL_RCC_CLEAR_IT(__INTERRUPT__)
Clear the RCC's interrupt pending bits (Perform Byte access to RCC_CIR[23:16] bits to clear the selec...
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1190
RCC_CR_PLLON
#define RCC_CR_PLLON
Definition: stm32f407xx.h:9468
MODIFY_REG
#define MODIFY_REG(REG, CLEARMASK, SETMASK)
Definition: stm32f407/stm32f407g-disc1/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h:224
RCC_OSCILLATORTYPE_HSI
#define RCC_OSCILLATORTYPE_HSI
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:110
IS_RCC_LSI
#define IS_RCC_LSI(LSI)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1369
GPIO_SPEED_FREQ_VERY_HIGH
#define GPIO_SPEED_FREQ_VERY_HIGH
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:145
HAL_RCC_OscConfig
HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct)
RCC_CFGR_HPRE_Pos
#define RCC_CFGR_HPRE_Pos
Definition: stm32f407xx.h:9555
CLOCKSWITCH_TIMEOUT_VALUE
#define CLOCKSWITCH_TIMEOUT_VALUE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1341
RESET
@ RESET
Definition: stm32f407/stm32f407g-disc1/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h:187
RCC_OscInitTypeDef::PLL
RCC_PLLInitTypeDef PLL
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:71
RCC_CR_HSION
#define RCC_CR_HSION
Definition: stm32f407xx.h:9428
__HAL_RCC_HSI_ENABLE
#define __HAL_RCC_HSI_ENABLE()
Macros to enable or disable the Internal High Speed oscillator (HSI).
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:836
RCC_CFGR_PPRE2_Pos
#define RCC_CFGR_PPRE2_Pos
Definition: stm32f407xx.h:9588
RCC_ClkInitTypeDef::ClockType
uint32_t ClockType
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:79
GPIO_InitTypeDef::Speed
uint32_t Speed
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:58
HAL_RCC_DisableCSS
void HAL_RCC_DisableCSS(void)
RCC_CLOCKTYPE_PCLK2
#define RCC_CLOCKTYPE_PCLK2
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:193
RCC_OSCILLATORTYPE_LSE
#define RCC_OSCILLATORTYPE_LSE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:111
RCC_LSI_OFF
#define RCC_LSI_OFF
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:151
IS_RCC_SYSCLKSOURCE
#define IS_RCC_SYSCLKSOURCE(SOURCE)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1376
IS_RCC_MCODIV
#define IS_RCC_MCODIV(DIV)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1437
RCC_CFGR_SWS_HSE
#define RCC_CFGR_SWS_HSE
Definition: stm32f407xx.h:9551
RCC_LSE_BYPASS
#define RCC_LSE_BYPASS
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:132
READ_BIT
#define READ_BIT(REG, BIT)
Definition: stm32f407/stm32f407g-disc1/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h:216
IS_RCC_HCLK
#define IS_RCC_HCLK(HCLK)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1420
__HAL_RCC_SYSCLK_CONFIG
#define __HAL_RCC_SYSCLK_CONFIG(__RCC_SYSCLKSOURCE__)
Macro to configure the system clock source.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1077
IS_RCC_PLLN_VALUE
#define IS_RCC_PLLN_VALUE(VALUE)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h:6877
RCC_CSR_LSION
#define RCC_CSR_LSION
Definition: stm32f407xx.h:10299
RCC_CLOCKTYPE_SYSCLK
#define RCC_CLOCKTYPE_SYSCLK
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:190
RCC_LSE_TIMEOUT_VALUE
#define RCC_LSE_TIMEOUT_VALUE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1336
HAL_RCC_MCOConfig
void HAL_RCC_MCOConfig(uint32_t RCC_MCOx, uint32_t RCC_MCOSource, uint32_t RCC_MCODiv)
RCC_HSE_ON
#define RCC_HSE_ON
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:121
HAL_RCC_GetHCLKFreq
uint32_t HAL_RCC_GetHCLKFreq(void)
RCC_PLLCFGR_PLLQ_Pos
#define RCC_PLLCFGR_PLLQ_Pos
Definition: stm32f407xx.h:9522
RCC
#define RCC
Definition: stm32f407xx.h:1113
__HAL_RCC_PWR_CLK_ENABLE
#define __HAL_RCC_PWR_CLK_ENABLE()
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:512
RCC_MCO1
#define RCC_MCO1
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:296
AHBPrescTable
const uint8_t AHBPrescTable[16]
Definition: stm32f407/stm32f407g-disc1/Src/system_stm32f4xx.c:123
IS_RCC_HSE
#define IS_RCC_HSE(HSE)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1361
RCC_CLOCKTYPE_HCLK
#define RCC_CLOCKTYPE_HCLK
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:191
IS_RCC_HSI
#define IS_RCC_HSI(HSI)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1367
HAL_TIMEOUT
@ HAL_TIMEOUT
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h:45
__HAL_RCC_PLL_ENABLE
#define __HAL_RCC_PLL_ENABLE()
Macros to enable or disable the main PLL.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1037
RCC_CR_HSITRIM
#define RCC_CR_HSITRIM
Definition: stm32f407xx.h:9435
RCC_OscInitTypeDef::LSIState
uint32_t LSIState
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:68
__HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST
#define __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(__HSICalibrationValue__)
Macro to adjust the Internal High Speed oscillator (HSI) calibration value.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:846
APBPrescTable
const uint8_t APBPrescTable[8]
Definition: stm32f407/stm32f407g-disc1/Src/system_stm32f4xx.c:124
RCC_PLL_OFF
#define RCC_PLL_OFF
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:161
__HAL_RCC_LSI_ENABLE
#define __HAL_RCC_LSI_ENABLE()
Macros to enable or disable the Internal Low Speed oscillator (LSI).
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:864
RCC_PLLCFGR_PLLN
#define RCC_PLLCFGR_PLLN
Definition: stm32f407xx.h:9497
HAL_RCC_GetPCLK1Freq
uint32_t HAL_RCC_GetPCLK1Freq(void)
RCC_CR_HSEBYP
#define RCC_CR_HSEBYP
Definition: stm32f407xx.h:9462
SET
@ SET
Definition: stm32f407/stm32f407g-disc1/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h:188
RCC_PLLCFGR_PLLN_Pos
#define RCC_PLLCFGR_PLLN_Pos
Definition: stm32f407xx.h:9495
__HAL_RCC_GET_FLAG
#define __HAL_RCC_GET_FLAG(__FLAG__)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1230
HAL_InitTick
HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority)
This function configures the source of the time base. The time source is configured to have 1ms time ...
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:253
RCC_BDCR_LSEON
#define RCC_BDCR_LSEON
Definition: stm32f407xx.h:10275
HAL_RCC_GetSysClockFreq
uint32_t HAL_RCC_GetSysClockFreq(void)
FlagStatus
FlagStatus
Definition: stm32f407/stm32f407g-disc1/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h:185
RCC_CFGR_SWS_HSI
#define RCC_CFGR_SWS_HSI
Definition: stm32f407xx.h:9550
IS_FLASH_LATENCY
#define IS_FLASH_LATENCY(LATENCY)
Definition: stm32f7xx_hal_flash_ex.h:589
__HAL_RCC_LSI_DISABLE
#define __HAL_RCC_LSI_DISABLE()
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:865
RCC_CFGR_MCO1PRE
#define RCC_CFGR_MCO1PRE
Definition: stm32f407xx.h:9624
FLASH
#define FLASH
Definition: stm32f407xx.h:1114
RCC_DBP_TIMEOUT_VALUE
#define RCC_DBP_TIMEOUT_VALUE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1335
RCC_SYSCLKSOURCE_HSE
#define RCC_SYSCLKSOURCE_HSE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:204
RCC_LSE_ON
#define RCC_LSE_ON
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:131
HSE_VALUE
#define HSE_VALUE
Adjust the value of External High Speed oscillator (HSE) used in your application....
Definition: stm32f407/stm32f407g-disc1/Inc/stm32f4xx_hal_conf.h:69
__HAL_RCC_GET_SYSCLK_SOURCE
#define __HAL_RCC_GET_SYSCLK_SOURCE()
Macro to get the clock source used as system clock.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1088
RCC_ClkInitTypeDef::SYSCLKSource
uint32_t SYSCLKSource
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:82
RCC_OSCILLATORTYPE_HSE
#define RCC_OSCILLATORTYPE_HSE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:109
RCC_OscInitTypeDef::HSEState
uint32_t HSEState
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:56
WRITE_REG
#define WRITE_REG(REG, VAL)
Definition: stm32f407/stm32f407g-disc1/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h:220
PWR_CR_DBP
#define PWR_CR_DBP
Definition: stm32f407xx.h:9383
RCC_FLAG_LSIRDY
#define RCC_FLAG_LSIRDY
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:358
SET_BIT
#define SET_BIT(REG, BIT)
Definition: stm32f407/stm32f407g-disc1/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h:212
RCC_LSI_ON
#define RCC_LSI_ON
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:152
LSI_TIMEOUT_VALUE
#define LSI_TIMEOUT_VALUE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1340
IS_RCC_LSE
#define IS_RCC_LSE(LSE)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1364
RCC_PLLInitTypeDef::PLLN
uint32_t PLLN
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h:58
IS_RCC_PLLM_VALUE
#define IS_RCC_PLLM_VALUE(VALUE)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1414
RCC_OscInitTypeDef::OscillatorType
uint32_t OscillatorType
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:53
RCC_PLLCFGR_PLLP
#define RCC_PLLCFGR_PLLP
Definition: stm32f407xx.h:9510
IS_RCC_PLL
#define IS_RCC_PLL(PLL)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1371
RCC_HSI_ON
#define RCC_HSI_ON
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:141
RCC_ClkInitTypeDef::APB1CLKDivider
uint32_t APB1CLKDivider
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:88
IS_RCC_PLLP_VALUE
#define IS_RCC_PLLP_VALUE(VALUE)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1416
RCC_HSI_OFF
#define RCC_HSI_OFF
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:140
RCC_OSCILLATORTYPE_LSI
#define RCC_OSCILLATORTYPE_LSI
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:112
HAL_RCC_EnableCSS
void HAL_RCC_EnableCSS(void)
IS_RCC_PCLK
#define IS_RCC_PCLK(PCLK)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:1428
RCC_CR_HSITRIM_Pos
#define RCC_CR_HSITRIM_Pos
Definition: stm32f407xx.h:9433
__HAL_RCC_PWR_IS_CLK_DISABLED
#define __HAL_RCC_PWR_IS_CLK_DISABLED()
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:552
GPIO_InitTypeDef::Pin
uint32_t Pin
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:49


picovoice_driver
Author(s):
autogenerated on Fri Apr 1 2022 02:14:52