From 056c1d39e17074bab44d10acacea6fc1aaa1bbd2 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 2 Sep 2025 23:10:25 +0100 Subject: [PATCH 1/2] AP_Scripting: check channel is valid before trying to send on it --- libraries/AP_Scripting/docs/docs.lua | 2 +- libraries/AP_Scripting/lua_bindings.cpp | 8 +++++++- 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 5b248ec283a6a..4919b6a187cd8 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -3972,7 +3972,7 @@ function mavlink:receive_chan() end ---@param chan integer ---@param msgid integer ---@param message string ----@return boolean -- success +---@return boolean|nil -- True if send was successful, false if send was not successful, nil if channel does not exist function mavlink:send_chan(chan, msgid, message) end -- Block a given MAV_CMD from being processed by ArduPilot diff --git a/libraries/AP_Scripting/lua_bindings.cpp b/libraries/AP_Scripting/lua_bindings.cpp index 995202a704250..70fe679464e0e 100644 --- a/libraries/AP_Scripting/lua_bindings.cpp +++ b/libraries/AP_Scripting/lua_bindings.cpp @@ -161,9 +161,15 @@ int lua_mavlink_send_chan(lua_State *L) { const int arg_offset = (luaL_testudata(L, 1, "mavlink") != NULL) ? 1 : 0; binding_argcheck(L, 3+arg_offset); - + const mavlink_channel_t chan = (mavlink_channel_t)get_uint32(L, 1+arg_offset, 0, MAVLINK_COMM_NUM_BUFFERS - 1); + // Check if the channel is valid + if (chan >= gcs().num_gcs()) { + // Return nil + return 0; + } + const uint32_t msgid = get_uint32(L, 2+arg_offset, 0, (1 << 24) - 1); const char *packet = luaL_checkstring(L, 3+arg_offset); From 6e18e1095a1559e7443382779f55a7110a5daf7c Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 2 Sep 2025 23:32:09 +0100 Subject: [PATCH 2/2] GCS_MAVLink: GCS_Signing: check status is valid before using it --- libraries/GCS_MAVLink/GCS_Signing.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Signing.cpp b/libraries/GCS_MAVLink/GCS_Signing.cpp index 9f3cfe1acb29b..44396eaf15bb6 100644 --- a/libraries/GCS_MAVLink/GCS_Signing.cpp +++ b/libraries/GCS_MAVLink/GCS_Signing.cpp @@ -234,7 +234,7 @@ void GCS_MAVLINK::save_signing_timestamp(bool force_save_now) bool GCS_MAVLINK::signing_enabled(void) const { const mavlink_status_t *status = mavlink_get_channel_status(chan); - if (status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING)) { + if ((status != nullptr) && status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING)) { return true; } return false; @@ -260,7 +260,7 @@ uint8_t GCS_MAVLINK::packet_overhead_chan(mavlink_channel_t chan) } const mavlink_status_t *status = mavlink_get_channel_status(chan); - if (status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING)) { + if ((status != nullptr) && status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING)) { return MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_SIGNATURE_BLOCK_LEN + reserved_space; } return MAVLINK_NUM_NON_PAYLOAD_BYTES + reserved_space;