diff --git a/src/MissionManager/MissionManager.cc b/src/MissionManager/MissionManager.cc index db35e2fca8bb0797774e246ed2691504eb29a581..8c9029fa726dc4464e20ee90fa1bcf49ce29dd14 100644 --- a/src/MissionManager/MissionManager.cc +++ b/src/MissionManager/MissionManager.cc @@ -983,6 +983,8 @@ void MissionManager::generateResumeMission(int resumeIndex) } } + resumeIndex = qMin(resumeIndex, _missionItems.count() - 1); + int seqNum = 0; QList resumeMission; @@ -1001,6 +1003,9 @@ void MissionManager::generateResumeMission(int resumeIndex) << MAV_CMD_IMAGE_STOP_CAPTURE << MAV_CMD_VIDEO_START_CAPTURE << MAV_CMD_VIDEO_STOP_CAPTURE; + if (_vehicle->fixedWing() && _vehicle->px4Firmware()) { + includedResumeCommands << MAV_CMD_NAV_TAKEOFF; + } bool addHomePosition = _vehicle->firmwarePlugin()->sendHomePositionToVehicle(); int setCurrentIndex = addHomePosition ? 1 : 0;