Refactor missing prototypes 2 (#14170)
[betaflight.git] / src / platform / APM32 / startup / system_apm32f4xx.c
blob02a935aa8ef466fd019abf2db4b4dcf8c87ab3b0
1 /**
3 * @file system_apm32f4xx.c
5 * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
7 * @version V1.0.0
9 * @date 2023-07-31
11 * @attention
13 * Copyright (C) 2023 Geehy Semiconductor
15 * You may not use this file except in compliance with the
16 * GEEHY COPYRIGHT NOTICE (GEEHY SOFTWARE PACKAGE LICENSE).
18 * The program is only for reference, which is distributed in the hope
19 * that it will be useful and instructional for customers to develop
20 * their software. Unless required by applicable law or agreed to in
21 * writing, the program is distributed on an "AS IS" BASIS, WITHOUT
22 * ANY WARRANTY OR CONDITIONS OF ANY KIND, either express or implied.
23 * See the GEEHY SOFTWARE PACKAGE LICENSE for the governing permissions
24 * and limitations under the License.
27 /** @addtogroup CMSIS
28 * @{
31 /** @addtogroup apm32f4xx_system
32 * @{
35 /** @addtogroup APM32F4xx_System_Private_Includes
36 * @{
39 #include "apm32f4xx.h"
40 #include "system_apm32f4xx.h"
41 #include "platform.h"
42 #include "drivers/system.h"
43 #include "drivers/persistent.h"
45 #include <string.h>
47 /* Value of the external oscillator in Hz */
48 #if !defined (HSE_VALUE)
49 #define HSE_VALUE ((uint32_t)8000000U)
50 #endif /* HSE_VALUE */
52 /* Value of the internal oscillator in Hz */
53 #if !defined (HSI_VALUE)
54 #define HSI_VALUE ((uint32_t)16000000U)
55 #endif /* HSI_VALUE */
57 /**
58 * @}
61 /** @addtogroup APM32F4xx_System_Private_TypesDefinitions
62 * @{
65 /**
66 * @}
69 /** @addtogroup APM32F4xx_System_Private_Defines
70 * @{
72 /* Uncomment the following line if you need to relocate your vector table in internal SRAM */
73 /* #define VECT_TAB_SRAM */
75 /* Vector table base offset field. This value must be a multiple of 0x200 */
76 #define VECT_TAB_OFFSET 0x00
78 /**
79 * @}
82 /** @addtogroup APM32F4xx_System_Private_Macros
83 * @{
85 #define PLLI2S_TARGET_FREQ_MHZ (27 * 4)
86 #define PLLI2S_R 2
88 /**
89 * @}
92 /** @addtogroup APM32F4xx_System_Private_Variables
93 * @{
95 uint32_t SystemCoreClock = 16000000;
96 const uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
97 const uint8_t APBPrescTable[8] = {0, 0, 0, 0, 1, 2, 3, 4};
99 uint32_t pll_src, pll_input, pll_m, pll_p, pll_n, pll_q;
101 typedef struct pllConfig_s {
102 uint16_t mhz; // target SYSCLK
103 uint16_t n;
104 uint16_t p;
105 uint16_t q;
106 } pllConfig_t;
108 // PLL parameters for PLL input = 1MHz.
109 // For PLL input = 2MHz, divide n by 2; see SystemInitPLLParameters below.
111 static const pllConfig_t overclockLevels[] = {
112 { 168, 336, 2, 7 }, // 168 MHz
113 { 192, 384, 2, 8 }, // 192 MHz
114 { 216, 432, 2, 9 }, // 216 MHz
115 { 240, 480, 2, 10 } // 240 MHz
119 * @}
122 /** @addtogroup APM32F4xx_System_Private_FunctionPrototypes
123 * @{
127 * @}
130 /** @addtogroup APM32F4xx_System_Private_Functions
131 * @{
134 static void SystemInitPLLParameters(void);
135 void DAL_SysClkConfig(void);
136 void DAL_ErrorHandler(void);
139 * @brief Setup the microcontroller system
141 * @param None
143 * @retval None
145 void SystemInit(void)
147 initialiseMemorySections();
149 /* FPU settings */
150 #if (__FPU_PRESENT == 1U) && (__FPU_USED == 1U)
151 SCB->CPACR |= ((3UL << 10U * 2U)|(3UL << 11U * 2U)); /* set CP10 and CP11 Full Access */
152 #endif
154 /* Reset the RCM clock configuration to the default reset state */
155 /* Set HSIEN bit */
156 RCM->CTRL |= (uint32_t)0x00000001;
158 /* Reset CFG register */
159 RCM->CFG = 0x00000000;
161 /* Reset HSEEN, CSSEN and PLL1EN bits */
162 RCM->CTRL &= (uint32_t)0xFEF6FFFF;
164 /* Reset PLL1CFG register */
165 RCM->PLL1CFG = 0x24003010;
167 /* Reset HSEBCFG bit */
168 RCM->CTRL &= (uint32_t)0xFFFBFFFF;
170 /* Disable all interrupts */
171 RCM->INT = 0x00000000;
173 /* Configure the Vector Table location add offset address */
174 extern uint8_t isr_vector_table_flash_base;
175 extern uint8_t isr_vector_table_base;
176 extern uint8_t isr_vector_table_end;
178 if (&isr_vector_table_base != &isr_vector_table_flash_base) {
179 memcpy(&isr_vector_table_base, &isr_vector_table_flash_base, (size_t) (&isr_vector_table_end - &isr_vector_table_base));
182 SCB->VTOR = (uint32_t)&isr_vector_table_base;
186 * @brief Update SystemCoreClock variable according to clock register values
187 * The SystemCoreClock variable contains the core clock (HCLK)
189 * @param None
190 * @retval None
192 void SystemCoreClockUpdate(void)
194 uint32_t sysClock = 0, pllvco = 0, pllc, pllClock, pllb;
196 uint32_t hse_value = persistentObjectRead(PERSISTENT_OBJECT_HSE_VALUE);
198 /* Get SYSCLK source */
199 sysClock = RCM->CFG & RCM_CFG_SCLKSWSTS;
201 switch (sysClock)
203 case 0x00: /* HSI used as system clock source */
204 SystemCoreClock = HSI_VALUE;
205 break;
207 case 0x04: /* HSE used as system clock source */
208 SystemCoreClock = hse_value;
209 break;
211 case 0x08: /* PLL used as system clock source */
212 pllClock = (RCM->PLL1CFG & RCM_PLL1CFG_PLL1CLKS) >> 22;
213 pllb = RCM->PLL1CFG & RCM_PLL1CFG_PLLB;
215 if (pllClock != 0)
217 /* HSE used as PLL clock source */
218 pllvco = (hse_value / pllb) * ((RCM->PLL1CFG & RCM_PLL1CFG_PLL1A) >> 6);
220 else
222 /* HSI used as PLL clock source */
223 pllvco = (HSI_VALUE / pllb) * ((RCM->PLL1CFG & RCM_PLL1CFG_PLL1A) >> 6);
226 pllc = (((RCM->PLL1CFG & RCM_PLL1CFG_PLL1C) >> 16) + 1 ) * 2;
227 SystemCoreClock = pllvco / pllc;
228 break;
230 default:
231 SystemCoreClock = HSI_VALUE;
232 break;
235 /* Compute HCLK frequency --------------------------------------------------*/
236 /* Get HCLK prescaler */
237 sysClock = AHBPrescTable[((RCM->CFG & RCM_CFG_AHBPSC) >> 4)];
238 /* HCLK frequency */
239 SystemCoreClock >>= sysClock;
243 * @brief System clock configuration
245 * @param None
247 * @retval None
249 void DAL_SysClkConfig(void)
251 RCM_ClkInitTypeDef RCM_ClkInitStruct = {0U};
252 RCM_OscInitTypeDef RCM_OscInitStruct = {0U};
253 RCM_PeriphCLKInitTypeDef PeriphClk_InitStruct = {0U};
255 uint32_t hse_value = persistentObjectRead(PERSISTENT_OBJECT_HSE_VALUE);
256 uint32_t hse_mhz = hse_value / 1000000;
258 if (hse_value == 0) {
259 pll_src = RCM_PLLSOURCE_HSI;
261 // HSI is fixed at 16MHz
262 pll_m = 8;
263 pll_input = 2;
265 else {
266 // HSE frequency is given
267 pll_src = RCM_PLLSOURCE_HSE;
269 pll_m = hse_mhz / 2;
270 if (pll_m * 2 != hse_mhz) {
271 pll_m = hse_mhz;
273 pll_input = hse_mhz / pll_m;
276 SystemInitPLLParameters();
278 /* Enable PMU clock */
279 __DAL_RCM_PMU_CLK_ENABLE();
281 /* Configure the voltage scaling value */
282 __DAL_PMU_VOLTAGESCALING_CONFIG(PMU_REGULATOR_VOLTAGE_SCALE1);
284 /* Enable HSE Oscillator and activate PLL with HSE as source */
285 RCM_OscInitStruct.OscillatorType = RCM_OSCILLATORTYPE_HSI | RCM_OSCILLATORTYPE_HSE | RCM_OSCILLATORTYPE_LSI;
286 RCM_OscInitStruct.HSEState = RCM_HSE_ON;
287 RCM_OscInitStruct.HSIState = RCM_HSI_ON;
288 RCM_OscInitStruct.LSIState = RCM_LSI_ON;
289 RCM_OscInitStruct.PLL.PLLState = RCM_PLL_ON;
290 RCM_OscInitStruct.PLL.PLLSource = pll_src;
291 RCM_OscInitStruct.PLL.PLLB = pll_m;
292 RCM_OscInitStruct.PLL.PLL1A = pll_n;
293 RCM_OscInitStruct.PLL.PLL1C = pll_p;
294 RCM_OscInitStruct.PLL.PLLD = pll_q;
295 RCM_OscInitStruct.HSICalibrationValue = 0x10;
296 if(DAL_RCM_OscConfig(&RCM_OscInitStruct) != DAL_OK)
298 DAL_ErrorHandler();
301 /* Configure clock */
302 RCM_ClkInitStruct.ClockType = (RCM_CLOCKTYPE_SYSCLK | RCM_CLOCKTYPE_HCLK | RCM_CLOCKTYPE_PCLK1 | RCM_CLOCKTYPE_PCLK2);
303 RCM_ClkInitStruct.SYSCLKSource = RCM_SYSCLKSOURCE_PLLCLK;
304 RCM_ClkInitStruct.AHBCLKDivider = RCM_SYSCLK_DIV1;
305 RCM_ClkInitStruct.APB1CLKDivider = RCM_HCLK_DIV4;
306 RCM_ClkInitStruct.APB2CLKDivider = RCM_HCLK_DIV2;
307 if(DAL_RCM_ClockConfig(&RCM_ClkInitStruct, FLASH_LATENCY_5) != DAL_OK)
309 DAL_ErrorHandler();
312 /* I2S clock */
313 // Configure PLLI2S for 27MHz operation
314 // Use pll_input (1 or 2) to derive multiplier N for
315 // 108MHz (27 * 4) PLLI2SCLK with R divider fixed at 2.
316 // 108MHz will further be prescaled by 4 by mcoInit.
318 uint32_t plli2s_n = (PLLI2S_TARGET_FREQ_MHZ * PLLI2S_R) / pll_input;
320 PeriphClk_InitStruct.PeriphClockSelection = RCM_PERIPHCLK_I2S;
321 PeriphClk_InitStruct.PLLI2S.PLL2A = plli2s_n;
322 PeriphClk_InitStruct.PLLI2S.PLL2C = PLLI2S_R;
323 if (DAL_RCMEx_PeriphCLKConfig(&PeriphClk_InitStruct) != DAL_OK)
325 DAL_ErrorHandler();
330 * @brief Error handler
332 * @param None
334 * @retval None
336 void DAL_ErrorHandler(void)
338 /* When the function is needed, this function
339 could be implemented in the user file
341 while(1)
346 LOCAL_UNUSED_FUNCTION static void AssertFailedHandler(uint8_t *file, uint32_t line)
348 /* When the function is needed, this function
349 could be implemented in the user file
351 UNUSED(file);
352 UNUSED(line);
353 while(1)
359 * @brief Get the SYSCLK source
361 * @param None
363 * @retval The SYSCLK source
364 * - 0x00: HSI used as system clock source
365 * - 0x01: HSE used as system clock source
366 * - 0x02: PLL used as system clock source
368 int SystemSYSCLKSource(void)
370 return (int)((RCM->CFG & RCM_CFG_SCLKSWSTS) >> 2);
374 * @brief Get the PLL source
376 * @param None
378 * @retval The PLL source
379 * - 0x00: HSI used as PLL clock source
380 * - 0x01: HSE used as PLL clock source
382 int SystemPLLSource(void)
384 return (int)((RCM->PLL1CFG & RCM_PLL1CFG_PLL1CLKS) >> 22);
388 * @brief Reboot the system if necessary after changing the overclock level
390 * @param overclockLevel
392 * @retval None
394 void OverclockRebootIfNecessary(uint32_t overclockLevel)
396 if (overclockLevel >= ARRAYLEN(overclockLevels)) {
397 return;
400 const pllConfig_t * const pll = overclockLevels + overclockLevel;
402 // Reboot to adjust overclock frequency
403 if (SystemCoreClock != pll->mhz * 1000000U) {
404 persistentObjectWrite(PERSISTENT_OBJECT_OVERCLOCK_LEVEL, overclockLevel);
405 __disable_irq();
406 NVIC_SystemReset();
411 * @brief Set the HSE value
413 * @param frequency
415 * @retval None
417 void systemClockSetHSEValue(uint32_t frequency)
419 uint32_t hse_value = persistentObjectRead(PERSISTENT_OBJECT_HSE_VALUE);
421 if (hse_value != frequency) {
422 persistentObjectWrite(PERSISTENT_OBJECT_HSE_VALUE, frequency);
423 __disable_irq();
424 NVIC_SystemReset();
429 * @brief Initialize the PLL parameters
431 * @param None
433 * @retval None
436 static void SystemInitPLLParameters(void)
438 /* PLL setting for overclocking */
440 uint32_t currentOverclockLevel = persistentObjectRead(PERSISTENT_OBJECT_OVERCLOCK_LEVEL);
442 if (currentOverclockLevel >= ARRAYLEN(overclockLevels)) {
443 return;
446 const pllConfig_t * const pll = overclockLevels + currentOverclockLevel;
448 pll_n = pll->n / pll_input;
449 pll_p = pll->p;
450 pll_q = pll->q;
454 * @}
458 * @}
462 * @}