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
This commit is contained in:
Andrew Tridgell 2019-11-20 18:56:46 +11:00
parent b06152ff7e
commit 23d171e597
1 changed files with 6 additions and 0 deletions

View File

@ -26,8 +26,14 @@
#include <AP_Param/AP_Param.h> #include <AP_Param/AP_Param.h>
#ifdef HAL_UART_NUM_SERIAL_PORTS #ifdef HAL_UART_NUM_SERIAL_PORTS
#if HAL_UART_NUM_SERIAL_PORTS >= 4
#define SERIALMANAGER_NUM_PORTS HAL_UART_NUM_SERIAL_PORTS #define SERIALMANAGER_NUM_PORTS HAL_UART_NUM_SERIAL_PORTS
#else #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 // assume max 8 ports
#define SERIALMANAGER_NUM_PORTS 8 #define SERIALMANAGER_NUM_PORTS 8
#endif #endif