From 3f6ce2dc0941e5edd60839a2e80fe003b904581e Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 25 May 2024 23:28:50 +0100 Subject: [PATCH] AP_DroneCAN: Serial: map baudrates so param works as expected --- libraries/AP_DroneCAN/AP_DroneCAN_serial.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_DroneCAN/AP_DroneCAN_serial.cpp b/libraries/AP_DroneCAN/AP_DroneCAN_serial.cpp index f0bbd72884..4eb488117d 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN_serial.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN_serial.cpp @@ -132,7 +132,7 @@ void AP_DroneCAN_Serial::handle_tunnel_targetted(AP_DroneCAN *dronecan, */ void AP_DroneCAN_Serial::Port::init(void) { - baudrate = state.baud; + baudrate = AP_SerialManager::map_baudrate(state.baud); begin(baudrate, 0, 0); }