mirror of https://github.com/ArduPilot/ardupilot
Rover: fix to support uploading partial missions
This commit is contained in:
parent
30194b9e72
commit
df5c874f73
|
@ -1444,12 +1444,8 @@ mission_item_send_failed:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
// new mission arriving, clear current mission
|
// new mission arriving, truncate mission to be the same length
|
||||||
if (!mission.clear()) {
|
mission.truncate(packet.count);
|
||||||
// return error if we were unable to clear the mission (possibly because we're currently flying the mission)
|
|
||||||
mavlink_msg_mission_ack_send(chan, msg->sysid, msg->compid, MAV_MISSION_ERROR);
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
waypoint_timelast_receive = millis();
|
waypoint_timelast_receive = millis();
|
||||||
waypoint_timelast_request = 0;
|
waypoint_timelast_request = 0;
|
||||||
|
|
Loading…
Reference in New Issue