From fec1df1053440cd55ab9ffcd3463c07e54df9cd2 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 5 May 2026 12:07:54 +1200 Subject: [PATCH] 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 --- src/modules/mavlink/mavlink_receiver.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index cb330bb9d85..b692010d0f4 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -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;