Browse Source

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
master
Andrew Tridgell 5 years ago
parent
commit
aad4598644
  1. 6
      libraries/AP_SerialManager/AP_SerialManager.h

6
libraries/AP_SerialManager/AP_SerialManager.h

@ -26,8 +26,14 @@ @@ -26,8 +26,14 @@
#include <AP_Param/AP_Param.h>
#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

Loading…
Cancel
Save