[FLYWOOF411] add board documentation
[inav/snaewe.git] / src / main / target / system_stm32f7xx.c
blob034c14a2db35cf0d85ae18afbbbc0fcd8fb4f414
1 /**
2 ******************************************************************************
3 * @file system_stm32f7xx.c
4 * @author MCD Application Team
5 * @version V1.0.0
6 * @date 22-April-2016
7 * @brief CMSIS Cortex-M7 Device Peripheral Access Layer System Source File.
9 * This file provides two functions and one global variable to be called from
10 * user application:
11 * - SystemInit(): This function is called at startup just after reset and
12 * before branch to main program. This call is made inside
13 * the "startup_stm32f7xx.s" file.
15 * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
16 * by the user application to setup the SysTick
17 * timer or configure other parameters.
19 * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
20 * be called whenever the core clock is changed
21 * during program execution.
24 ******************************************************************************
25 * @attention
27 * <h2><center>&copy; COPYRIGHT 2016 STMicroelectronics</center></h2>
29 * Redistribution and use in source and binary forms, with or without modification,
30 * are permitted provided that the following conditions are met:
31 * 1. Redistributions of source code must retain the above copyright notice,
32 * this list of conditions and the following disclaimer.
33 * 2. Redistributions in binary form must reproduce the above copyright notice,
34 * this list of conditions and the following disclaimer in the documentation
35 * and/or other materials provided with the distribution.
36 * 3. Neither the name of STMicroelectronics nor the names of its contributors
37 * may be used to endorse or promote products derived from this software
38 * without specific prior written permission.
40 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
41 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
42 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
43 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
44 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
45 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
46 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
47 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
48 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
49 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
51 ******************************************************************************
54 /** @addtogroup CMSIS
55 * @{
58 /** @addtogroup stm32f7xx_system
59 * @{
62 /** @addtogroup STM32F7xx_System_Private_Includes
63 * @{
66 #include <string.h>
67 #include "stm32f7xx.h"
69 #if !defined (HSE_VALUE)
70 #define HSE_VALUE ((uint32_t)8000000) /*!< Default value of the External oscillator in Hz */
71 #endif /* HSE_VALUE */
73 #if !defined (HSI_VALUE)
74 #define HSI_VALUE ((uint32_t)16000000) /*!< Value of the Internal oscillator in Hz*/
75 #endif /* HSI_VALUE */
77 #if !defined(MHZ_VALUE)
78 #define MHZ_VALUE 216
79 #endif
81 #if MHZ_VALUE == 216
82 #define PLL_N 432
83 #define PLL_Q 9
84 #elif MHZ_VALUE == 168
85 #define PLL_N 336
86 #define PLL_Q 7
87 #else
88 #error "Unsupported MHZ_VALUE!"
89 #endif
91 #define PLL_M 8
92 #define PLL_P RCC_PLLP_DIV2 /* 2 */
94 #define PLL_SAIN 384
95 #define PLL_SAIQ 7
96 #define PLL_SAIP RCC_PLLSAIP_DIV8
98 /**
99 * @}
102 /** @addtogroup STM32F7xx_System_Private_TypesDefinitions
103 * @{
107 * @}
110 /** @addtogroup STM32F7xx_System_Private_Defines
111 * @{
114 /************************* Miscellaneous Configuration ************************/
116 /*!< Uncomment the following line if you need to relocate your vector Table in
117 Internal SRAM. */
118 /* #define VECT_TAB_SRAM */
119 #define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field.
120 This value must be a multiple of 0x200. */
121 /******************************************************************************/
124 * @}
127 /** @addtogroup STM32F7xx_System_Private_Macros
128 * @{
132 * @}
135 /** @addtogroup STM32F7xx_System_Private_Variables
136 * @{
139 /* This variable is updated in three ways:
140 1) by calling CMSIS function SystemCoreClockUpdate()
141 2) by calling HAL API function HAL_RCC_GetHCLKFreq()
142 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
143 Note: If you use this function to configure the system clock; then there
144 is no need to call the 2 first functions listed above, since SystemCoreClock
145 variable is updated automatically.
147 uint32_t SystemCoreClock = (PLL_N / PLL_P) * 1000000;
148 const uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
149 const uint8_t APBPrescTable[8] = {0, 0, 0, 0, 1, 2, 3, 4};
152 * @}
155 /** @addtogroup STM32F7xx_System_Private_FunctionPrototypes
156 * @{
159 /// TODO: F7 check if this is the best configuration for the clocks.
160 // current settings are just a copy from one of the example projects
161 void SystemClock_Config(void)
163 RCC_ClkInitTypeDef RCC_ClkInitStruct;
164 RCC_OscInitTypeDef RCC_OscInitStruct;
165 RCC_PeriphCLKInitTypeDef PeriphClkInitStruct;
166 HAL_StatusTypeDef ret;
168 __HAL_RCC_PWR_CLK_ENABLE();
170 __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
172 /* Enable HSE Oscillator and activate PLL with HSE as source */
173 RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
174 RCC_OscInitStruct.HSEState = RCC_HSE_ON;
175 RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
176 RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
177 RCC_OscInitStruct.PLL.PLLM = PLL_M;
178 RCC_OscInitStruct.PLL.PLLN = PLL_N;
179 RCC_OscInitStruct.PLL.PLLP = PLL_P;
180 RCC_OscInitStruct.PLL.PLLQ = PLL_Q;
182 ret = HAL_RCC_OscConfig(&RCC_OscInitStruct);
183 if (ret != HAL_OK)
185 while (1) { ; }
188 /* Activate the OverDrive to reach the 216 MHz Frequency */
189 ret = HAL_PWREx_EnableOverDrive();
190 if (ret != HAL_OK)
192 while (1) { ; }
194 /* Select PLLSAI output as USB clock source */
195 PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_CLK48;
196 PeriphClkInitStruct.Clk48ClockSelection = RCC_CLK48SOURCE_PLLSAIP;
197 PeriphClkInitStruct.PLLSAI.PLLSAIN = PLL_SAIN;
198 PeriphClkInitStruct.PLLSAI.PLLSAIQ = PLL_SAIQ;
199 PeriphClkInitStruct.PLLSAI.PLLSAIP = PLL_SAIP;
200 if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
202 while (1) {};
205 /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */
206 RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2);
207 RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
208 RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
209 RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4;
210 RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;
212 ret = HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7);
213 if (ret != HAL_OK)
215 while (1) { ; }
218 PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USART1|RCC_PERIPHCLK_USART2
219 |RCC_PERIPHCLK_USART3|RCC_PERIPHCLK_USART6
220 |RCC_PERIPHCLK_UART4|RCC_PERIPHCLK_UART5
221 |RCC_PERIPHCLK_UART7|RCC_PERIPHCLK_UART8
222 |RCC_PERIPHCLK_I2C1|RCC_PERIPHCLK_I2C3
223 |RCC_PERIPHCLK_I2C2|RCC_PERIPHCLK_I2C4;
224 PeriphClkInitStruct.Usart1ClockSelection = RCC_USART1CLKSOURCE_PCLK2;
225 PeriphClkInitStruct.Usart2ClockSelection = RCC_USART2CLKSOURCE_PCLK1;
226 PeriphClkInitStruct.Usart3ClockSelection = RCC_USART3CLKSOURCE_PCLK1;
227 PeriphClkInitStruct.Uart4ClockSelection = RCC_UART4CLKSOURCE_PCLK1;
228 PeriphClkInitStruct.Uart5ClockSelection = RCC_UART5CLKSOURCE_PCLK1;
229 PeriphClkInitStruct.Usart6ClockSelection = RCC_USART6CLKSOURCE_PCLK2;
230 PeriphClkInitStruct.Uart7ClockSelection = RCC_UART7CLKSOURCE_PCLK1;
231 PeriphClkInitStruct.Uart8ClockSelection = RCC_UART8CLKSOURCE_PCLK1;
232 PeriphClkInitStruct.I2c1ClockSelection = RCC_I2C1CLKSOURCE_PCLK1;
233 PeriphClkInitStruct.I2c2ClockSelection = RCC_I2C2CLKSOURCE_PCLK1;
234 PeriphClkInitStruct.I2c3ClockSelection = RCC_I2C3CLKSOURCE_PCLK1;
235 PeriphClkInitStruct.I2c4ClockSelection = RCC_I2C4CLKSOURCE_PCLK1;
236 ret = HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct);
237 if (ret != HAL_OK)
239 while (1) { ; }
242 // Activating the timerprescalers while the APBx prescalers are 1/2/4 will connect the TIMxCLK to HCLK which has been configured to 216MHz
243 __HAL_RCC_TIMCLKPRESCALER(RCC_TIMPRES_ACTIVATED);
245 SystemCoreClockUpdate();
249 * @}
252 /** @addtogroup STM32F7xx_System_Private_Functions
253 * @{
256 void CopyFastCode(void)
258 /* Load functions into ITCM RAM */
259 extern uint8_t tcm_code_start;
260 extern uint8_t tcm_code_end;
261 extern uint8_t tcm_code;
262 memcpy(&tcm_code_start, &tcm_code, (size_t) (&tcm_code_end - &tcm_code_start));
266 * @brief Setup the microcontroller system
267 * Initialize the Embedded Flash Interface, the PLL and update the
268 * SystemFrequency variable.
269 * @param None
270 * @retval None
272 void SystemInit(void)
274 /* FPU settings ------------------------------------------------------------*/
275 #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
276 SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
277 #endif
278 /* Reset the RCC clock configuration to the default reset state ------------*/
279 /* Set HSION bit */
280 RCC->CR |= (uint32_t)0x00000001;
282 /* Reset CFGR register */
283 RCC->CFGR = 0x00000000;
285 /* Reset HSEON, CSSON and PLLON bits */
286 RCC->CR &= (uint32_t)0xFEF6FFFF;
288 /* Reset PLLCFGR register */
289 RCC->PLLCFGR = 0x24003010;
291 /* Reset HSEBYP bit */
292 RCC->CR &= (uint32_t)0xFFFBFFFF;
294 /* Disable all interrupts */
295 RCC->CIR = 0x00000000;
297 /* Configure the Vector Table location add offset address ------------------*/
298 #ifdef VECT_TAB_SRAM
299 SCB->VTOR = RAMDTCM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */
300 #else
301 SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
302 #endif
304 /* Enable I-Cache */
305 SCB_EnableICache();
307 /* Enable D-Cache */
308 //SCB_EnableDCache();
310 /* Configure the system clock to 216 MHz */
311 SystemClock_Config();
313 if (SystemCoreClock != MHZ_VALUE * 1000000)
315 while (1)
317 // There is a mismatch between the configured clock and the expected clock in portable.h
325 * @brief Update SystemCoreClock variable according to Clock Register Values.
326 * The SystemCoreClock variable contains the core clock (HCLK), it can
327 * be used by the user application to setup the SysTick timer or configure
328 * other parameters.
330 * @note Each time the core clock (HCLK) changes, this function must be called
331 * to update SystemCoreClock variable value. Otherwise, any configuration
332 * based on this variable will be incorrect.
334 * @note - The system frequency computed by this function is not the real
335 * frequency in the chip. It is calculated based on the predefined
336 * constant and the selected clock source:
338 * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
340 * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
342 * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
343 * or HSI_VALUE(*) multiplied/divided by the PLL factors.
345 * (*) HSI_VALUE is a constant defined in stm32f7xx_hal_conf.h file (default value
346 * 16 MHz) but the real value may vary depending on the variations
347 * in voltage and temperature.
349 * (**) HSE_VALUE is a constant defined in stm32f7xx_hal_conf.h file (default value
350 * 25 MHz), user has to ensure that HSE_VALUE is same as the real
351 * frequency of the crystal used. Otherwise, this function may
352 * have wrong result.
354 * - The result of this function could be not correct when using fractional
355 * value for HSE crystal.
357 * @param None
358 * @retval None
360 void SystemCoreClockUpdate(void)
362 uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2;
364 /* Get SYSCLK source -------------------------------------------------------*/
365 tmp = RCC->CFGR & RCC_CFGR_SWS;
367 switch (tmp)
369 case 0x00: /* HSI used as system clock source */
370 SystemCoreClock = HSI_VALUE;
371 break;
372 case 0x04: /* HSE used as system clock source */
373 SystemCoreClock = HSE_VALUE;
374 break;
375 case 0x08: /* PLL used as system clock source */
377 /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
378 SYSCLK = PLL_VCO / PLL_P
380 pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
381 pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
383 if (pllsource != 0)
385 /* HSE used as PLL clock source */
386 pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
388 else
390 /* HSI used as PLL clock source */
391 pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
394 pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2;
395 SystemCoreClock = pllvco/pllp;
396 break;
397 default:
398 SystemCoreClock = HSI_VALUE;
399 break;
401 /* Compute HCLK frequency --------------------------------------------------*/
402 /* Get HCLK prescaler */
403 tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
404 /* HCLK frequency */
405 SystemCoreClock >>= tmp;
409 * @}
413 * @}
417 * @}
419 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/