mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: support H7 at 200MHz
This commit is contained in:
parent
d87404adfa
commit
98479658d4
|
@ -202,6 +202,9 @@
|
||||||
#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
|
#define STM32_PLL1_DIVQ_VALUE 12
|
||||||
|
#elif HAL_CUSTOM_MCU_CLOCKRATE == 200000000
|
||||||
|
#define STM32_PLL1_DIVN_VALUE 50
|
||||||
|
#define STM32_PLL1_DIVQ_VALUE 5
|
||||||
#else
|
#else
|
||||||
#error "Unable to configure custom clockrate"
|
#error "Unable to configure custom clockrate"
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue