Browse Source

Fix resume mission for VTOL not handling takeoff correctly

QGC4.4
DonLakeFlyer 4 years ago committed by Don Gagne
parent
commit
5288ad7767
  1. 10
      src/MissionManager/MissionManager.cc

10
src/MissionManager/MissionManager.cc

@ -98,11 +98,11 @@ void MissionManager::generateResumeMission(int resumeIndex)
resumeIndex = qMax(0, qMin(resumeIndex, _missionItems.count() - 1)); resumeIndex = qMax(0, qMin(resumeIndex, _missionItems.count() - 1));
// Adjust resume index to be a location based command // 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()) { if (!uiInfo || uiInfo->isStandaloneCoordinate() || !uiInfo->specifiesCoordinate()) {
// We have to back up to the last command which the vehicle flies through // We have to back up to the last command which the vehicle flies through
while (--resumeIndex > 0) { 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())) { if (uiInfo && (uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate())) {
// Found it // Found it
break; break;
@ -130,15 +130,15 @@ void MissionManager::generateResumeMission(int resumeIndex)
<< 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
<< MAV_CMD_SET_CAMERA_MODE << MAV_CMD_SET_CAMERA_MODE;
<< MAV_CMD_NAV_TAKEOFF;
bool addHomePosition = _vehicle->firmwarePlugin()->sendHomePositionToVehicle(); bool addHomePosition = _vehicle->firmwarePlugin()->sendHomePositionToVehicle();
int prefixCommandCount = 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())) { 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) { if (i < resumeIndex) {
prefixCommandCount++; prefixCommandCount++;
} }

Loading…
Cancel
Save