mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: automatically set AP_FEATURE_RTSCTS
This commit is contained in:
parent
0288b3d43c
commit
b3459c024c
|
@ -968,6 +968,7 @@ def write_UART_config(f):
|
|||
need_uart_driver = False
|
||||
OTG2_index = None
|
||||
devlist = []
|
||||
have_rts_cts = False
|
||||
for dev in uart_list:
|
||||
if dev.startswith('UART'):
|
||||
n = int(dev[4:])
|
||||
|
@ -983,6 +984,7 @@ def write_UART_config(f):
|
|||
if dev + "_RTS" in bylabel:
|
||||
p = bylabel[dev + '_RTS']
|
||||
rts_line = 'PAL_LINE(GPIO%s,%uU)' % (p.port, p.pin)
|
||||
have_rts_cts = True
|
||||
else:
|
||||
rts_line = "0"
|
||||
if dev.startswith('OTG2'):
|
||||
|
@ -1010,6 +1012,8 @@ def write_UART_config(f):
|
|||
f.write("%s, " % get_extra_bylabel(dev + "_RXINV", "POL", "0"))
|
||||
f.write("%d, " % get_gpio_bylabel(dev + "_TXINV"))
|
||||
f.write("%s}\n" % get_extra_bylabel(dev + "_TXINV", "POL", "0"))
|
||||
if have_rts_cts:
|
||||
f.write('#define AP_FEATURE_RTSCTS 1\n')
|
||||
if OTG2_index is not None:
|
||||
f.write('#define HAL_OTG2_UART_INDEX %d\n' % OTG2_index)
|
||||
f.write('''
|
||||
|
|
Loading…
Reference in New Issue