mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: check for common hwdef.dat errors
catches missing GPIO type, mismatched timers and UARTs or bad pin types
This commit is contained in:
parent
f0a284c1e7
commit
4dbff85de7
|
@ -2227,6 +2227,43 @@ def romfs_add_dir(subdirs):
|
|||
relpath = os.path.normpath(os.path.join(dirname, os.path.relpath(root, romfs_dir), f))
|
||||
romfs[relpath] = fullpath
|
||||
|
||||
def valid_type(ptype, label):
|
||||
'''check type of a pin line is valid'''
|
||||
patterns = [ 'INPUT', 'OUTPUT', 'TIM\d+', 'USART\d+', 'UART\d+', 'ADC\d+',
|
||||
'SPI\d+', 'OTG\d+', 'SWD', 'CAN\d?', 'I2C\d+', 'CS',
|
||||
'SDMMC\d+', 'SDIO', 'QUADSPI\d' ]
|
||||
matches = False
|
||||
for p in patterns:
|
||||
if re.match(p, ptype):
|
||||
matches = True
|
||||
break
|
||||
if not matches:
|
||||
return False
|
||||
# special checks for common errors
|
||||
m1 = re.match('TIM(\d+)', ptype)
|
||||
m2 = re.match('TIM(\d+)_CH\d+', label)
|
||||
if (m1 and not m2) or (m2 and not m1) or (m1 and m1.group(1) != m2.group(1)):
|
||||
'''timer numbers need to match'''
|
||||
return False
|
||||
m1 = re.match('CAN(\d+)', ptype)
|
||||
m2 = re.match('CAN(\d+)_(RX|TX)', label)
|
||||
if (m1 and not m2) or (m2 and not m1) or (m1 and m1.group(1) != m2.group(1)):
|
||||
'''CAN numbers need to match'''
|
||||
return False
|
||||
if ptype == 'OUTPUT' and re.match('US?ART\d+_(TXINV|RXINV)', label):
|
||||
return True
|
||||
m1 = re.match('USART(\d+)', ptype)
|
||||
m2 = re.match('USART(\d+)_(RX|TX|CTS|RTS)', label)
|
||||
if (m1 and not m2) or (m2 and not m1) or (m1 and m1.group(1) != m2.group(1)):
|
||||
'''usart numbers need to match'''
|
||||
return False
|
||||
m1 = re.match('UART(\d+)', ptype)
|
||||
m2 = re.match('UART(\d+)_(RX|TX|CTS|RTS)', label)
|
||||
if (m1 and not m2) or (m2 and not m1) or (m1 and m1.group(1) != m2.group(1)):
|
||||
'''uart numbers need to match'''
|
||||
return False
|
||||
return True
|
||||
|
||||
def process_line(line):
|
||||
'''process one line of pin definition file'''
|
||||
global allpins, imu_list, compass_list, baro_list, airspeed_list
|
||||
|
@ -2249,6 +2286,9 @@ def process_line(line):
|
|||
error("Bad pin line: %s" % a)
|
||||
return
|
||||
|
||||
if not valid_type(type, label):
|
||||
error("bad type on line: %s" % a)
|
||||
|
||||
p = generic_pin(port, pin, label, type, extra)
|
||||
af = get_alt_function(mcu_type, a[0], label)
|
||||
if af is not None:
|
||||
|
|
Loading…
Reference in New Issue