mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
HAL_ChibiOS: required EXPECTED_CLOCK in all MCU files
this ensures we validate the clock setup at compile time
This commit is contained in:
parent
1224ff48b3
commit
a8b98bfcc4
@ -23,7 +23,9 @@ pincount = {
|
||||
mcu = {
|
||||
'RAM_MAP' : [
|
||||
(0x20000000, 64, 1), # main memory, DMA safe
|
||||
]
|
||||
],
|
||||
|
||||
'EXPECTED_CLOCK' : 72000000
|
||||
}
|
||||
|
||||
ADC1_map = {
|
||||
|
@ -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 = {
|
||||
|
@ -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 = {
|
||||
|
@ -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 = {
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user