mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
HAL_ChibiOS: fixed USB pass-thru for 2nd USB endpoint
we need to align the endpoint ID in the structure
This commit is contained in:
parent
4f0a573c73
commit
e2535a3851
@ -1796,13 +1796,13 @@ def write_UART_config(f):
|
||||
|
||||
if dev.startswith('OTG2'):
|
||||
f.write(
|
||||
'#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU2, 2, true, false, 0, 0, false, 0, 0, 2}\n'
|
||||
'#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)
|
||||
OTG2_index = uart_list.index(dev)
|
||||
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}\n'
|
||||
'#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)
|
||||
else:
|
||||
need_uart_driver = True
|
||||
|
Loading…
Reference in New Issue
Block a user