|
|
|
@ -98,11 +98,11 @@ void MissionManager::generateResumeMission(int resumeIndex)
@@ -98,11 +98,11 @@ void MissionManager::generateResumeMission(int resumeIndex)
|
|
|
|
|
resumeIndex = qMax(0, qMin(resumeIndex, _missionItems.count() - 1)); |
|
|
|
|
|
|
|
|
|
// Adjust resume index to be a location based command
|
|
|
|
|
const MissionCommandUIInfo* uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_vehicle, QGCMAVLink::VehicleClassGeneric, _missionItems[resumeIndex]->command()); |
|
|
|
|
const MissionCommandUIInfo* uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_vehicle, _vehicle->vehicleClass(), _missionItems[resumeIndex]->command()); |
|
|
|
|
if (!uiInfo || uiInfo->isStandaloneCoordinate() || !uiInfo->specifiesCoordinate()) { |
|
|
|
|
// We have to back up to the last command which the vehicle flies through
|
|
|
|
|
while (--resumeIndex > 0) { |
|
|
|
|
uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_vehicle, QGCMAVLink::VehicleClassGeneric, _missionItems[resumeIndex]->command()); |
|
|
|
|
uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_vehicle, _vehicle->vehicleClass(), _missionItems[resumeIndex]->command()); |
|
|
|
|
if (uiInfo && (uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate())) { |
|
|
|
|
// Found it
|
|
|
|
|
break; |
|
|
|
@ -130,15 +130,15 @@ void MissionManager::generateResumeMission(int resumeIndex)
@@ -130,15 +130,15 @@ void MissionManager::generateResumeMission(int resumeIndex)
|
|
|
|
|
<< MAV_CMD_VIDEO_START_CAPTURE |
|
|
|
|
<< MAV_CMD_VIDEO_STOP_CAPTURE |
|
|
|
|
<< MAV_CMD_DO_CHANGE_SPEED |
|
|
|
|
<< MAV_CMD_SET_CAMERA_MODE |
|
|
|
|
<< MAV_CMD_NAV_TAKEOFF; |
|
|
|
|
<< MAV_CMD_SET_CAMERA_MODE; |
|
|
|
|
|
|
|
|
|
bool addHomePosition = _vehicle->firmwarePlugin()->sendHomePositionToVehicle(); |
|
|
|
|
|
|
|
|
|
int prefixCommandCount = 0; |
|
|
|
|
for (int i=0; i<_missionItems.count(); i++) { |
|
|
|
|
MissionItem* oldItem = _missionItems[i]; |
|
|
|
|
if ((i == 0 && addHomePosition) || i >= resumeIndex || includedResumeCommands.contains(oldItem->command())) { |
|
|
|
|
const MissionCommandUIInfo* uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_vehicle, _vehicle->vehicleClass(), oldItem->command()); |
|
|
|
|
if ((i == 0 && addHomePosition) || i >= resumeIndex || includedResumeCommands.contains(oldItem->command()) || (uiInfo && uiInfo->isTakeoffCommand())) { |
|
|
|
|
if (i < resumeIndex) { |
|
|
|
|
prefixCommandCount++; |
|
|
|
|
} |
|
|
|
|