AP_HAL_ChibiOS: hwdef.py: find alt function for UART RTS and add to init struct

This commit is contained in:
Iampete1 2024-04-30 17:42:33 +01:00 committed by Andrew Tridgell
parent 0959930289
commit e6a0abdfce
1 changed files with 28 additions and 4 deletions

View File

@ -1885,7 +1885,8 @@ INCLUDE common.ld
devlist.append('HAL_%s_CONFIG' % dev)
tx_line = self.make_line(dev + '_TX')
rx_line = self.make_line(dev + '_RX')
rts_line = self.make_line(dev + '_RTS')
rts_line_name = dev + '_RTS'
rts_line = self.make_line(rts_line_name)
cts_line = self.make_line(dev + '_CTS')
if rts_line != "0":
have_rts_cts = True
@ -1893,12 +1894,12 @@ INCLUDE common.ld
if dev.startswith('OTG2'):
f.write(
'#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU2, 2, true, false, 0, 0, false, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2}\n' % dev) # noqa
'#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU2, 2, true, false, 0, 0, false, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, UINT8_MAX}\n' % dev) # noqa
OTG2_index = serial_list.index(dev)
self.dual_USB_enabled = True
elif dev.startswith('OTG'):
f.write(
'#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU1, 1, true, false, 0, 0, false, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}\n' % dev) # noqa
'#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU1, 1, true, false, 0, 0, false, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, UINT8_MAX}\n' % dev) # noqa
else:
need_uart_driver = True
f.write(
@ -1914,7 +1915,30 @@ INCLUDE common.ld
f.write("%d, " % self.get_gpio_bylabel(dev + "_RXINV"))
f.write("%s, " % self.get_extra_bylabel(dev + "_RXINV", "POL", "0"))
f.write("%d, " % self.get_gpio_bylabel(dev + "_TXINV"))
f.write("%s, 0}\n" % self.get_extra_bylabel(dev + "_TXINV", "POL", "0"))
f.write("%s, " % self.get_extra_bylabel(dev + "_TXINV", "POL", "0"))
# USB endpoint ID, not used
f.write("0, ")
# Find and add RTS alt fuction number if avalable
def get_RTS_alt_function():
# Typicaly we do software RTS control, so there is no requirement for the pin to have valid UART RTS alternative function
# If it does this enables hardware flow control for RS-485
lib = self.get_mcu_lib(self.mcu_type)
if (rts_line == "0") or (rts_line_name not in self.bylabel) or not hasattr(lib, "AltFunction_map"):
# No pin, 0 is a valid alt function, use UINT8_MAX for invalid
return "UINT8_MAX"
pin = self.bylabel[rts_line_name]
for label in self.af_labels:
if rts_line_name.startswith(label):
s = pin.portpin + ":" + rts_line_name
if s not in lib.AltFunction_map:
return "UINT8_MAX"
return lib.AltFunction_map[s]
f.write("%s}\n" % get_RTS_alt_function())
if have_rts_cts:
f.write('#define AP_FEATURE_RTSCTS 1\n')
if OTG2_index is not None: