Browse Source

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.
sbg
Julian Oes 8 years ago committed by Lorenz Meier
parent
commit
0ed29192b8
  1. 3
      src/modules/mavlink/mavlink_mission.cpp

3
src/modules/mavlink/mavlink_mission.cpp

@ -1382,9 +1382,6 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t * @@ -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;

Loading…
Cancel
Save