From e8d2097ec434d2bd3036aa7d06c3622754a67944 Mon Sep 17 00:00:00 2001 From: Brad Bosch Date: Thu, 25 Apr 2024 11:29:32 -0500 Subject: [PATCH] GCS_MAVLink: Avoid serial passthrough buffer exhausted/lost data Just don't read more than we can write. --- libraries/GCS_MAVLink/GCS_Common.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 207143d08a..613fdd819a 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -6767,14 +6767,14 @@ void GCS::passthru_timer(void) uint8_t buf[64]; // read from port1, and write to port2 - int16_t nbytes = _passthru.port1->read_locked(buf, sizeof(buf), lock_key); + int16_t nbytes = _passthru.port1->read_locked(buf, MIN(sizeof(buf),_passthru.port2->txspace()), lock_key); if (nbytes > 0) { _passthru.last_port1_data_ms = AP_HAL::millis(); _passthru.port2->write_locked(buf, nbytes, lock_key); } // read from port2, and write to port1 - nbytes = _passthru.port2->read_locked(buf, sizeof(buf), lock_key); + nbytes = _passthru.port2->read_locked(buf, MIN(sizeof(buf),_passthru.port1->txspace()), lock_key); if (nbytes > 0) { _passthru.port1->write_locked(buf, nbytes, lock_key); }