Skip to content

Commit

Permalink
HAL_ChibiOS: adjust clocks for H723 and H730
Browse files Browse the repository at this point in the history
FDCAN clock must be 80MHz, and also align no-crystal clocks with
clocks for boards with crystals
  • Loading branch information
tridge committed Jan 27, 2024
1 parent 2340306 commit 0fe2e8d
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 31 deletions.
33 changes: 8 additions & 25 deletions libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_type2_mcuconf.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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

Expand All @@ -135,33 +135,16 @@
#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

#else
#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
Expand All @@ -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
Expand Down Expand Up @@ -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
Expand Down
10 changes: 5 additions & 5 deletions libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H723xx.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,13 +34,13 @@
],

'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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H730xx.py
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@
('STM32_OSPICLK', 200000000),
('STM32_SDMMC1CLK', 86666666),
('STM32_SPI45CLK', 100000000),
('STM32_FDCANCLK', 86666666),
('STM32_FDCANCLK', 80000000),
],

# this MCU has M7 instructions and hardware double precision
Expand Down

0 comments on commit 0fe2e8d

Please sign in to comment.