From 848e1bfdf86c53e53a84f58bdcc07c92f240892f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 24 Jun 2023 14:34:44 +1000 Subject: [PATCH] AP_GPS: ensure uart buffer sizes are OK for RTK rover needs higher tx size, base needs higher rx size --- libraries/AP_GPS/AP_GPS.cpp | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 1e94fa810c..42009f7e3e 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -763,7 +763,14 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance) dstate->current_baud = 0; } uint32_t baudrate = _baudrates[dstate->current_baud]; - _port[instance]->begin(baudrate); + uint16_t rx_size=0, tx_size=0; + if (_type[instance] == GPS_TYPE_UBLOX_RTK_ROVER) { + tx_size = 2048; + } + if (_type[instance] == GPS_TYPE_UBLOX_RTK_BASE) { + rx_size = 2048; + } + _port[instance]->begin(baudrate, rx_size, tx_size); _port[instance]->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); dstate->last_baud_change_ms = now;