HAL_ChibiOS: fixed 24mhz crystal on H7 with 480MHz clock

need to adjust the PLLQ as well as the PLLN
This commit is contained in:
Andrew Tridgell 2023-06-20 12:51:20 +10:00
parent 1055c5f1c6
commit ddb991d9b5
1 changed files with 2 additions and 1 deletions

View File

@ -199,14 +199,15 @@
#ifdef HAL_CUSTOM_MCU_CLOCKRATE
#if HAL_CUSTOM_MCU_CLOCKRATE == 480000000
#define STM32_PLL1_DIVN_VALUE 120
#define STM32_PLL1_DIVQ_VALUE 12
#else
#error "Unable to configure custom clockrate"
#endif
#else
#define STM32_PLL1_DIVN_VALUE 100
#define STM32_PLL1_DIVQ_VALUE 10
#endif
#define STM32_PLL1_DIVP_VALUE 2
#define STM32_PLL1_DIVQ_VALUE 10
#define STM32_PLL1_DIVR_VALUE 2
#define STM32_PLL2_DIVN_VALUE 50