mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-08 02:17:07 +08:00
Abort on large packets which do not fit in buffer - not just if the gap is not provided any more.
This commit is contained in:
@@ -763,7 +763,7 @@ Mavlink::send_message(const uint8_t msgid, const void *msg)
|
||||
_last_write_try_time = hrt_absolute_time();
|
||||
|
||||
/* check if there is space in the buffer, let it overflow else */
|
||||
if (buf_free < TX_BUFFER_GAP) {
|
||||
if ((buf_free < TX_BUFFER_GAP) || (buf_free < packet_len)) {
|
||||
/* no enough space in buffer to send */
|
||||
count_txerr();
|
||||
count_txerrbytes(packet_len);
|
||||
|
||||
Reference in New Issue
Block a user