this ensures we validate the clock setup at compile time
@ -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 = {
(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
(0x20000000, 256, 1), # main memory, DMA safe
'EXPECTED_CLOCK' : 100000000,
@ -31,7 +31,9 @@ mcu = {
(0x20000000, 320, 1), # main memory, DMA safe
(0x10000000, 64, 1), # CCM memory, faster, not DMA safe
'EXPECTED_CLOCK' : 180000000
@ -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