5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-05 15:38:29 -04:00

AP_SerialManager: use unbuffered writes for volz

This commit is contained in:
Andrew Tridgell 2018-02-03 14:26:33 +11:00
parent e29b79f41b
commit 2513e60e3c

View File

@ -231,6 +231,8 @@ void AP_SerialManager::init()
state[i].uart->begin(map_baudrate(state[i].baud),
AP_SERIALMANAGER_VOLZ_BUFSIZE_RX,
AP_SERIALMANAGER_VOLZ_BUFSIZE_TX);
state[i].uart->set_unbuffered_writes(true);
state[i].uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
break;
case SerialProtocol_Sbus1:
state[i].baud = AP_SERIALMANAGER_SBUS1_BAUD / 1000; // update baud param in case user looks at it