Browse Source

AP_SerialManager: fixed AP_Periph GPS

the disable of RX/TX pins broke AP_Periph on boards that don't enable
the GCS, as they don't have the SERIALn parameters, so we disable the
UART pins of the GPS
gps-1.3.1
Andrew Tridgell 3 years ago
parent
commit
08ca708347
  1. 7
      libraries/AP_SerialManager/AP_SerialManager.cpp

7
libraries/AP_SerialManager/AP_SerialManager.cpp

@ -450,9 +450,14 @@ void AP_SerialManager::init() @@ -450,9 +450,14 @@ void AP_SerialManager::init()
set_options(i);
switch (state[i].protocol) {
case SerialProtocol_None:
#if HAL_GCS_ENABLED
// disable RX and TX pins in case they are shared
// with another peripheral (eg. RCIN pin)
// with another peripheral (eg. RCIN pin). We
// don't do this if GCS is not enabled as in that
// case we don't have serialmanager parameters and
// this would prevent AP_Periph from using a GPS
uart->disable_rxtx();
#endif
break;
case SerialProtocol_Console:
case SerialProtocol_MAVLink:

Loading…
Cancel
Save