Browse Source

AP_HAL_ChibiOS: allow H7 480Mhz clock speed to be configured in hwdef via MCU_CLOCKRATE_MHZ

apm_2208
Andy Piper 3 years ago committed by Andrew Tridgell
parent
commit
ceef68e07b
  1. 2
      libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef.dat
  2. 17
      libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h
  3. 2
      libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H750xx.py
  4. 6
      libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py

2
libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef.dat

@ -11,6 +11,8 @@ APJ_BOARD_ID 1060 @@ -11,6 +11,8 @@ APJ_BOARD_ID 1060
# crystal frequency, setup to use external oscillator
OSCILLATOR_HZ 8000000
MCU_CLOCKRATE_MHZ 480
env OPTIMIZE -O2
STM32_ST_USE_TIMER 2

17
libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h

@ -19,7 +19,7 @@ @@ -19,7 +19,7 @@
#pragma once
// we want to cope with both revision XY chips and newer chips
#ifndef STM32H750xx
#if !defined(HAL_CUSTOM_MCU_CLOCKRATE) || HAL_CUSTOM_MCU_CLOCKRATE <= 400000000
#define STM32_ENFORCE_H7_REV_XY
#endif
@ -161,9 +161,13 @@ @@ -161,9 +161,13 @@
#elif (STM32_HSECLK == 8000000U) || (STM32_HSECLK == 16000000U)
// common clock tree for multiples of 8MHz crystals
#ifdef STM32H750xx
#ifdef HAL_CUSTOM_MCU_CLOCKRATE
#if HAL_CUSTOM_MCU_CLOCKRATE == 480000000
#define STM32_PLL1_DIVN_VALUE 120
#else
#error "Unable to configure custom clockrate"
#endif
#else
#define STM32_PLL1_DIVN_VALUE 100
#endif
#define STM32_PLL1_DIVP_VALUE 2
@ -181,9 +185,13 @@ @@ -181,9 +185,13 @@
#define STM32_PLL3_DIVR_VALUE 9
#elif STM32_HSECLK == 24000000U
#ifdef STM32H750xx
#ifdef HAL_CUSTOM_MCU_CLOCKRATE
#if HAL_CUSTOM_MCU_CLOCKRATE == 480000000
#define STM32_PLL1_DIVN_VALUE 120
#else
#error "Unable to configure custom clockrate"
#endif
#else
#define STM32_PLL1_DIVN_VALUE 100
#endif
#define STM32_PLL1_DIVP_VALUE 2
@ -201,6 +209,9 @@ @@ -201,6 +209,9 @@
#define STM32_PLL3_DIVR_VALUE 9
#elif STM32_HSECLK == 25000000U
#ifdef HAL_CUSTOM_MCU_CLOCKRATE
#error "Unable to configure custom clockrate"
#endif
#define STM32_PLL1_DIVN_VALUE 64
#define STM32_PLL1_DIVP_VALUE 2
#define STM32_PLL1_DIVQ_VALUE 10

2
libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H750xx.py

@ -61,7 +61,7 @@ mcu = { @@ -61,7 +61,7 @@ mcu = {
(0x38000000, 64, 1), # SRAM4.
],
'EXPECTED_CLOCK' : 480000000,
'EXPECTED_CLOCK' : 400000000,
# this MCU has M7 instructions and hardware double precision
'CORTEX' : 'cortex-m7',

6
libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py

@ -1037,7 +1037,11 @@ def write_mcu_config(f): @@ -1037,7 +1037,11 @@ def write_mcu_config(f):
#endif
''')
if get_mcu_config('EXPECTED_CLOCK', required=True):
if get_config('MCU_CLOCKRATE_MHZ', required=False):
clockrate = int(get_config('MCU_CLOCKRATE_MHZ'))
f.write('#define HAL_CUSTOM_MCU_CLOCKRATE %u\n' % (clockrate * 1000000))
f.write('#define HAL_EXPECTED_SYSCLOCK %u\n' % (clockrate * 1000000))
elif get_mcu_config('EXPECTED_CLOCK', required=True):
f.write('#define HAL_EXPECTED_SYSCLOCK %u\n' % get_mcu_config('EXPECTED_CLOCK'))
env_vars['CORTEX'] = cortex

Loading…
Cancel
Save