mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: use WITH_SEMAPHORE()
this is a suggestion from Peter, will need some discussion
This commit is contained in:
parent
6f058e8c0d
commit
a26e534654
|
@ -1281,7 +1281,7 @@ void GCS::send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const cha
|
|||
statustext.msg.severity = severity;
|
||||
strncpy(statustext.msg.text, text, sizeof(statustext.msg.text));
|
||||
|
||||
_statustext_sem.take_blocking();
|
||||
WITH_SEMAPHORE(_statustext_sem);
|
||||
|
||||
// The force push will ensure comm links do not block other comm links forever if they fail.
|
||||
// If we push to a full buffer then we overwrite the oldest entry, effectively removing the
|
||||
|
@ -1295,8 +1295,6 @@ void GCS::send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const cha
|
|||
if (notify) {
|
||||
notify->send_text(text);
|
||||
}
|
||||
|
||||
_statustext_sem.give();
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -1363,9 +1361,8 @@ void GCS::retry_deferred()
|
|||
chan(i).retry_deferred();
|
||||
}
|
||||
}
|
||||
_statustext_sem.take_blocking();
|
||||
WITH_SEMAPHORE(_statustext_sem);
|
||||
service_statustext();
|
||||
_statustext_sem.give();
|
||||
}
|
||||
|
||||
void GCS::data_stream_send()
|
||||
|
|
Loading…
Reference in New Issue