Browse Source

HAL_ChibiOS: required EXPECTED_CLOCK in all MCU files

this ensures we validate the clock setup at compile time
gps-1.3.1
Andrew Tridgell 3 years ago
parent
commit
a8b98bfcc4
  1. 4
      libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F105xC.py
  2. 4
      libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F407xx.py
  3. 4
      libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F412Rx.py
  4. 4
      libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F469xx.py
  5. 2
      libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py

4
libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F105xC.py

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

4
libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F407xx.py

@ -18,7 +18,9 @@ mcu = { @@ -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 = {

4
libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F412Rx.py

@ -17,7 +17,9 @@ mcu = { @@ -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 = {

4
libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F469xx.py

@ -31,7 +31,9 @@ mcu = { @@ -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 = {

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

@ -1006,7 +1006,7 @@ def write_mcu_config(f): @@ -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…
Cancel
Save