mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
GCS_MAVLink: correct potential uint underflow in stream slowdown
This commit is contained in:
parent
77abaef092
commit
db2736c297
@ -792,7 +792,11 @@ void GCS_MAVLINK::handle_radio_status(const mavlink_message_t &msg, bool log_rad
|
||||
stream_slowdown_ms -= 40;
|
||||
} else if (packet.txbuf > 90 && stream_slowdown_ms != 0) {
|
||||
// the buffer has enough space, speed up a bit
|
||||
stream_slowdown_ms -= 20;
|
||||
if (stream_slowdown_ms > 20) {
|
||||
stream_slowdown_ms -= 20;
|
||||
} else {
|
||||
stream_slowdown_ms = 0;
|
||||
}
|
||||
}
|
||||
|
||||
#if GCS_DEBUG_SEND_MESSAGE_TIMINGS
|
||||
|
Loading…
Reference in New Issue
Block a user