mirror of https://github.com/ArduPilot/ardupilot
HAL_SITL: fixed baudrate 0 set in SITL
this fixes MSP sensors in SITL with real uarts
This commit is contained in:
parent
7b6392fcb5
commit
2e18334165
|
@ -557,7 +557,9 @@ void UARTDriver::_uart_start_connection(void)
|
|||
tcsetattr(_fd, TCSANOW, &t);
|
||||
|
||||
// set baudrate
|
||||
set_speed(_uart_baudrate);
|
||||
if (_uart_baudrate != 0) {
|
||||
set_speed(_uart_baudrate);
|
||||
}
|
||||
|
||||
_connected = true;
|
||||
_use_send_recv = false;
|
||||
|
|
Loading…
Reference in New Issue