diff --git a/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp b/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp index 3605dc152b..3c2b298630 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp @@ -97,13 +97,8 @@ MAV_MISSION_RESULT MissionItemProtocol_Waypoints::get_item(const GCS_MAVLINK &_l // set packet's current field to 1 if this is the command being executed if (cmd.id == (uint16_t)mission.get_current_nav_cmd().index) { ret_packet.current = 1; - } else { - ret_packet.current = 0; } - // set auto continue to 1 - ret_packet.autocontinue = 1; // 1 (true), 0 (false) - return MAV_MISSION_ACCEPTED; }