Commit a476cf58 authored by DonLakeFlyer's avatar DonLakeFlyer

Fix resume mission generation and crashes

* Resume index adjust to previous coordinate command
* Takeoff always added to resume mission
* Remove camera id checks which are no longer part of spec
* Simplified de-dup logic
parent aee8ac12
...@@ -988,7 +988,23 @@ void MissionManager::generateResumeMission(int resumeIndex) ...@@ -988,7 +988,23 @@ void MissionManager::generateResumeMission(int resumeIndex)
} }
} }
resumeIndex = qMin(resumeIndex, _missionItems.count() - 1); // Be anal about crap input
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, _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, _missionItems[resumeIndex]->command());
if (uiInfo && (uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate())) {
// Found it
break;
}
}
}
resumeIndex = qMax(0, resumeIndex);
int seqNum = 0; int seqNum = 0;
QList<MissionItem*> resumeMission; QList<MissionItem*> resumeMission;
...@@ -1008,20 +1024,19 @@ void MissionManager::generateResumeMission(int resumeIndex) ...@@ -1008,20 +1024,19 @@ void MissionManager::generateResumeMission(int resumeIndex)
<< MAV_CMD_IMAGE_STOP_CAPTURE << MAV_CMD_IMAGE_STOP_CAPTURE
<< MAV_CMD_VIDEO_START_CAPTURE << MAV_CMD_VIDEO_START_CAPTURE
<< MAV_CMD_VIDEO_STOP_CAPTURE << MAV_CMD_VIDEO_STOP_CAPTURE
<< MAV_CMD_DO_CHANGE_SPEED; << MAV_CMD_DO_CHANGE_SPEED
if (_vehicle->fixedWing() && _vehicle->px4Firmware()) { << MAV_CMD_SET_CAMERA_MODE
includedResumeCommands << MAV_CMD_NAV_TAKEOFF; << MAV_CMD_NAV_TAKEOFF;
}
bool addHomePosition = _vehicle->firmwarePlugin()->sendHomePositionToVehicle(); bool addHomePosition = _vehicle->firmwarePlugin()->sendHomePositionToVehicle();
int setCurrentIndex = addHomePosition ? 1 : 0; int setCurrentIndex = addHomePosition ? 1 : 0;
int resumeCommandCount = 0; int prefixCommandCount = 0;
for (int i=0; i<_missionItems.count(); i++) { for (int i=0; i<_missionItems.count(); i++) {
MissionItem* oldItem = _missionItems[i]; MissionItem* oldItem = _missionItems[i];
if ((i == 0 && addHomePosition) || i >= resumeIndex || includedResumeCommands.contains(oldItem->command())) { if ((i == 0 && addHomePosition) || i >= resumeIndex || includedResumeCommands.contains(oldItem->command())) {
if (i < resumeIndex) { if (i < resumeIndex) {
resumeCommandCount++; prefixCommandCount++;
} }
MissionItem* newItem = new MissionItem(*oldItem, this); MissionItem* newItem = new MissionItem(*oldItem, this);
newItem->setIsCurrentItem( i == setCurrentIndex); newItem->setIsCurrentItem( i == setCurrentIndex);
...@@ -1029,91 +1044,56 @@ void MissionManager::generateResumeMission(int resumeIndex) ...@@ -1029,91 +1044,56 @@ void MissionManager::generateResumeMission(int resumeIndex)
resumeMission.append(newItem); resumeMission.append(newItem);
} }
} }
prefixCommandCount = qMax(0, qMin(prefixCommandCount, resumeMission.count())); // Anal prevention against crashes
// De-dup and remove no-ops from the commands which were added to the front of the mission // De-dup and remove no-ops from the commands which were added to the front of the mission
bool foundROI = false; bool foundROI = false;
bool foundCamTrigDist = false; bool foundCameraSetMode = false;
QList<int> imageStartCameraIds; bool foundCameraStartStop = false;
QList<int> imageStopCameraIds; prefixCommandCount--; // Change from count to array index
QList<int> videoStartCameraIds; while (prefixCommandCount >= 0) {
QList<int> videoStopCameraIds; MissionItem* resumeItem = resumeMission[prefixCommandCount];
while (resumeIndex >= 0) {
MissionItem* resumeItem = resumeMission[resumeIndex];
switch (resumeItem->command()) { switch (resumeItem->command()) {
case MAV_CMD_SET_CAMERA_MODE:
// Only keep the last one
if (foundCameraSetMode) {
resumeMission.removeAt(prefixCommandCount);
}
foundCameraSetMode = true;
break;
case MAV_CMD_DO_SET_ROI: case MAV_CMD_DO_SET_ROI:
// Only keep the last one // Only keep the last one
if (foundROI) { if (foundROI) {
resumeMission.removeAt(resumeIndex); resumeMission.removeAt(prefixCommandCount);
} }
foundROI = true; foundROI = true;
break; break;
case MAV_CMD_DO_SET_CAM_TRIGG_DIST: case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
// Only keep the last one
if (foundCamTrigDist) {
resumeMission.removeAt(resumeIndex);
}
foundCamTrigDist = true;
break;
case MAV_CMD_IMAGE_START_CAPTURE:
{
// FIXME: Handle single image capture
int cameraId = resumeItem->param1();
if (resumeItem->param3() == 1) {
// This is an individual image capture command, remove it
resumeMission.removeAt(resumeIndex);
break;
}
// If we already found an image stop, then all image start/stop commands are useless
// De-dup repeated image start commands
// Otherwise keep only the last image start
if (imageStopCameraIds.contains(cameraId) || imageStartCameraIds.contains(cameraId)) {
resumeMission.removeAt(resumeIndex);
}
if (!imageStopCameraIds.contains(cameraId)) {
imageStopCameraIds.append(cameraId);
}
}
break;
case MAV_CMD_IMAGE_STOP_CAPTURE: case MAV_CMD_IMAGE_STOP_CAPTURE:
{
int cameraId = resumeItem->param1();
// Image stop only matters to kill all previous image starts
if (!imageStopCameraIds.contains(cameraId)) {
imageStopCameraIds.append(cameraId);
}
resumeMission.removeAt(resumeIndex);
}
break;
case MAV_CMD_VIDEO_START_CAPTURE: case MAV_CMD_VIDEO_START_CAPTURE:
{ case MAV_CMD_VIDEO_STOP_CAPTURE:
int cameraId = resumeItem->param1(); // Only keep the first of these commands that are found
// If we've already found a video stop, then all video start/stop commands are useless if (foundCameraStartStop) {
// De-dup repeated video start commands resumeMission.removeAt(prefixCommandCount);
// Otherwise keep only the last video start
if (videoStopCameraIds.contains(cameraId) || videoStopCameraIds.contains(cameraId)) {
resumeMission.removeAt(resumeIndex);
}
if (!videoStopCameraIds.contains(cameraId)) {
videoStopCameraIds.append(cameraId);
} }
} foundCameraStartStop = true;
break; break;
case MAV_CMD_VIDEO_STOP_CAPTURE: case MAV_CMD_IMAGE_START_CAPTURE:
{ // Only keep the first of these commands that are found
int cameraId = resumeItem->param1(); if (foundCameraStartStop) {
// Video stop only matters to kill all previous video starts resumeMission.removeAt(prefixCommandCount);
if (!videoStopCameraIds.contains(cameraId)) {
videoStopCameraIds.append(cameraId);
} }
resumeMission.removeAt(resumeIndex); if (resumeItem->param3() != 0) {
} // Remove commands which do no trigger by time
resumeMission.removeAt(prefixCommandCount);
}
foundCameraStartStop = true;
break; break;
default: default:
break; break;
} }
resumeIndex--; prefixCommandCount--;
} }
// Send to vehicle // Send to vehicle
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment