diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 3186354556..17e3762f59 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1010,6 +1010,10 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in } return MAV_RESULT_FAILED; + case MAV_CMD_MISSION_START: + plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND); + return MAV_RESULT_ACCEPTED; + default: return GCS_MAVLINK::handle_command_int_packet(packet, msg); } @@ -1057,10 +1061,6 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l } #endif // HAL_QUADPLANE_ENABLED - case MAV_CMD_MISSION_START: - plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND); - return MAV_RESULT_ACCEPTED; - default: return GCS_MAVLINK::handle_command_long_packet(packet, msg); }