mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
HAL_ChibiOS: automatically set AP_FEATURE_RTSCTS
This commit is contained in:
parent
5c4802ce25
commit
17118977dc
@ -943,6 +943,7 @@ def write_UART_config(f):
|
|||||||
need_uart_driver = False
|
need_uart_driver = False
|
||||||
OTG2_index = None
|
OTG2_index = None
|
||||||
devlist = []
|
devlist = []
|
||||||
|
have_rts_cts = False
|
||||||
for dev in uart_list:
|
for dev in uart_list:
|
||||||
if dev.startswith('UART'):
|
if dev.startswith('UART'):
|
||||||
n = int(dev[4:])
|
n = int(dev[4:])
|
||||||
@ -958,6 +959,7 @@ def write_UART_config(f):
|
|||||||
if dev + "_RTS" in bylabel:
|
if dev + "_RTS" in bylabel:
|
||||||
p = bylabel[dev + '_RTS']
|
p = bylabel[dev + '_RTS']
|
||||||
rts_line = 'PAL_LINE(GPIO%s,%uU)' % (p.port, p.pin)
|
rts_line = 'PAL_LINE(GPIO%s,%uU)' % (p.port, p.pin)
|
||||||
|
have_rts_cts = True
|
||||||
else:
|
else:
|
||||||
rts_line = "0"
|
rts_line = "0"
|
||||||
if dev.startswith('OTG2'):
|
if dev.startswith('OTG2'):
|
||||||
@ -985,6 +987,8 @@ def write_UART_config(f):
|
|||||||
f.write("%s, " % get_extra_bylabel(dev + "_RXINV", "POL", "0"))
|
f.write("%s, " % get_extra_bylabel(dev + "_RXINV", "POL", "0"))
|
||||||
f.write("%d, " % get_gpio_bylabel(dev + "_TXINV"))
|
f.write("%d, " % get_gpio_bylabel(dev + "_TXINV"))
|
||||||
f.write("%s}\n" % get_extra_bylabel(dev + "_TXINV", "POL", "0"))
|
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:
|
if OTG2_index is not None:
|
||||||
f.write('#define HAL_OTG2_UART_INDEX %d\n' % OTG2_index)
|
f.write('#define HAL_OTG2_UART_INDEX %d\n' % OTG2_index)
|
||||||
f.write('''
|
f.write('''
|
||||||
|
Loading…
Reference in New Issue
Block a user