Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/docs/docs.lua
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
8 changes: 7 additions & 1 deletion libraries/AP_Scripting/lua_bindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
4 changes: 2 additions & 2 deletions libraries/GCS_MAVLink/GCS_Signing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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;
Expand Down
Loading