From 23d171e5975ac442fca08a0e133607fa6baf4659 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 20 Nov 2019 18:56:46 +1100 Subject: [PATCH] AP_SerialManager: fixed GPS in AP_Periph we need to have at least 4 SERIALn_* parameters to support GPS on AP_Periph due to the odd ordering of hal.uartB as SERIAL3 --- libraries/AP_SerialManager/AP_SerialManager.h | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index 10b39d5e6c..f0517bf167 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -26,8 +26,14 @@ #include #ifdef HAL_UART_NUM_SERIAL_PORTS +#if HAL_UART_NUM_SERIAL_PORTS >= 4 #define SERIALMANAGER_NUM_PORTS HAL_UART_NUM_SERIAL_PORTS #else +// we need a minimum of 4 to allow for a GPS due to the odd ordering +// of hal.uartB as SERIAL3 +#define SERIALMANAGER_NUM_PORTS 4 +#endif +#else // assume max 8 ports #define SERIALMANAGER_NUM_PORTS 8 #endif