mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
GCS_MAVLink: fixed mavlink packet corruption with multiple threads
this ensures we don't try to send more data to a uart than is available in the tx buffer
This commit is contained in:
parent
fd8d28e23c
commit
cce89099c5
@ -2053,6 +2053,8 @@ void GCS_MAVLINK::service_statustext(void)
|
||||
{
|
||||
GCS::StatusTextQueue &_statustext_queue = gcs().statustext_queue();
|
||||
|
||||
WITH_SEMAPHORE(comm_chan_lock(chan));
|
||||
|
||||
const uint8_t chan_bit = (1U<<chan);
|
||||
// note the lack of idx++ here. We may remove the iteration item
|
||||
// from the queue as the last thing we do, in which case we don't
|
||||
|
Loading…
Reference in New Issue
Block a user