system_stm32f4xx.c
Go to the documentation of this file.
1 
117 #include "stm32f4xx.h"
118 
137 /* #define DATA_IN_ExtSRAM */
138 
141 /* #define VECT_TAB_SRAM */
142 #define VECT_TAB_OFFSET 0x00
146 /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */
147 #define PLL_M 8
148 #define PLL_N 336
150 /* SYSCLK = PLL_VCO / PLL_P */
151 #define PLL_P 2
153 /* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
154 #define PLL_Q 7
172  uint32_t SystemCoreClock = 168000000;
174  __I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
184 static void SetSysClock(void);
185 #ifdef DATA_IN_ExtSRAM
186  static void SystemInit_ExtMemCtl(void);
187 #endif /* DATA_IN_ExtSRAM */
188 
204 void SystemInit(void)
205 {
206 
207  /* FPU settings ------------------------------------------------------------*/
208  #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
209  SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
210  #endif
211 
212  /* Reset the RCC clock configuration to the default reset state ------------*/
213  /* Set HSION bit */
214  RCC->CR |= (uint32_t)0x00000001;
215 
216  /* Reset CFGR register */
217  RCC->CFGR = 0x00000000;
218 
219  /* Reset HSEON, CSSON and PLLON bits */
220  RCC->CR &= (uint32_t)0xFEF6FFFF;
221 
222  /* Reset PLLCFGR register */
223  RCC->PLLCFGR = 0x24003010;
224 
225  /* Reset HSEBYP bit */
226  RCC->CR &= (uint32_t)0xFFFBFFFF;
227 
228  /* Disable all interrupts */
229  RCC->CIR = 0x00000000;
230 
231 #ifdef DATA_IN_ExtSRAM
232  SystemInit_ExtMemCtl();
233 #endif /* DATA_IN_ExtSRAM */
234 
235  /* Configure the System clock source, PLL Multiplier and Divider factors,
236  AHB/APBx prescalers and Flash settings ----------------------------------*/
237  SetSysClock();
238 
239  /* Configure the Vector Table location add offset address ------------------*/
240 #ifdef VECT_TAB_SRAM
241  SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */
242 #else
243  SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
244 #endif
245 
246 
247 }
248 
285 void SystemCoreClockUpdate(void)
286 {
287  uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2;
288 
289  /* Get SYSCLK source -------------------------------------------------------*/
290  tmp = RCC->CFGR & RCC_CFGR_SWS;
291 
292  switch (tmp)
293  {
294  case 0x00: /* HSI used as system clock source */
296  break;
297  case 0x04: /* HSE used as system clock source */
299  break;
300  case 0x08: /* PLL used as system clock source */
301 
302  /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
303  SYSCLK = PLL_VCO / PLL_P
304  */
305  pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
306  pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
307 
308  if (pllsource != 0)
309  {
310  /* HSE used as PLL clock source */
311  pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
312  }
313  else
314  {
315  /* HSI used as PLL clock source */
316  pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
317  }
318 
319  pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2;
320  SystemCoreClock = pllvco/pllp;
321  break;
322  default:
324  break;
325  }
326  /* Compute HCLK frequency --------------------------------------------------*/
327  /* Get HCLK prescaler */
328  tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
329  /* HCLK frequency */
330  SystemCoreClock >>= tmp;
331 }
332 
341 static void SetSysClock(void)
342 {
343 /******************************************************************************/
344 /* PLL (clocked by HSE) used as System clock source */
345 /******************************************************************************/
346  __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
347 
348  /* Enable HSE */
349  RCC->CR |= ((uint32_t)RCC_CR_HSEON);
350 
351  /* Wait till HSE is ready and if Time out is reached exit */
352  do
353  {
354  HSEStatus = RCC->CR & RCC_CR_HSERDY;
355  StartUpCounter++;
356  } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
357 
358  if ((RCC->CR & RCC_CR_HSERDY) != RESET)
359  {
360  HSEStatus = (uint32_t)0x01;
361  }
362  else
363  {
364  HSEStatus = (uint32_t)0x00;
365  }
366 
367  if (HSEStatus == (uint32_t)0x01)
368  {
369  /* Enable high performance mode, System frequency up to 168 MHz */
370  RCC->APB1ENR |= RCC_APB1ENR_PWREN;
371  PWR->CR |= PWR_CR_PMODE;
372 
373  /* HCLK = SYSCLK / 1*/
374  RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
375 
376  /* PCLK2 = HCLK / 2*/
377  RCC->CFGR |= RCC_CFGR_PPRE2_DIV2;
378 
379  /* PCLK1 = HCLK / 4*/
380  RCC->CFGR |= RCC_CFGR_PPRE1_DIV4;
381 
382  /* Configure the main PLL */
383  RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
384  (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
385 
386  /* Enable the main PLL */
387  RCC->CR |= RCC_CR_PLLON;
388 
389  /* Wait till the main PLL is ready */
390  while((RCC->CR & RCC_CR_PLLRDY) == 0)
391  {
392  }
393 
394  /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
396 
397  /* Select the main PLL as system clock source */
398  RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
399  RCC->CFGR |= RCC_CFGR_SW_PLL;
400 
401  /* Wait till the main PLL is used as system clock source */
402  while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
403  {
404  }
405  }
406  else
407  { /* If HSE fails to start-up, the application will have wrong clock
408  configuration. User can add here some code to deal with this error */
409  }
410 
411 }
412 
419 #ifdef DATA_IN_ExtSRAM
420 
428 void SystemInit_ExtMemCtl(void)
429 {
430 /*-- GPIOs Configuration -----------------------------------------------------*/
431 /*
432  +-------------------+--------------------+------------------+------------------+
433  + SRAM pins assignment +
434  +-------------------+--------------------+------------------+------------------+
435  | PD0 <-> FSMC_D2 | PE0 <-> FSMC_NBL0 | PF0 <-> FSMC_A0 | PG0 <-> FSMC_A10 |
436  | PD1 <-> FSMC_D3 | PE1 <-> FSMC_NBL1 | PF1 <-> FSMC_A1 | PG1 <-> FSMC_A11 |
437  | PD4 <-> FSMC_NOE | PE3 <-> FSMC_A19 | PF2 <-> FSMC_A2 | PG2 <-> FSMC_A12 |
438  | PD5 <-> FSMC_NWE | PE4 <-> FSMC_A20 | PF3 <-> FSMC_A3 | PG3 <-> FSMC_A13 |
439  | PD8 <-> FSMC_D13 | PE7 <-> FSMC_D4 | PF4 <-> FSMC_A4 | PG4 <-> FSMC_A14 |
440  | PD9 <-> FSMC_D14 | PE8 <-> FSMC_D5 | PF5 <-> FSMC_A5 | PG5 <-> FSMC_A15 |
441  | PD10 <-> FSMC_D15 | PE9 <-> FSMC_D6 | PF12 <-> FSMC_A6 | PG9 <-> FSMC_NE2 |
442  | PD11 <-> FSMC_A16 | PE10 <-> FSMC_D7 | PF13 <-> FSMC_A7 |------------------+
443  | PD12 <-> FSMC_A17 | PE11 <-> FSMC_D8 | PF14 <-> FSMC_A8 |
444  | PD13 <-> FSMC_A18 | PE12 <-> FSMC_D9 | PF15 <-> FSMC_A9 |
445  | PD14 <-> FSMC_D0 | PE13 <-> FSMC_D10 |------------------+
446  | PD15 <-> FSMC_D1 | PE14 <-> FSMC_D11 |
447  | | PE15 <-> FSMC_D12 |
448  +-------------------+--------------------+
449 */
450  /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */
451  RCC->AHB1ENR = 0x00000078;
452 
453  /* Connect PDx pins to FSMC Alternate function */
454  GPIOD->AFR[0] = 0x00cc00cc;
455  GPIOD->AFR[1] = 0xcc0ccccc;
456  /* Configure PDx pins in Alternate function mode */
457  GPIOD->MODER = 0xaaaa0a0a;
458  /* Configure PDx pins speed to 100 MHz */
459  GPIOD->OSPEEDR = 0xffff0f0f;
460  /* Configure PDx pins Output type to push-pull */
461  GPIOD->OTYPER = 0x00000000;
462  /* No pull-up, pull-down for PDx pins */
463  GPIOD->PUPDR = 0x00000000;
464 
465  /* Connect PEx pins to FSMC Alternate function */
466  GPIOE->AFR[0] = 0xc00cc0cc;
467  GPIOE->AFR[1] = 0xcccccccc;
468  /* Configure PEx pins in Alternate function mode */
469  GPIOE->MODER = 0xaaaa828a;
470  /* Configure PEx pins speed to 100 MHz */
471  GPIOE->OSPEEDR = 0xffffc3cf;
472  /* Configure PEx pins Output type to push-pull */
473  GPIOE->OTYPER = 0x00000000;
474  /* No pull-up, pull-down for PEx pins */
475  GPIOE->PUPDR = 0x00000000;
476 
477  /* Connect PFx pins to FSMC Alternate function */
478  GPIOF->AFR[0] = 0x00cccccc;
479  GPIOF->AFR[1] = 0xcccc0000;
480  /* Configure PFx pins in Alternate function mode */
481  GPIOF->MODER = 0xaa000aaa;
482  /* Configure PFx pins speed to 100 MHz */
483  GPIOF->OSPEEDR = 0xff000fff;
484  /* Configure PFx pins Output type to push-pull */
485  GPIOF->OTYPER = 0x00000000;
486  /* No pull-up, pull-down for PFx pins */
487  GPIOF->PUPDR = 0x00000000;
488 
489  /* Connect PGx pins to FSMC Alternate function */
490  GPIOG->AFR[0] = 0x00cccccc;
491  GPIOG->AFR[1] = 0x000000c0;
492  /* Configure PGx pins in Alternate function mode */
493  GPIOG->MODER = 0x00080aaa;
494  /* Configure PGx pins speed to 100 MHz */
495  GPIOG->OSPEEDR = 0x000c0fff;
496  /* Configure PGx pins Output type to push-pull */
497  GPIOG->OTYPER = 0x00000000;
498  /* No pull-up, pull-down for PGx pins */
499  GPIOG->PUPDR = 0x00000000;
500 
501 /*-- FSMC Configuration ------------------------------------------------------*/
502  /* Enable the FSMC interface clock */
503  RCC->AHB3ENR = 0x00000001;
504 
505  /* Configure and enable Bank1_SRAM2 */
506  FSMC_Bank1->BTCR[2] = 0x00001015;
507  FSMC_Bank1->BTCR[3] = 0x00010603;//0x00010400;
508  FSMC_Bank1E->BWTR[2] = 0x0fffffff;
509 /*
510  Bank1_SRAM2 is configured as follow:
511 
512  p.FSMC_AddressSetupTime = 3;//0;
513  p.FSMC_AddressHoldTime = 0;
514  p.FSMC_DataSetupTime = 6;//4;
515  p.FSMC_BusTurnAroundDuration = 1;
516  p.FSMC_CLKDivision = 0;
517  p.FSMC_DataLatency = 0;
518  p.FSMC_AccessMode = FSMC_AccessMode_A;
519 
520  FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM2;
521  FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable;
522  FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_PSRAM;
523  FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b;
524  FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
525  FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable;
526  FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
527  FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable;
528  FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
529  FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable;
530  FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable;
531  FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
532  FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable;
533  FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &p;
534  FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &p;
535 */
536 
537 }
538 #endif /* DATA_IN_ExtSRAM */
539 
540 
552 /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
553 
#define RCC_PLLCFGR_PLLP
Definition: stm32f4xx.h:8609
#define RCC_PLLCFGR_PLLSRC_HSE
Definition: stm32f4xx.h:8614
uint32_t SystemCoreClock
#define FLASH_BASE
Definition: stm32f4xx.h:1843
#define RCC_CFGR_SWS_PLL
Definition: stm32f4xx.h:8650
#define FLASH_ACR_DCEN
Definition: stm32f4xx.h:4554
void SystemCoreClockUpdate(void)
Update SystemCoreClock variable according to Clock Register Values. The SystemCoreClock variable cont...
#define RCC_APB1ENR_PWREN
Definition: stm32f4xx.h:8941
#define FSMC_Bank1
Definition: stm32f10x.h:1448
#define GPIOG
Definition: stm32f4xx.h:2116
#define RCC_CFGR_HPRE
Definition: stm32f4xx.h:8656
#define RCC_CR_HSEON
Definition: stm32f4xx.h:8578
CMSIS Cortex-M4 Device Peripheral Access Layer Header File. This file contains all the peripheral reg...
#define RCC_PLLCFGR_PLLM
Definition: stm32f4xx.h:8590
#define RCC_CFGR_SW_PLL
Definition: stm32f4xx.h:8638
#define __I
Definition: core_cm0.h:195
#define FLASH
Definition: stm32f4xx.h:2123
#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 RCC_CR_PLLRDY
Definition: stm32f4xx.h:8583
#define SRAM_BASE
Definition: stm32f4xx.h:1871
#define RCC_PLLCFGR_PLLSRC
Definition: stm32f4xx.h:8613
#define RCC_CR_PLLON
Definition: stm32f4xx.h:8582
#define HSI_VALUE
Definition: stm32f4xx.h:150
#define SCB
Definition: core_cm0.h:503
#define RCC_PLLCFGR_PLLN
Definition: stm32f4xx.h:8598
#define GPIOD
Definition: stm32f4xx.h:2113
#define RCC_CFGR_HPRE_DIV1
Definition: stm32f4xx.h:8662
#define __IO
Definition: core_cm0.h:198
#define RCC_CFGR_PPRE2_DIV2
Definition: stm32f4xx.h:8697
__I uint8_t AHBPrescTable[16]
#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 RCC
Definition: stm32f4xx.h:2122
#define VECT_TAB_OFFSET
void SystemInit(void)
Setup the microcontroller system Initialize the Embedded Flash Interface, the PLL and update the Syst...
#define GPIOF
Definition: stm32f4xx.h:2115
#define FLASH_ACR_ICEN
Definition: stm32f4xx.h:4553
#define RCC_CFGR_SWS
Definition: stm32f4xx.h:8644
#define GPIOE
Definition: stm32f4xx.h:2114
#define FLASH_ACR_LATENCY_5WS
Definition: stm32f4xx.h:4540
#define RCC_CFGR_SW
Definition: stm32f4xx.h:8632
#define PWR
Definition: stm32f4xx.h:2074
static void SetSysClock(void)
Configures the System clock source, PLL Multiplier and Divider factors, AHB/APBx prescalers and Flash...
#define PLL_M
#define PWR_CR_PMODE
Definition: stm32f4xx.h:8397
#define FSMC_Bank1E
Definition: stm32f10x.h:1449
#define PLL_Q
#define RCC_CR_HSERDY
Definition: stm32f4xx.h:8579
#define RCC_CFGR_PPRE1_DIV4
Definition: stm32f4xx.h:8686


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