From 0ed29192b806e150825d74fbf0c3c585fb5990af Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 24 Mar 2017 20:21:46 +0100 Subject: [PATCH] mavlink_mission: don't reset vertex_count Since vertex_count is in a union with do_jump_current_count, we can't always reset the current count, otherwise the vertex_count ends up being 0. --- src/modules/mavlink/mavlink_mission.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp index cc7d0e6f39..bbb1f76679 100644 --- a/src/modules/mavlink/mavlink_mission.cpp +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -1382,9 +1382,6 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t * mission_item->autocontinue = mavlink_mission_item->autocontinue; // mission_item->index = mavlink_mission_item->seq; - /* reset DO_JUMP count */ - mission_item->do_jump_current_count = 0; - mission_item->origin = ORIGIN_MAVLINK; return MAV_MISSION_ACCEPTED;