HAL_SITL: fixed baudrate 0 set in SITL

this fixes MSP sensors in SITL with real uarts
This commit is contained in:
Andrew Tridgell 2020-12-09 14:59:31 +11:00 committed by Peter Barker
parent 7b6392fcb5
commit 2e18334165

View File

@ -557,7 +557,9 @@ void UARTDriver::_uart_start_connection(void)
tcsetattr(_fd, TCSANOW, &t); tcsetattr(_fd, TCSANOW, &t);
// set baudrate // set baudrate
set_speed(_uart_baudrate); if (_uart_baudrate != 0) {
set_speed(_uart_baudrate);
}
_connected = true; _connected = true;
_use_send_recv = false; _use_send_recv = false;