GCS_MAVLink: stop taking semaphore aorund statustext queue loop

we're taking it in the loop
This commit is contained in:
Peter Barker 2022-02-22 10:27:40 +11:00 committed by Andrew Tridgell
parent b444420329
commit 87439eec80

View File

@ -2053,8 +2053,6 @@ 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