forked from Archive/PX4-Autopilot
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.
This commit is contained in:
parent
c4cdaa48e0
commit
0ed29192b8
|
@ -1382,9 +1382,6 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t *
|
||||||
mission_item->autocontinue = mavlink_mission_item->autocontinue;
|
mission_item->autocontinue = mavlink_mission_item->autocontinue;
|
||||||
// mission_item->index = mavlink_mission_item->seq;
|
// mission_item->index = mavlink_mission_item->seq;
|
||||||
|
|
||||||
/* reset DO_JUMP count */
|
|
||||||
mission_item->do_jump_current_count = 0;
|
|
||||||
|
|
||||||
mission_item->origin = ORIGIN_MAVLINK;
|
mission_item->origin = ORIGIN_MAVLINK;
|
||||||
|
|
||||||
return MAV_MISSION_ACCEPTED;
|
return MAV_MISSION_ACCEPTED;
|
||||||
|
|
Loading…
Reference in New Issue