AP_DroneCAN: Serial: map baudrates so param works as expected

This commit is contained in:
Iampete1 2024-05-25 23:28:50 +01:00 committed by Andrew Tridgell
parent 720c8719dc
commit 3f6ce2dc09
1 changed files with 1 additions and 1 deletions

View File

@ -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);
}