diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index ee268d7291..0c7e16d088 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -674,6 +674,12 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_in static_cast(packet.param3), packet.param4); + case MAV_CMD_MISSION_START: + if (rover.set_mode(rover.mode_auto, ModeReason::GCS_COMMAND)) { + return MAV_RESULT_ACCEPTED; + } + return MAV_RESULT_FAILED; + default: return GCS_MAVLINK::handle_command_int_packet(packet, msg); } @@ -683,12 +689,6 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_l { switch (packet.command) { - case MAV_CMD_MISSION_START: - if (rover.set_mode(rover.mode_auto, ModeReason::GCS_COMMAND)) { - return MAV_RESULT_ACCEPTED; - } - return MAV_RESULT_FAILED; - case MAV_CMD_NAV_SET_YAW_SPEED: { // param1 : yaw angle to adjust direction by in centidegress