HAL_ChibiOS: added build time check for right system clock

this helps prevent cases where we underclock a chip due to mistake in
headers or hwdef.dat
This commit is contained in:
Andrew Tridgell 2020-05-07 12:13:29 +10:00
parent 69676cd614
commit 61d036acf3
11 changed files with 36 additions and 5 deletions

View File

@ -30,7 +30,9 @@ mcu = {
# flags of 2 means faster memory for CPU intensive work
'RAM_MAP' : [
(0x20000000, 8, 1), # main memory, DMA safe
]
],
'EXPECTED_CLOCK' : 24000000
}
ADC1_map = {

View File

@ -27,7 +27,9 @@ mcu = {
'RAM_MAP' : [
(0x20000000, 20, 1), # main memory, DMA safe
]
],
'EXPECTED_CLOCK' : 72000000
}
ADC1_map = {

View File

@ -21,7 +21,9 @@ mcu = {
'RAM_MAP' : [
(0x20000000, 40, 1), # main memory, DMA safe
(0x10000000, 8, 2), # CCM memory, faster, but not DMA safe
]
],
'EXPECTED_CLOCK' : 72000000
}
AltFunction_map = {

View File

@ -21,7 +21,9 @@ mcu = {
'RAM_MAP' : [
(0x20000000, 128, 1), # main memory, DMA safe
(0x10000000, 64, 2), # CCM memory, faster, but not DMA safe
]
],
'EXPECTED_CLOCK' : 168000000
}
AltFunction_map = {

View File

@ -21,7 +21,9 @@ mcu = {
'RAM_MAP' : [
(0x20000000, 192, 1), # main memory, DMA safe
(0x10000000, 64, 2), # CCM memory, faster, but not DMA safe
]
],
'EXPECTED_CLOCK' : 168000000
}
DMA_Map = {

View File

@ -23,6 +23,8 @@ mcu = {
(0x20000000, 64, 1), # DTCM memory, DMA safe
],
'EXPECTED_CLOCK' : 216000000,
# this board has M7 instructions, but single precision only FPU
# we build as m4 as it makes for a smaller build, and given the 1M
# flash limit we care more about size

View File

@ -40,6 +40,8 @@ mcu = {
(0x20010000, 64, 2), # DTCM, 2nd half, used as fast memory. This lowers memory contention in the EKF code
],
'EXPECTED_CLOCK' : 216000000,
# this MCU has M7 instructions and hardware double precision
'CORTEX' : 'cortex-m7',
'CPU_FLAGS' : '-mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard',

View File

@ -37,6 +37,8 @@ mcu = {
(0x20000000, 128, 1), # DTCM, DMA
],
'EXPECTED_CLOCK' : 216000000,
# this MCU has M7 instructions and hardware double precision
'CORTEX' : 'cortex-m7',
'CPU_FLAGS' : '-mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard',

View File

@ -26,6 +26,8 @@ mcu = {
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
],
'EXPECTED_CLOCK' : 400000000,
# this MCU has M7 instructions and hardware double precision
'CORTEX' : 'cortex-m7',
'CPU_FLAGS' : '-mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard',

View File

@ -727,6 +727,9 @@ def write_mcu_config(f):
env_vars['CPU_FLAGS'] = ["-mcpu=%s" % cortex, "-mfpu=fpv4-sp-d16", "-mfloat-abi=hard"]
build_info['MCU'] = cortex
if get_mcu_config('EXPECTED_CLOCK'):
f.write('#define HAL_EXPECTED_SYSCLOCK %u\n' % get_mcu_config('EXPECTED_CLOCK'))
env_vars['CORTEX'] = cortex
if not args.bootloader:

View File

@ -32,6 +32,16 @@ static_assert(sizeof(systime_t) == 2, "expected 16 bit systime_t");
static_assert(sizeof(systime_t) == 4, "expected 32 bit systime_t");
#endif
#if defined(HAL_EXPECTED_SYSCLOCK)
#ifdef STM32_SYS_CK
static_assert(HAL_EXPECTED_SYSCLOCK == STM32_SYS_CK, "unexpected STM32_SYS_CK value");
#elif defined(STM32_HCLK)
static_assert(HAL_EXPECTED_SYSCLOCK == STM32_HCLK, "unexpected STM32_HCLK value");
#else
#error "unknown system clock"
#endif
#endif
extern const AP_HAL::HAL& hal;
extern "C"
{