Browse Source

AP_SerialManager: call set_options() before first UART use

this ensures options are set before the first begin() call
zr-v5.1
Andrew Tridgell 4 years ago committed by Randy Mackay
parent
commit
fcc9e4627c
  1. 8
      libraries/AP_SerialManager/AP_SerialManager.cpp

8
libraries/AP_SerialManager/AP_SerialManager.cpp

@ -569,7 +569,13 @@ AP_HAL::UARTDriver *AP_SerialManager::find_serial(enum SerialProtocol protocol, @@ -569,7 +569,13 @@ AP_HAL::UARTDriver *AP_SerialManager::find_serial(enum SerialProtocol protocol,
return nullptr;
}
const uint8_t serial_idx = _state - &state[0];
return hal.serial(serial_idx);
// set options before any user does begin()
AP_HAL::UARTDriver *port = hal.serial(serial_idx);
if (port) {
port->set_options(_state->options);
}
return port;
}
// find_baudrate - searches available serial ports for the first instance that allows the given protocol

Loading…
Cancel
Save