feat(mavlink): propagate COMMAND_INT frame into vehicle_command

Without this the new VehicleCommand.frame field is never populated from
its intended source. COMMAND_LONG has no frame slot on the wire, so
default to FRAME_GLOBAL there to preserve existing behaviour.

Signed-off-by: Julian Oes <julian@oes.ch>
This commit is contained in:
Julian Oes
2026-05-05 12:07:54 +12:00
parent d87a73e23b
commit fec1df1053
+2
View File
@@ -508,6 +508,7 @@ MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg)
vcmd.param5 = (double)cmd_mavlink.param5;
vcmd.param6 = (double)cmd_mavlink.param6;
vcmd.param7 = cmd_mavlink.param7;
vcmd.frame = vehicle_command_s::FRAME_GLOBAL; // COMMAND_LONG has no frame field; default to AMSL
vcmd.command = cmd_mavlink.command;
vcmd.target_system = cmd_mavlink.target_system;
vcmd.target_component = cmd_mavlink.target_component;
@@ -553,6 +554,7 @@ MavlinkReceiver::handle_message_command_int(mavlink_message_t *msg)
}
vcmd.param7 = cmd_mavlink.z;
vcmd.frame = cmd_mavlink.frame;
vcmd.command = cmd_mavlink.command;
vcmd.target_system = cmd_mavlink.target_system;
vcmd.target_component = cmd_mavlink.target_component;