mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
HAL_ChibiOS: fixed build on boards with less than max uarts
This commit is contained in:
parent
1919268801
commit
2f0a4ff1ab
@ -894,7 +894,7 @@ def write_UART_config(f):
|
|||||||
% (devnames[idx], devnames[idx], sdev))
|
% (devnames[idx], devnames[idx], sdev))
|
||||||
sdev += 1
|
sdev += 1
|
||||||
idx += 1
|
idx += 1
|
||||||
for idx in range(len(uart_list), 7):
|
for idx in range(len(uart_list), len(devnames)):
|
||||||
f.write('#define HAL_UART%s_DRIVER Empty::UARTDriver uart%sDriver\n' %
|
f.write('#define HAL_UART%s_DRIVER Empty::UARTDriver uart%sDriver\n' %
|
||||||
(devnames[idx], devnames[idx]))
|
(devnames[idx], devnames[idx]))
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user