Skip to content

Commit

Permalink
GCS_MAVLink: Avoid serial passthrough buffer exhausted/lost data
Browse files Browse the repository at this point in the history
Just don't read more than we can write.
  • Loading branch information
brad112358 authored and tridge committed Apr 29, 2024
1 parent bcf6332 commit e8d2097
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
Expand Down

0 comments on commit e8d2097

Please sign in to comment.