diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 7667506d9a..fb97e5ee1d 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -477,14 +477,18 @@ MavlinkReceiver::handle_message_command_int(mavlink_message_t *msg) vcmd.frame = vehicle_command_s::FRAME_GLOBAL; break; + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + + // FALLTHROUGH case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT: vcmd.frame = vehicle_command_s::FRAME_GLOBAL_RELATIVE_ALT; break; default: vcmd.frame = vehicle_command_s::FRAME_UNKNOWN; - PX4_WARN("invalid frame %" PRIu8 " for command %" PRIu16, cmd_mavlink.frame, cmd_mavlink.command); - break; + PX4_ERR("invalid frame %" PRIu8 " for command %" PRIu16, cmd_mavlink.frame, cmd_mavlink.command); + acknowledge(msg->sysid, msg->compid, cmd_mavlink.command, vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED); + return; } if (cmd_mavlink.x == INT32_MAX && cmd_mavlink.y == INT32_MAX) {