Minor MAVLink fixes

This commit is contained in:
Marek S. Łukasiewicz 2025-12-13 21:44:41 +01:00
parent e5bebc86cc
commit f3d38c7569

View file

@ -26,6 +26,7 @@
#include "mavlink/mavlink_types.h" #include "mavlink/mavlink_types.h"
#include <cstdint> #include <cstdint>
#include <optional> #include <optional>
#include <string.h>
using namespace godot; using namespace godot;
@ -403,10 +404,11 @@ Error MarshConnector::send_param(Parameter index) {
} }
mavlink_param_value_t param_value; mavlink_param_value_t param_value;
memset(param_value.param_id, 0, sizeof(param_value.param_id));
CharString nameBuffer = parameter_names[index].ascii(); CharString nameBuffer = parameter_names[index].ascii();
const char *name = nameBuffer.get_data(); const char *name = nameBuffer.get_data();
strcpy_s(param_value.param_id, name);
// strncpy will write nulls after data until reaching target count
strncpy(param_value.param_id, name, sizeof(param_value.param_id));
param_value.param_value = parameters[index]; param_value.param_value = parameters[index];
param_value.param_type = MAV_PARAM_TYPE_REAL32; param_value.param_type = MAV_PARAM_TYPE_REAL32;
param_value.param_count = PARAM_COUNT; param_value.param_count = PARAM_COUNT;
@ -447,9 +449,8 @@ void MarshConnector::handle_heartbeat(mavlink_message_t message) {
// subscribe to messages not sent to visualisation node by default // subscribe to messages not sent to visualisation node by default
mavlink_command_long_t command; mavlink_command_long_t command;
command.target_system = 1; command.target_system = message.sysid;
command.target_component = command.target_component = message.compid;
MAV_COMP_ID_USER1; // HACK: Should get it from received HEARTBEAT
command.command = MAV_CMD_SET_MESSAGE_INTERVAL; command.command = MAV_CMD_SET_MESSAGE_INTERVAL;
command.confirmation = 0; command.confirmation = 0;
command.param1 = static_cast<float>(MAVLINK_MSG_ID_MANUAL_CONTROL); command.param1 = static_cast<float>(MAVLINK_MSG_ID_MANUAL_CONTROL);
@ -458,7 +459,7 @@ void MarshConnector::handle_heartbeat(mavlink_message_t message) {
command.param4 = 0; command.param4 = 0;
command.param5 = 0; command.param5 = 0;
command.param6 = 0; command.param6 = 0;
command.param7 = 1; // Address of requestor command.param7 = 1; // Address of requester
mavlink_message_t message_sent; mavlink_message_t message_sent;
mavlink_msg_command_long_encode_chan( mavlink_msg_command_long_encode_chan(