mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
GCS_MAVLink: Pause to allow serial port to drain.
This avoids a race between the UART and the auto flow control code.
This commit is contained in:
parent
f1eb2f88df
commit
c87a7c7df9
@ -89,6 +89,9 @@ GCS_MAVLINK::setup_uart(const AP_SerialManager& serial_manager, AP_SerialManager
|
||||
uart->write(0x30);
|
||||
uart->write(0x20);
|
||||
}
|
||||
// since tcdrain() and TCSADRAIN may not be implemented...
|
||||
hal.scheduler->delay(1);
|
||||
|
||||
uart->set_flow_control(old_flow_control);
|
||||
|
||||
// now change back to desired baudrate
|
||||
|
Loading…
Reference in New Issue
Block a user