AP_Scripting: do semaphore lock when sending mavlink message from lua

This commit is contained in:
bugobliterator 2023-05-14 16:08:36 +10:00 committed by Andrew Tridgell
parent 949f0e36d0
commit 28d49834c0

View File

@ -144,6 +144,8 @@ int lua_mavlink_send_chan(lua_State *L) {
if (entry == nullptr) {
return luaL_error(L, "Unknown MAVLink message ID (%d)", msgid);
}
WITH_SEMAPHORE(comm_chan_lock(chan));
if (comm_get_txspace(chan) >= (GCS_MAVLINK::packet_overhead_chan(chan) + entry->max_msg_len)) {
_mav_finalize_message_chan_send(chan,
entry->msgid,