From e2535a385118eae2053f8b8fc98ab39f33e7650d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 30 May 2023 17:10:31 +1000 Subject: [PATCH] HAL_ChibiOS: fixed USB pass-thru for 2nd USB endpoint we need to align the endpoint ID in the structure --- libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index 4c95c6ab3b..cc789e5a14 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -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