mirror of https://github.com/ArduPilot/ardupilot
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:
parent
1055c5f1c6
commit
ddb991d9b5
|
@ -199,14 +199,15 @@
|
||||||
#ifdef HAL_CUSTOM_MCU_CLOCKRATE
|
#ifdef HAL_CUSTOM_MCU_CLOCKRATE
|
||||||
#if HAL_CUSTOM_MCU_CLOCKRATE == 480000000
|
#if HAL_CUSTOM_MCU_CLOCKRATE == 480000000
|
||||||
#define STM32_PLL1_DIVN_VALUE 120
|
#define STM32_PLL1_DIVN_VALUE 120
|
||||||
|
#define STM32_PLL1_DIVQ_VALUE 12
|
||||||
#else
|
#else
|
||||||
#error "Unable to configure custom clockrate"
|
#error "Unable to configure custom clockrate"
|
||||||
#endif
|
#endif
|
||||||
#else
|
#else
|
||||||
#define STM32_PLL1_DIVN_VALUE 100
|
#define STM32_PLL1_DIVN_VALUE 100
|
||||||
|
#define STM32_PLL1_DIVQ_VALUE 10
|
||||||
#endif
|
#endif
|
||||||
#define STM32_PLL1_DIVP_VALUE 2
|
#define STM32_PLL1_DIVP_VALUE 2
|
||||||
#define STM32_PLL1_DIVQ_VALUE 10
|
|
||||||
#define STM32_PLL1_DIVR_VALUE 2
|
#define STM32_PLL1_DIVR_VALUE 2
|
||||||
|
|
||||||
#define STM32_PLL2_DIVN_VALUE 50
|
#define STM32_PLL2_DIVN_VALUE 50
|
||||||
|
|
Loading…
Reference in New Issue