mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: add passthrough from secondary through primary while in bootloader
This commit is contained in:
parent
e64dfa4d58
commit
04879d2c42
|
@ -41,14 +41,23 @@ PA14 JTCK-SWCLK SWD
|
|||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
# primary <-> secondary
|
||||
PE7 UART7_RX UART7
|
||||
PE8 UART7_TX UART7
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 USART2
|
||||
# USART2 USART6 USART3 UART8 UART7 UART4
|
||||
|
||||
define STM32_SERIAL_USE_USART2 TRUE
|
||||
define STM32_SERIAL_USE_UART7 TRUE
|
||||
define HAL_USE_SERIAL TRUE
|
||||
|
||||
define BOOTLOADER_DEBUG SD2
|
||||
define BOOTLOADER_FORWARD_OTG2_SERIAL SD7
|
||||
define BOOTLOADER_FORWARD_OTG2_SERIAL_BAUDRATE 2000000
|
||||
define BOOTLOADER_FORWARD_OTG2_SERIAL_SWAP TRUE
|
||||
define HAL_HAVE_DUAL_USB_CDC 1
|
||||
|
||||
# reserve 256 bytes for comms between app and bootloader
|
||||
RAM_RESERVE_START 256
|
||||
|
|
Loading…
Reference in New Issue