From a8b98bfcc42a2178c7d89996aa26d2fb2de0a3e8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 26 Jan 2022 11:03:19 +1100 Subject: [PATCH] HAL_ChibiOS: required EXPECTED_CLOCK in all MCU files this ensures we validate the clock setup at compile time --- libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F105xC.py | 4 +++- libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F407xx.py | 4 +++- libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F412Rx.py | 4 +++- libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F469xx.py | 4 +++- libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py | 2 +- 5 files changed, 13 insertions(+), 5 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F105xC.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F105xC.py index 3e5c53fb7e..669fd2a1a4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F105xC.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F105xC.py @@ -23,7 +23,9 @@ pincount = { mcu = { 'RAM_MAP' : [ (0x20000000, 64, 1), # main memory, DMA safe - ] + ], + + 'EXPECTED_CLOCK' : 72000000 } ADC1_map = { diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F407xx.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F407xx.py index 9f8938e3b6..3bfea70ee3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F407xx.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F407xx.py @@ -18,7 +18,9 @@ mcu = { 'RAM_MAP' : [ (0x20000000, 128, 1), # main memory, DMA safe (0x10000000, 64, 2), # CCM memory, faster, but not DMA safe - ] + ], + + 'EXPECTED_CLOCK' : 168000000 } DMA_Map = { diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F412Rx.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F412Rx.py index aeea41b6c2..0d8597f2ec 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F412Rx.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F412Rx.py @@ -17,7 +17,9 @@ mcu = { # flags of 2 means faster memory for CPU intensive work 'RAM_MAP' : [ (0x20000000, 256, 1), # main memory, DMA safe - ] + ], + + 'EXPECTED_CLOCK' : 100000000, } DMA_Map = { diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F469xx.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F469xx.py index 9b2316093f..b9cde287a1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F469xx.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F469xx.py @@ -31,7 +31,9 @@ mcu = { 'RAM_MAP' : [ (0x20000000, 320, 1), # main memory, DMA safe (0x10000000, 64, 1), # CCM memory, faster, not DMA safe - ] + ], + + 'EXPECTED_CLOCK' : 180000000 } DMA_Map = { diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index d5e38eb316..c1061a470a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -1006,7 +1006,7 @@ def write_mcu_config(f): #endif ''') - if get_mcu_config('EXPECTED_CLOCK'): + if get_mcu_config('EXPECTED_CLOCK', required=True): f.write('#define HAL_EXPECTED_SYSCLOCK %u\n' % get_mcu_config('EXPECTED_CLOCK')) env_vars['CORTEX'] = cortex