AP_SerialManager: fix ESC telem baud rate so that it is consistent with other protocols baud forcing
This commit is contained in:
parent
ea4c3d68d6
commit
04a170d141
@ -481,7 +481,7 @@ void AP_SerialManager::init()
|
||||
|
||||
case SerialProtocol_ESCTelemetry:
|
||||
// ESC telemetry protocol from BLHeli32 ESCs. Note that baudrate is hardcoded to 115200
|
||||
state[i].baud = 115200;
|
||||
state[i].baud = 115200 / 1000;
|
||||
uart->begin(map_baudrate(state[i].baud), 30, 30);
|
||||
uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
|
||||
break;
|
||||
|
Loading…
Reference in New Issue
Block a user