diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index d7416c1268..e5cfb004f4 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -684,7 +684,8 @@ void AP_SerialManager::set_options(uint16_t i) } // get the passthru ports if enabled -bool AP_SerialManager::get_passthru(AP_HAL::UARTDriver *&port1, AP_HAL::UARTDriver *&port2, uint8_t &timeout_s) const +bool AP_SerialManager::get_passthru(AP_HAL::UARTDriver *&port1, AP_HAL::UARTDriver *&port2, uint8_t &timeout_s, + uint32_t &baud1, uint32_t &baud2) const { if (passthru_port2 < 0 || passthru_port2 >= SERIALMANAGER_NUM_PORTS || @@ -694,6 +695,8 @@ bool AP_SerialManager::get_passthru(AP_HAL::UARTDriver *&port1, AP_HAL::UARTDriv } port1 = state[passthru_port1].uart; port2 = state[passthru_port2].uart; + baud1 = map_baudrate(state[passthru_port1].baud); + baud2 = map_baudrate(state[passthru_port2].baud); timeout_s = MAX(passthru_timeout, 0); return true; } diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index 50cc1dd408..6cdb93c1a3 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -189,7 +189,8 @@ public: void set_blocking_writes_all(bool blocking); // get the passthru ports if enabled - bool get_passthru(AP_HAL::UARTDriver *&port1, AP_HAL::UARTDriver *&port2, uint8_t &timeout_s) const; + bool get_passthru(AP_HAL::UARTDriver *&port1, AP_HAL::UARTDriver *&port2, uint8_t &timeout_s, + uint32_t &baud1, uint32_t &baud2) const; // disable passthru by settings SERIAL_PASS2 to -1 void disable_passthru(void);