mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: adjust clocks for H723 and H730
FDCAN clock must be 80MHz, and also align no-crystal clocks with clocks for boards with crystals
This commit is contained in:
parent
aea2863141
commit
0a6057f2b3
|
@ -112,7 +112,7 @@
|
|||
#if STM32_HSECLK == 0U
|
||||
// no crystal, this gives 400MHz system clock
|
||||
#define STM32_HSE_ENABLED FALSE
|
||||
#define STM32_HSI_ENABLED TRUE
|
||||
#define STM32_HSI_ENABLED TRUE // HSI is 64MHz
|
||||
#define STM32_PLL1_DIVM_VALUE 32
|
||||
#define STM32_PLL2_DIVM_VALUE 32
|
||||
#define STM32_PLL3_DIVM_VALUE 32
|
||||
|
@ -125,8 +125,8 @@
|
|||
#define STM32_HSE_ENABLED TRUE
|
||||
#define STM32_HSI_ENABLED FALSE
|
||||
#define STM32_PLL1_DIVM_VALUE 4
|
||||
#define STM32_PLL2_DIVM_VALUE 8
|
||||
#define STM32_PLL3_DIVM_VALUE 8
|
||||
#define STM32_PLL2_DIVM_VALUE 4
|
||||
#define STM32_PLL3_DIVM_VALUE 4
|
||||
#define STM32_PLLSRC STM32_PLLSRC_HSE_CK
|
||||
#define STM32_CKPERSEL STM32_CKPERSEL_HSE_CK
|
||||
|
||||
|
@ -135,8 +135,8 @@
|
|||
#define STM32_HSE_ENABLED TRUE
|
||||
#define STM32_HSI_ENABLED FALSE
|
||||
#define STM32_PLL1_DIVM_VALUE 8
|
||||
#define STM32_PLL2_DIVM_VALUE 16
|
||||
#define STM32_PLL3_DIVM_VALUE 16
|
||||
#define STM32_PLL2_DIVM_VALUE 8
|
||||
#define STM32_PLL3_DIVM_VALUE 8
|
||||
#define STM32_PLLSRC STM32_PLLSRC_HSE_CK
|
||||
#define STM32_CKPERSEL STM32_CKPERSEL_HSE_CK
|
||||
|
||||
|
@ -144,24 +144,7 @@
|
|||
#error "Unsupported HSE clock"
|
||||
#endif
|
||||
|
||||
#if STM32_HSECLK == 0U
|
||||
// no crystal
|
||||
#define STM32_PLL1_DIVN_VALUE 260
|
||||
#define STM32_PLL1_DIVP_VALUE 1
|
||||
#define STM32_PLL1_DIVQ_VALUE 6
|
||||
#define STM32_PLL1_DIVR_VALUE 4
|
||||
|
||||
#define STM32_PLL2_DIVN_VALUE 200
|
||||
#define STM32_PLL2_DIVP_VALUE 3
|
||||
#define STM32_PLL2_DIVQ_VALUE 3
|
||||
#define STM32_PLL2_DIVR_VALUE 2
|
||||
|
||||
#define STM32_PLL3_DIVN_VALUE 96
|
||||
#define STM32_PLL3_DIVP_VALUE 1
|
||||
#define STM32_PLL3_DIVQ_VALUE 2
|
||||
#define STM32_PLL3_DIVR_VALUE 4
|
||||
|
||||
#elif (STM32_HSECLK == 8000000U) || (STM32_HSECLK == 16000000U)
|
||||
#if (STM32_HSECLK == 0U) || (STM32_HSECLK == 8000000U) || (STM32_HSECLK == 16000000U)
|
||||
// common clock tree for multiples of 8MHz crystals
|
||||
#ifdef HAL_CUSTOM_MCU_CLOCKRATE
|
||||
#if HAL_CUSTOM_MCU_CLOCKRATE == 520000000
|
||||
|
@ -185,7 +168,7 @@
|
|||
|
||||
#define STM32_PLL2_DIVN_VALUE 400
|
||||
#define STM32_PLL2_DIVP_VALUE 3
|
||||
#define STM32_PLL2_DIVQ_VALUE 3
|
||||
#define STM32_PLL2_DIVQ_VALUE 10 // 80MHz for FDCAN
|
||||
#define STM32_PLL2_DIVR_VALUE 2
|
||||
|
||||
#define STM32_PLL3_DIVN_VALUE 192
|
||||
|
@ -256,7 +239,7 @@
|
|||
#define STM32_FMCSEL STM32_OCTOSPISEL_HCLK
|
||||
|
||||
#define STM32_SWPSEL STM32_SWPSEL_PCLK1
|
||||
#define STM32_FDCANSEL STM32_FDCANSEL_PLL1_Q_CK
|
||||
#define STM32_FDCANSEL STM32_FDCANSEL_PLL2_Q_CK
|
||||
#define STM32_DFSDM1SEL STM32_DFSDM1SEL_PCLK2
|
||||
#define STM32_SPDIFSEL STM32_SPDIFSEL_PLL1_Q_CK
|
||||
#define STM32_SPI45SEL STM32_SPI45SEL_PCLK2
|
||||
|
|
|
@ -34,13 +34,13 @@ mcu = {
|
|||
],
|
||||
|
||||
'EXPECTED_CLOCK' : 400000000,
|
||||
|
||||
|
||||
'EXPECTED_CLOCKS' : [
|
||||
('STM32_SYS_CK', 400000000),
|
||||
('STM32_QSPICLK', 200000000),
|
||||
('STM32_SDMMC1CLK', 80000000),
|
||||
('STM32_SYS_CK', 400000000),
|
||||
('STM32_OSPICLK', 200000000),
|
||||
('STM32_SDMMC1CLK', 66666666),
|
||||
('STM32_SPI45CLK', 100000000),
|
||||
('STM32_FDCANCLK', 80000000),
|
||||
('STM32_FDCANCLK', 80000000),
|
||||
],
|
||||
|
||||
# this MCU has M7 instructions and hardware double precision
|
||||
|
|
|
@ -69,7 +69,7 @@ mcu = {
|
|||
('STM32_OSPICLK', 200000000),
|
||||
('STM32_SDMMC1CLK', 86666666),
|
||||
('STM32_SPI45CLK', 100000000),
|
||||
('STM32_FDCANCLK', 86666666),
|
||||
('STM32_FDCANCLK', 80000000),
|
||||
],
|
||||
|
||||
# this MCU has M7 instructions and hardware double precision
|
||||
|
|
Loading…
Reference in New Issue