mirror of https://github.com/ArduPilot/ardupilot
AP_DroneCAN: Serial: map baudrates so param works as expected
This commit is contained in:
parent
720c8719dc
commit
3f6ce2dc09
|
@ -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);
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue