From fcc9e4627c211b2ac07785a1190fb10e525a605f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 8 Jul 2021 08:25:07 +1000 Subject: [PATCH] AP_SerialManager: call set_options() before first UART use this ensures options are set before the first begin() call --- libraries/AP_SerialManager/AP_SerialManager.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 7be211fa6a..67fcb64e49 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -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