MissionController.cc 113 KB
Newer Older
1 2
/****************************************************************************
 *
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
9

10
#include "MissionController.h"
11 12
#include "AppSettings.h"
#include "CorridorScanComplexItem.h"
13
#include "FirmwarePlugin.h"
14
#include "FixedWingLandingComplexItem.h"
15
#include "FlightPathSegment.h"
16
#include "JsonHelper.h"
17
#include "KMLPlanDomDocument.h"
Valentin Platzgummer's avatar
Valentin Platzgummer committed
18
#include "MeasurementComplexItem.h"
19 20
#include "MissionCommandUIInfo.h"
#include "MissionManager.h"
21
#include "MissionSettingsItem.h"
22 23
#include "MultiVehicleManager.h"
#include "ParameterManager.h"
24
#include "PlanMasterController.h"
25 26
#include "PlanViewSettings.h"
#include "QGCApplication.h"
27
#include "QGCCorePlugin.h"
28 29 30 31 32 33
#include "QGCQGeoCoordinate.h"
#include "QGroundControlQmlGlobal.h"
#include "SettingsManager.h"
#include "SimpleMissionItem.h"
#include "StructureScanComplexItem.h"
#include "SurveyComplexItem.h"
34
#include "TakeoffMissionItem.h"
35
#include "VTOLLandingComplexItem.h"
36

37
#define UPDATE_TIMEOUT 5000 ///< How often we check for bounding box changes
38

39
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")
40

41 42 43 44 45 46 47 48 49 50 51 52
const char *MissionController::_settingsGroup = "MissionController";
const char *MissionController::_jsonFileTypeValue = "Mission";
const char *MissionController::_jsonItemsKey = "items";
const char *MissionController::_jsonPlannedHomePositionKey =
    "plannedHomePosition";
const char *MissionController::_jsonFirmwareTypeKey = "firmwareType";
const char *MissionController::_jsonVehicleTypeKey = "vehicleType";
const char *MissionController::_jsonCruiseSpeedKey = "cruiseSpeed";
const char *MissionController::_jsonHoverSpeedKey = "hoverSpeed";
const char *MissionController::_jsonParamsKey = "params";
const char *MissionController::_jsonGlobalPlanAltitudeModeKey =
    "globalPlanAltitudeMode";
53

54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169
// Deprecated V1 format keys
const char *MissionController::_jsonComplexItemsKey = "complexItems";
const char *MissionController::_jsonMavAutopilotKey = "MAV_AUTOPILOT";

const int MissionController::_missionFileVersion = 2;

MissionController::MissionController(PlanMasterController *masterController,
                                     QObject *parent)
    : PlanElementController(masterController, parent),
      _controllerVehicle(masterController->controllerVehicle()),
      _managerVehicle(masterController->managerVehicle()),
      _missionManager(masterController->managerVehicle()->missionManager()),
      _visualItems(new QmlObjectListModel(this)),
      _planViewSettings(
          qgcApp()->toolbox()->settingsManager()->planViewSettings()),
      _appSettings(qgcApp()->toolbox()->settingsManager()->appSettings()) {
  _resetMissionFlightStatus();

  _updateTimer.setSingleShot(true);

  connect(&_updateTimer, &QTimer::timeout, this,
          &MissionController::_updateTimeout);
  connect(_planViewSettings->takeoffItemNotRequired(), &Fact::rawValueChanged,
          this, &MissionController::_takeoffItemNotRequiredChanged);
  connect(this, &MissionController::missionDistanceChanged, this,
          &MissionController::recalcTerrainProfile);

  // The follow is used to compress multiple recalc calls in a row to into a
  // single call.
  connect(this, &MissionController::_recalcMissionFlightStatusSignal, this,
          &MissionController::_recalcMissionFlightStatus, Qt::QueuedConnection);
  connect(this, &MissionController::_recalcFlightPathSegmentsSignal, this,
          &MissionController::_recalcFlightPathSegments, Qt::QueuedConnection);
  qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(
      &MissionController::_recalcMissionFlightStatusSignal));
  qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(
      &MissionController::_recalcFlightPathSegmentsSignal));
  qgcApp()->addCompressedSignal(
      QMetaMethod::fromSignal(&MissionController::recalcTerrainProfile));
}

MissionController::~MissionController() {}

void MissionController::_resetMissionFlightStatus(void) {
  _missionFlightStatus.totalDistance = 0.0;
  _missionFlightStatus.maxTelemetryDistance = 0.0;
  _missionFlightStatus.totalTime = 0.0;
  _missionFlightStatus.hoverTime = 0.0;
  _missionFlightStatus.cruiseTime = 0.0;
  _missionFlightStatus.hoverDistance = 0.0;
  _missionFlightStatus.cruiseDistance = 0.0;
  _missionFlightStatus.cruiseSpeed = _controllerVehicle->defaultCruiseSpeed();
  _missionFlightStatus.hoverSpeed = _controllerVehicle->defaultHoverSpeed();
  _missionFlightStatus.vehicleSpeed =
      _controllerVehicle->multiRotor() || _managerVehicle->vtol()
          ? _missionFlightStatus.hoverSpeed
          : _missionFlightStatus.cruiseSpeed;
  _missionFlightStatus.vehicleYaw = qQNaN();
  _missionFlightStatus.gimbalYaw = qQNaN();
  _missionFlightStatus.gimbalPitch = qQNaN();
  _missionFlightStatus.mAhBattery = 0;
  _missionFlightStatus.hoverAmps = 0;
  _missionFlightStatus.cruiseAmps = 0;
  _missionFlightStatus.ampMinutesAvailable = 0;
  _missionFlightStatus.hoverAmpsTotal = 0;
  _missionFlightStatus.cruiseAmpsTotal = 0;
  _missionFlightStatus.batteryChangePoint = -1;
  _missionFlightStatus.batteriesRequired = -1;
  _missionFlightStatus.vtolMode = _missionContainsVTOLTakeoff
                                      ? QGCMAVLink::VehicleClassMultiRotor
                                      : QGCMAVLink::VehicleClassFixedWing;

  _controllerVehicle->firmwarePlugin()->batteryConsumptionData(
      _controllerVehicle, _missionFlightStatus.mAhBattery,
      _missionFlightStatus.hoverAmps, _missionFlightStatus.cruiseAmps);
  if (_missionFlightStatus.mAhBattery != 0) {
    double batteryPercentRemainingAnnounce =
        qgcApp()
            ->toolbox()
            ->settingsManager()
            ->appSettings()
            ->batteryPercentRemainingAnnounce()
            ->rawValue()
            .toDouble();
    _missionFlightStatus.ampMinutesAvailable =
        static_cast<double>(_missionFlightStatus.mAhBattery) / 1000.0 * 60.0 *
        ((100.0 - batteryPercentRemainingAnnounce) / 100.0);
  }

  emit missionDistanceChanged(_missionFlightStatus.totalDistance);
  emit missionTimeChanged();
  emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
  emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
  emit missionHoverTimeChanged();
  emit missionCruiseTimeChanged();
  emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
  emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
  emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
}

void MissionController::start(bool flyView) {
  qCDebug(MissionControllerLog) << "start flyView" << flyView;

  _managerVehicleChanged(_managerVehicle);
  connect(_masterController, &PlanMasterController::managerVehicleChanged, this,
          &MissionController::_managerVehicleChanged);

  PlanElementController::start(flyView);
  _init();
}

void MissionController::_init(void) {
  // We start with an empty mission
  _addMissionSettings(_visualItems);
  _initAllVisualItems();
}
170

171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246
// Called when new mission items have completed downloading from Vehicle
void MissionController::_newMissionItemsAvailableFromVehicle(
    bool removeAllRequested) {
  qCDebug(MissionControllerLog)
      << "_newMissionItemsAvailableFromVehicle flyView:count" << _flyView
      << _missionManager->missionItems().count();

  // Fly view always reloads on _loadComplete
  // Plan view only reloads if:
  //  - Load was specifically requested
  //  - There is no current Plan
  if (_flyView || removeAllRequested || _itemsRequested || isEmpty()) {
    // Fly Mode (accept if):
    //      - Always accepts new items from the vehicle so Fly view is kept up
    //      to date
    // Edit Mode (accept if):
    //      - Remove all was requested from Fly view (clear mission on flight
    //      end)
    //      - A load from vehicle was manually requested
    //      - The initial automatic load from a vehicle completed and the
    //      current editor is empty

    _deinitAllVisualItems();
    _visualItems->deleteLater();
    _visualItems = nullptr;
    _settingsItem = nullptr;
    _takeoffMissionItem = nullptr;
    _updateContainsItems(); // This will clear containsItems which will be set
                            // again below. This will re-pop Start Mission
                            // confirmation.

    QmlObjectListModel *newControllerMissionItems =
        new QmlObjectListModel(this);
    const QList<MissionItem *> &newMissionItems =
        _missionManager->missionItems();
    qCDebug(MissionControllerLog)
        << "loading from vehicle: count" << newMissionItems.count();

    _missionItemCount = newMissionItems.count();
    emit missionItemCountChanged(_missionItemCount);

    MissionSettingsItem *settingsItem =
        _addMissionSettings(newControllerMissionItems);

    int i = 0;
    if (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() &&
        newMissionItems.count() != 0) {
      // First item is fake home position
      MissionItem *fakeHomeItem = newMissionItems[0];
      if (fakeHomeItem->coordinate().latitude() != 0 ||
          fakeHomeItem->coordinate().longitude() != 0) {
        settingsItem->setInitialHomePosition(fakeHomeItem->coordinate());
      }
      i = 1;
    }

    for (; i < newMissionItems.count(); i++) {
      const MissionItem *missionItem = newMissionItems[i];
      SimpleMissionItem *simpleItem = new SimpleMissionItem(
          _masterController, _flyView, *missionItem, this);
      if (TakeoffMissionItem::isTakeoffCommand(
              static_cast<MAV_CMD>(simpleItem->command()))) {
        // This needs to be a TakeoffMissionItem
        _takeoffMissionItem = new TakeoffMissionItem(
            *missionItem, _masterController, _flyView, settingsItem, this);
        simpleItem->deleteLater();
        simpleItem = _takeoffMissionItem;
      }
      newControllerMissionItems->append(simpleItem);
    }

    _visualItems = newControllerMissionItems;
    _settingsItem = settingsItem;

    MissionController::_scanForAdditionalSettings(_visualItems,
                                                  _masterController);
247

248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287
    _initAllVisualItems();
    _updateContainsItems();
    emit newItemsFromVehicle();
  }
  _itemsRequested = false;
}

void MissionController::loadFromVehicle(void) {
  if (_masterController->offline()) {
    qCWarning(MissionControllerLog)
        << "MissionControllerLog::loadFromVehicle called while offline";
  } else if (syncInProgress()) {
    qCWarning(MissionControllerLog)
        << "MissionControllerLog::loadFromVehicle called while syncInProgress";
  } else {
    _itemsRequested = true;
    _managerVehicle->missionManager()->loadFromVehicle();
  }
}

void MissionController::sendToVehicle(void) {
  if (_masterController->offline()) {
    qCWarning(MissionControllerLog)
        << "MissionControllerLog::sendToVehicle called while offline";
  } else if (syncInProgress()) {
    qCWarning(MissionControllerLog)
        << "MissionControllerLog::sendToVehicle called while syncInProgress";
  } else {
    qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
    if (_visualItems->count() == 1) {
      // This prevents us from sending a possibly bogus home position to the
      // vehicle
      QmlObjectListModel emptyModel;
      sendItemsToVehicle(_managerVehicle, &emptyModel);
    } else {
      sendItemsToVehicle(_managerVehicle, _visualItems);
    }
    setDirty(false);
  }
}
288

289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530
/// Converts from visual items to MissionItems
///     @param missionItemParent QObject parent for newly allocated MissionItems
/// @return true: Mission end action was added to end of list
bool MissionController::_convertToMissionItems(
    QmlObjectListModel *visualMissionItems,
    QList<MissionItem *> &rgMissionItems, QObject *missionItemParent) {
  if (visualMissionItems->count() == 0) {
    return false;
  }

  bool endActionSet = false;
  int lastSeqNum = 0;

  for (int i = 0; i < visualMissionItems->count(); i++) {
    VisualMissionItem *visualItem =
        qobject_cast<VisualMissionItem *>(visualMissionItems->get(i));

    lastSeqNum = visualItem->lastSequenceNumber();
    visualItem->appendMissionItems(rgMissionItems, missionItemParent);

    qCDebug(MissionControllerLog)
        << "_convertToMissionItems seqNum:lastSeqNum:command"
        << visualItem->sequenceNumber() << lastSeqNum
        << visualItem->commandName();
  }

  // Mission settings has a special case for end mission action
  MissionSettingsItem *settingsItem =
      visualMissionItems->value<MissionSettingsItem *>(0);
  if (settingsItem) {
    endActionSet = settingsItem->addMissionEndAction(
        rgMissionItems, lastSeqNum + 1, missionItemParent);
  }

  return endActionSet;
}

void MissionController::addMissionToKML(KMLPlanDomDocument &planKML) {
  QObject *deleteParent = new QObject();
  QList<MissionItem *> rgMissionItems;

  _convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
  planKML.addMission(_controllerVehicle, _visualItems, rgMissionItems);
  deleteParent->deleteLater();
}

void MissionController::sendItemsToVehicle(
    Vehicle *vehicle, QmlObjectListModel *visualMissionItems) {
  if (vehicle) {
    QList<MissionItem *> rgMissionItems;

    _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);

    // PlanManager takes control of MissionItems so no need to delete
    vehicle->missionManager()->writeMissionItems(rgMissionItems);
  }
}

int MissionController::_nextSequenceNumber(void) {
  if (_visualItems->count() == 0) {
    qWarning() << "Internal error: Empty visual item list";
    return 0;
  } else {
    VisualMissionItem *lastItem =
        _visualItems->value<VisualMissionItem *>(_visualItems->count() - 1);
    return lastItem->lastSequenceNumber() + 1;
  }
}

VisualMissionItem *MissionController::_insertSimpleMissionItemWorker(
    QGeoCoordinate coordinate, MAV_CMD command, int visualItemIndex,
    bool makeCurrentItem) {
  int sequenceNumber = _nextSequenceNumber();
  SimpleMissionItem *newItem = new SimpleMissionItem(
      _masterController, _flyView, false /* forLoad */, this);
  newItem->setSequenceNumber(sequenceNumber);
  newItem->setCoordinate(coordinate);
  newItem->setCommand(command);
  _initVisualItem(newItem);

  if (newItem->specifiesAltitude()) {
    if (!qgcApp()->toolbox()->missionCommandTree()->isLandCommand(command)) {
      double prevAltitude;
      int prevAltitudeMode;

      if (_findPreviousAltitude(visualItemIndex, &prevAltitude,
                                &prevAltitudeMode)) {
        newItem->altitude()->setRawValue(prevAltitude);
        if (globalAltitudeMode() == QGroundControlQmlGlobal::AltitudeModeNone) {
          // We are in mixed altitude modes, so copy from previous. Otherwise
          // alt mode will be set from global setting.
          newItem->setAltitudeMode(
              static_cast<QGroundControlQmlGlobal::AltitudeMode>(
                  prevAltitudeMode));
        }
      }
    }
  }
  if (visualItemIndex == -1) {
    _visualItems->append(newItem);
  } else {
    _visualItems->insert(visualItemIndex, newItem);
  }

  // We send the click coordinate through here to be able to set the planned
  // home position from the user click location if needed
  _recalcAllWithCoordinate(coordinate);

  if (makeCurrentItem) {
    setCurrentPlanViewSeqNum(newItem->sequenceNumber(), true);
  }

  _firstItemAdded();

  return newItem;
}

VisualMissionItem *MissionController::insertSimpleMissionItem(
    QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem) {
  return _insertSimpleMissionItemWorker(coordinate, MAV_CMD_NAV_WAYPOINT,
                                        visualItemIndex, makeCurrentItem);
}

VisualMissionItem *MissionController::insertTakeoffItem(
    QGeoCoordinate /*coordinate*/, int visualItemIndex, bool makeCurrentItem) {
  int sequenceNumber = _nextSequenceNumber();
  _takeoffMissionItem = new TakeoffMissionItem(
      _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF
                                 : MAV_CMD_NAV_TAKEOFF,
      _masterController, _flyView, _settingsItem, this);
  _takeoffMissionItem->setSequenceNumber(sequenceNumber);
  _initVisualItem(_takeoffMissionItem);

  if (_takeoffMissionItem->specifiesAltitude()) {
    double prevAltitude;
    int prevAltitudeMode;

    if (_findPreviousAltitude(visualItemIndex, &prevAltitude,
                              &prevAltitudeMode)) {
      _takeoffMissionItem->altitude()->setRawValue(prevAltitude);
      _takeoffMissionItem->setAltitudeMode(
          static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
    }
  }
  if (visualItemIndex == -1) {
    _visualItems->append(_takeoffMissionItem);
  } else {
    _visualItems->insert(visualItemIndex, _takeoffMissionItem);
  }

  _recalcAll();

  if (makeCurrentItem) {
    setCurrentPlanViewSeqNum(_takeoffMissionItem->sequenceNumber(), true);
  }

  _firstItemAdded();

  return _takeoffMissionItem;
}

VisualMissionItem *MissionController::insertLandItem(QGeoCoordinate coordinate,
                                                     int visualItemIndex,
                                                     bool makeCurrentItem) {
  if (_controllerVehicle->fixedWing()) {
    FixedWingLandingComplexItem *fwLanding =
        qobject_cast<FixedWingLandingComplexItem *>(insertComplexMissionItem(
            FixedWingLandingComplexItem::name, coordinate, visualItemIndex,
            makeCurrentItem));
    return fwLanding;
  } else if (_controllerVehicle->vtol()) {
    VTOLLandingComplexItem *vtolLanding =
        qobject_cast<VTOLLandingComplexItem *>(
            insertComplexMissionItem(VTOLLandingComplexItem::name, coordinate,
                                     visualItemIndex, makeCurrentItem));
    return vtolLanding;
  } else {
    return _insertSimpleMissionItemWorker(coordinate,
                                          _controllerVehicle->vtol()
                                              ? MAV_CMD_NAV_VTOL_LAND
                                              : MAV_CMD_NAV_RETURN_TO_LAUNCH,
                                          visualItemIndex, makeCurrentItem);
  }
}

VisualMissionItem *MissionController::insertROIMissionItem(
    QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem) {
  SimpleMissionItem *simpleItem = qobject_cast<SimpleMissionItem *>(
      _insertSimpleMissionItemWorker(coordinate, MAV_CMD_DO_SET_ROI_LOCATION,
                                     visualItemIndex, makeCurrentItem));

  if (!_controllerVehicle->firmwarePlugin()
           ->supportedMissionCommands(QGCMAVLink::VehicleClassGeneric)
           .contains(MAV_CMD_DO_SET_ROI_LOCATION)) {
    simpleItem->setCommand(MAV_CMD_DO_SET_ROI);
    simpleItem->missionItem().setParam1(MAV_ROI_LOCATION);
  }
  _recalcROISpecialVisuals();
  return simpleItem;
}

VisualMissionItem *
MissionController::insertCancelROIMissionItem(int visualItemIndex,
                                              bool makeCurrentItem) {
  SimpleMissionItem *simpleItem = qobject_cast<SimpleMissionItem *>(
      _insertSimpleMissionItemWorker(QGeoCoordinate(), MAV_CMD_DO_SET_ROI_NONE,
                                     visualItemIndex, makeCurrentItem));

  if (!_controllerVehicle->firmwarePlugin()
           ->supportedMissionCommands(QGCMAVLink::VehicleClassGeneric)
           .contains(MAV_CMD_DO_SET_ROI_NONE)) {
    simpleItem->setCommand(MAV_CMD_DO_SET_ROI);
    simpleItem->missionItem().setParam1(MAV_ROI_NONE);
  }
  _recalcROISpecialVisuals();
  return simpleItem;
}

VisualMissionItem *MissionController::insertComplexMissionItem(
    QString itemName, QGeoCoordinate mapCenterCoordinate, int visualItemIndex,
    bool makeCurrentItem) {
  ComplexMissionItem *newItem = nullptr;

  if (itemName == SurveyComplexItem::name) {
    newItem = new SurveyComplexItem(_masterController, _flyView,
                                    QString() /* kmlFile */,
                                    _visualItems /* parent */);
    newItem->setCoordinate(mapCenterCoordinate);
  } else if (itemName == FixedWingLandingComplexItem::name) {
    newItem = new FixedWingLandingComplexItem(_masterController, _flyView,
                                              _visualItems /* parent */);
  } else if (itemName == VTOLLandingComplexItem::name) {
    newItem = new VTOLLandingComplexItem(_masterController, _flyView,
                                         _visualItems /* parent */);
  } else if (itemName == StructureScanComplexItem::name) {
    newItem = new StructureScanComplexItem(_masterController, _flyView,
                                           QString() /* kmlFile */,
                                           _visualItems /* parent */);
  } else if (itemName == CorridorScanComplexItem::name) {
    newItem = new CorridorScanComplexItem(_masterController, _flyView,
                                          QString() /* kmlFile */,
                                          _visualItems /* parent */);
Valentin Platzgummer's avatar
Valentin Platzgummer committed
531 532 533 534
  } else if (itemName == MeasurementComplexItem::name) {
    newItem = new MeasurementComplexItem(_masterController, _flyView,
                                         QString() /* kmlFile */,
                                         _visualItems /* parent */);
535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577
  } else {
    qWarning() << "Internal error: Unknown complex item:" << itemName;
    return nullptr;
  }

  _insertComplexMissionItemWorker(mapCenterCoordinate, newItem, visualItemIndex,
                                  makeCurrentItem);

  return newItem;
}

VisualMissionItem *MissionController::insertComplexMissionItemFromKMLOrSHP(
    QString itemName, QString file, int visualItemIndex, bool makeCurrentItem) {
  ComplexMissionItem *newItem = nullptr;

  if (itemName == SurveyComplexItem::name) {
    newItem =
        new SurveyComplexItem(_masterController, _flyView, file, _visualItems);
  } else if (itemName == StructureScanComplexItem::name) {
    newItem = new StructureScanComplexItem(_masterController, _flyView, file,
                                           _visualItems);
  } else if (itemName == CorridorScanComplexItem::name) {
    newItem = new CorridorScanComplexItem(_masterController, _flyView, file,
                                          _visualItems);
  } else {
    qWarning() << "Internal error: Unknown complex item:" << itemName;
    return nullptr;
  }

  _insertComplexMissionItemWorker(QGeoCoordinate(), newItem, visualItemIndex,
                                  makeCurrentItem);

  return newItem;
}

void MissionController::_insertComplexMissionItemWorker(
    const QGeoCoordinate &mapCenterCoordinate, ComplexMissionItem *complexItem,
    int visualItemIndex, bool makeCurrentItem) {
  int sequenceNumber = _nextSequenceNumber();
  bool surveyStyleItem =
      qobject_cast<SurveyComplexItem *>(complexItem) ||
      qobject_cast<CorridorScanComplexItem *>(complexItem) ||
      qobject_cast<StructureScanComplexItem *>(complexItem) ||
Valentin Platzgummer's avatar
Valentin Platzgummer committed
578
      qobject_cast<MeasurementComplexItem *>(complexItem);
579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640

  if (surveyStyleItem) {
    bool rollSupported = false;
    bool pitchSupported = false;
    bool yawSupported = false;

    // If the vehicle is known to have a gimbal then we automatically point the
    // gimbal straight down if not already set

    MissionSettingsItem *settingsItem =
        _visualItems->value<MissionSettingsItem *>(0);
    CameraSection *cameraSection = settingsItem->cameraSection();

    // Set camera to photo mode (leave alone if user already specified)
    if (cameraSection->cameraModeSupported() &&
        !cameraSection->specifyCameraMode()) {
      cameraSection->setSpecifyCameraMode(true);
      cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
    }

    // Point gimbal straight down
    if (_controllerVehicle->firmwarePlugin()->hasGimbal(
            _controllerVehicle, rollSupported, pitchSupported, yawSupported) &&
        pitchSupported) {
      // If the user already specified a gimbal angle leave it alone
      if (!cameraSection->specifyGimbal()) {
        cameraSection->setSpecifyGimbal(true);
        cameraSection->gimbalPitch()->setRawValue(-90.0);
      }
    }
  }

  complexItem->setSequenceNumber(sequenceNumber);
  complexItem->setWizardMode(true);
  _initVisualItem(complexItem);

  if (visualItemIndex == -1) {
    _visualItems->append(complexItem);
  } else {
    _visualItems->insert(visualItemIndex, complexItem);
  }

  //-- Keep track of bounding box changes in complex items
  if (!complexItem->isSimpleItem()) {
    connect(complexItem, &ComplexMissionItem::boundingCubeChanged, this,
            &MissionController::_complexBoundingBoxChanged);
  }
  _recalcAllWithCoordinate(mapCenterCoordinate);

  if (makeCurrentItem) {
    setCurrentPlanViewSeqNum(complexItem->sequenceNumber(), true);
  }
  _firstItemAdded();
}

void MissionController::removeVisualItem(int viIndex) {
  if (viIndex <= 0 || viIndex >= _visualItems->count()) {
    qWarning() << "MissionController::removeVisualItem called with bad index - "
                  "count:index"
               << _visualItems->count() << viIndex;
    return;
  }
641

642 643 644
  bool removeSurveyStyle =
      _visualItems->value<SurveyComplexItem *>(viIndex) ||
      _visualItems->value<CorridorScanComplexItem *>(viIndex) ||
Valentin Platzgummer's avatar
Valentin Platzgummer committed
645
      _visualItems->value<MeasurementComplexItem *>(viIndex);
646 647
  VisualMissionItem *item =
      qobject_cast<VisualMissionItem *>(_visualItems->removeAt(viIndex));
648

649 650 651
  if (item == _takeoffMissionItem) {
    _takeoffMissionItem = nullptr;
  }
652

653 654
  _deinitVisualItem(item);
  item->deleteLater();
655

656 657 658 659 660 661
  if (removeSurveyStyle) {
    // Determine if the mission still has another survey style item in it
    bool foundSurvey = false;
    for (int i = 1; i < _visualItems->count(); i++) {
      if (_visualItems->value<SurveyComplexItem *>(i) ||
          _visualItems->value<CorridorScanComplexItem *>(i) ||
Valentin Platzgummer's avatar
Valentin Platzgummer committed
662
          _visualItems->value<MeasurementComplexItem *>(i)) {
663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767
        foundSurvey = true;
        break;
      }
    }

    // If there is no longer a survey item in the mission remove added commands
    if (!foundSurvey) {
      bool rollSupported = false;
      bool pitchSupported = false;
      bool yawSupported = false;
      CameraSection *cameraSection = _settingsItem->cameraSection();
      if (_controllerVehicle->firmwarePlugin()->hasGimbal(
              _controllerVehicle, rollSupported, pitchSupported,
              yawSupported) &&
          pitchSupported) {
        if (cameraSection->specifyGimbal() &&
            cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 &&
            cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
          cameraSection->setSpecifyGimbal(false);
        }
      }
      if (cameraSection->cameraModeSupported() &&
          cameraSection->specifyCameraMode() &&
          cameraSection->cameraMode()->rawValue().toInt() == 0) {
        cameraSection->setSpecifyCameraMode(false);
      }
    }
  }

  _recalcAll();

  // Adjust current item
  int newVIIndex;
  if (viIndex >= _visualItems->count()) {
    newVIIndex = _visualItems->count() - 1;
  } else {
    newVIIndex = viIndex;
  }
  setCurrentPlanViewSeqNum(
      _visualItems->value<VisualMissionItem *>(newVIIndex)->sequenceNumber(),
      true);

  setDirty(true);

  if (_visualItems->count() == 1) {
    _allItemsRemoved();
  }
}

void MissionController::removeAll(void) {
  if (_visualItems) {
    _deinitAllVisualItems();
    _visualItems->clearAndDeleteContents();
    _visualItems->deleteLater();
    _settingsItem = nullptr;
    _takeoffMissionItem = nullptr;
    _visualItems = new QmlObjectListModel(this);
    _addMissionSettings(_visualItems);
    _initAllVisualItems();
    setDirty(true);
    _resetMissionFlightStatus();
    _allItemsRemoved();
  }
}

bool MissionController::_loadJsonMissionFileV1(const QJsonObject &json,
                                               QmlObjectListModel *visualItems,
                                               QString &errorString) {
  // Validate root object keys
  QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
      {_jsonPlannedHomePositionKey, QJsonValue::Object, true},
      {_jsonItemsKey, QJsonValue::Array, true},
      {_jsonMavAutopilotKey, QJsonValue::Double, true},
      {_jsonComplexItemsKey, QJsonValue::Array, true},
  };
  if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
    return false;
  }

  setGlobalAltitudeMode(
      QGroundControlQmlGlobal::AltitudeModeNone); // Mixed mode

  // Read complex items
  QList<SurveyComplexItem *> surveyItems;
  QJsonArray complexArray(json[_jsonComplexItemsKey].toArray());
  qCDebug(MissionControllerLog)
      << "Json load: complex item count" << complexArray.count();
  for (int i = 0; i < complexArray.count(); i++) {
    const QJsonValue &itemValue = complexArray[i];

    if (!itemValue.isObject()) {
      errorString = QStringLiteral("Mission item is not an object");
      return false;
    }

    SurveyComplexItem *item = new SurveyComplexItem(_masterController, _flyView,
                                                    QString() /* kmlFile */,
                                                    visualItems /* parent */);
    const QJsonObject itemObject = itemValue.toObject();
    if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
      surveyItems.append(item);
    } else {
      return false;
    }
  }
768

769
  // Read simple items, interspersing complex items into the full list
770

771 772 773 774
  int nextSimpleItemIndex = 0;
  int nextComplexItemIndex = 0;
  int nextSequenceNumber = 1; // Start with 1 since home is in 0
  QJsonArray itemArray(json[_jsonItemsKey].toArray());
775

776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064
  MissionSettingsItem *settingsItem = _addMissionSettings(visualItems);
  if (json.contains(_jsonPlannedHomePositionKey)) {
    SimpleMissionItem *item = new SimpleMissionItem(
        _masterController, _flyView, true /* forLoad */, visualItems);
    if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0,
                   errorString)) {
      settingsItem->setInitialHomePositionFromUser(item->coordinate());
      item->deleteLater();
    } else {
      return false;
    }
  }

  qCDebug(MissionControllerLog)
      << "Json load: simple item loop start simpleItemCount:ComplexItemCount"
      << itemArray.count() << surveyItems.count();
  do {
    qCDebug(MissionControllerLog)
        << "Json load: simple item loop "
           "nextSimpleItemIndex:nextComplexItemIndex:nextSequenceNumber"
        << nextSimpleItemIndex << nextComplexItemIndex << nextSequenceNumber;

    // If there is a complex item that should be next in sequence add it in
    if (nextComplexItemIndex < surveyItems.count()) {
      SurveyComplexItem *complexItem = surveyItems[nextComplexItemIndex];

      if (complexItem->sequenceNumber() == nextSequenceNumber) {
        qCDebug(MissionControllerLog)
            << "Json load: injecting complex item "
               "expectedSequence:actualSequence:"
            << nextSequenceNumber << complexItem->sequenceNumber();
        visualItems->append(complexItem);
        nextSequenceNumber = complexItem->lastSequenceNumber() + 1;
        nextComplexItemIndex++;
        continue;
      }
    }

    // Add the next available simple item
    if (nextSimpleItemIndex < itemArray.count()) {
      const QJsonValue &itemValue = itemArray[nextSimpleItemIndex++];

      if (!itemValue.isObject()) {
        errorString = QStringLiteral("Mission item is not an object");
        return false;
      }

      const QJsonObject itemObject = itemValue.toObject();
      SimpleMissionItem *item = new SimpleMissionItem(
          _masterController, _flyView, true /* forLoad */, visualItems);
      if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
        if (TakeoffMissionItem::isTakeoffCommand(item->mavCommand())) {
          // This needs to be a TakeoffMissionItem
          TakeoffMissionItem *takeoffItem =
              new TakeoffMissionItem(_masterController, _flyView, settingsItem,
                                     true /* forLoad */, visualItems);
          takeoffItem->load(itemObject, itemObject["id"].toInt(), errorString);
          item->deleteLater();
          item = takeoffItem;
        }
        qCDebug(MissionControllerLog)
            << "Json load: adding simple item expectedSequence:actualSequence"
            << nextSequenceNumber << item->sequenceNumber();
        nextSequenceNumber = item->lastSequenceNumber() + 1;
        visualItems->append(item);
      } else {
        return false;
      }
    }
  } while (nextSimpleItemIndex < itemArray.count() ||
           nextComplexItemIndex < surveyItems.count());

  return true;
}

bool MissionController::_loadJsonMissionFileV2(const QJsonObject &json,
                                               QmlObjectListModel *visualItems,
                                               QString &errorString) {
  // Validate root object keys
  QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
      {_jsonPlannedHomePositionKey, QJsonValue::Array, true},
      {_jsonItemsKey, QJsonValue::Array, true},
      {_jsonFirmwareTypeKey, QJsonValue::Double, true},
      {_jsonVehicleTypeKey, QJsonValue::Double, false},
      {_jsonCruiseSpeedKey, QJsonValue::Double, false},
      {_jsonHoverSpeedKey, QJsonValue::Double, false},
      {_jsonGlobalPlanAltitudeModeKey, QJsonValue::Double, false},
  };
  if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
    return false;
  }

  setGlobalAltitudeMode(
      QGroundControlQmlGlobal::AltitudeModeNone); // Mixed mode

  qCDebug(MissionControllerLog)
      << "MissionController::_loadJsonMissionFileV2 itemCount:"
      << json[_jsonItemsKey].toArray().count();

  AppSettings *appSettings =
      qgcApp()->toolbox()->settingsManager()->appSettings();

  // Get the firmware/vehicle type from the plan file
  MAV_AUTOPILOT planFileFirmwareType =
      static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt());
  MAV_TYPE planFileVehicleType =
      static_cast<MAV_TYPE>(QGCMAVLink::vehicleClassToMavType(
          appSettings->offlineEditingVehicleClass()->rawValue().toInt()));
  if (json.contains(_jsonVehicleTypeKey)) {
    planFileVehicleType =
        static_cast<MAV_TYPE>(json[_jsonVehicleTypeKey].toInt());
  }

  // Update firmware/vehicle offline settings if we aren't connect to a vehicle
  if (_masterController->offline()) {
    appSettings->offlineEditingFirmwareClass()->setRawValue(
        QGCMAVLink::firmwareClass(
            static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt())));
    if (json.contains(_jsonVehicleTypeKey)) {
      appSettings->offlineEditingVehicleClass()->setRawValue(
          QGCMAVLink::vehicleClass(planFileVehicleType));
    }
  }

  // The controller vehicle always tracks the Plan file firmware/vehicle types
  // so update it
  _controllerVehicle->stopTrackingFirmwareVehicleTypeChanges();
  _controllerVehicle->_offlineFirmwareTypeSettingChanged(planFileFirmwareType);
  _controllerVehicle->_offlineVehicleTypeSettingChanged(planFileVehicleType);

  if (json.contains(_jsonCruiseSpeedKey)) {
    appSettings->offlineEditingCruiseSpeed()->setRawValue(
        json[_jsonCruiseSpeedKey].toDouble());
  }
  if (json.contains(_jsonHoverSpeedKey)) {
    appSettings->offlineEditingHoverSpeed()->setRawValue(
        json[_jsonHoverSpeedKey].toDouble());
  }
  if (json.contains(_jsonGlobalPlanAltitudeModeKey)) {
    setGlobalAltitudeMode(json[_jsonGlobalPlanAltitudeModeKey]
                              .toVariant()
                              .value<QGroundControlQmlGlobal::AltitudeMode>());
  }

  QGeoCoordinate homeCoordinate;
  if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey],
                                     true /* altitudeRequired */,
                                     homeCoordinate, errorString)) {
    return false;
  }
  MissionSettingsItem *settingsItem =
      new MissionSettingsItem(_masterController, _flyView, visualItems);
  settingsItem->setCoordinate(homeCoordinate);
  visualItems->insert(0, settingsItem);
  qCDebug(MissionControllerLog) << "plannedHomePosition" << homeCoordinate;

  // Read mission items

  int nextSequenceNumber = 1; // Start with 1 since home is in 0
  const QJsonArray rgMissionItems(json[_jsonItemsKey].toArray());
  for (int i = 0; i < rgMissionItems.count(); i++) {
    // Convert to QJsonObject
    const QJsonValue &itemValue = rgMissionItems[i];
    if (!itemValue.isObject()) {
      errorString = tr("Mission item %1 is not an object").arg(i);
      return false;
    }
    const QJsonObject itemObject = itemValue.toObject();

    // Load item based on type

    QList<JsonHelper::KeyValidateInfo> itemKeyInfoList = {
        {VisualMissionItem::jsonTypeKey, QJsonValue::String, true},
    };
    if (!JsonHelper::validateKeys(itemObject, itemKeyInfoList, errorString)) {
      return false;
    }
    QString itemType = itemObject[VisualMissionItem::jsonTypeKey].toString();

    if (itemType == VisualMissionItem::jsonTypeSimpleItemValue) {
      SimpleMissionItem *simpleItem = new SimpleMissionItem(
          _masterController, _flyView, true /* forLoad */, visualItems);
      if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
        if (TakeoffMissionItem::isTakeoffCommand(
                static_cast<MAV_CMD>(simpleItem->command()))) {
          // This needs to be a TakeoffMissionItem
          TakeoffMissionItem *takeoffItem =
              new TakeoffMissionItem(_masterController, _flyView, settingsItem,
                                     true /* forLoad */, this);
          takeoffItem->load(itemObject, nextSequenceNumber, errorString);
          simpleItem->deleteLater();
          simpleItem = takeoffItem;
        }
        qCDebug(MissionControllerLog)
            << "Loading simple item: nextSequenceNumber:command"
            << nextSequenceNumber << simpleItem->command();
        nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
        visualItems->append(simpleItem);
      } else {
        return false;
      }
    } else if (itemType == VisualMissionItem::jsonTypeComplexItemValue) {
      QList<JsonHelper::KeyValidateInfo> complexItemKeyInfoList = {
          {ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String,
           true},
      };
      if (!JsonHelper::validateKeys(itemObject, complexItemKeyInfoList,
                                    errorString)) {
        return false;
      }
      QString complexItemType =
          itemObject[ComplexMissionItem::jsonComplexItemTypeKey].toString();

      if (complexItemType == SurveyComplexItem::jsonComplexItemTypeValue) {
        qCDebug(MissionControllerLog)
            << "Loading Survey: nextSequenceNumber" << nextSequenceNumber;
        SurveyComplexItem *surveyItem = new SurveyComplexItem(
            _masterController, _flyView, QString() /* kmlFile */, visualItems);
        if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
          return false;
        }
        nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
        qCDebug(MissionControllerLog)
            << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
        visualItems->append(surveyItem);
      } else if (complexItemType ==
                 FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
        qCDebug(MissionControllerLog)
            << "Loading Fixed Wing Landing Pattern: nextSequenceNumber"
            << nextSequenceNumber;
        FixedWingLandingComplexItem *landingItem =
            new FixedWingLandingComplexItem(_masterController, _flyView,
                                            visualItems);
        if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
          return false;
        }
        nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
        qCDebug(MissionControllerLog)
            << "FW Landing Pattern load complete: nextSequenceNumber"
            << nextSequenceNumber;
        visualItems->append(landingItem);
      } else if (complexItemType ==
                 VTOLLandingComplexItem::jsonComplexItemTypeValue) {
        qCDebug(MissionControllerLog)
            << "Loading VTOL Landing Pattern: nextSequenceNumber"
            << nextSequenceNumber;
        VTOLLandingComplexItem *landingItem = new VTOLLandingComplexItem(
            _masterController, _flyView, visualItems);
        if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
          return false;
        }
        nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
        qCDebug(MissionControllerLog)
            << "VTOL Landing Pattern load complete: nextSequenceNumber"
            << nextSequenceNumber;
        visualItems->append(landingItem);
      } else if (complexItemType ==
                 StructureScanComplexItem::jsonComplexItemTypeValue) {
        qCDebug(MissionControllerLog)
            << "Loading Structure Scan: nextSequenceNumber"
            << nextSequenceNumber;
        StructureScanComplexItem *structureItem = new StructureScanComplexItem(
            _masterController, _flyView, QString() /* kmlFile */, visualItems);
        if (!structureItem->load(itemObject, nextSequenceNumber++,
                                 errorString)) {
          return false;
        }
        nextSequenceNumber = structureItem->lastSequenceNumber() + 1;
        qCDebug(MissionControllerLog)
            << "Structure Scan load complete: nextSequenceNumber"
            << nextSequenceNumber;
        visualItems->append(structureItem);
      } else if (complexItemType ==
                 CorridorScanComplexItem::jsonComplexItemTypeValue) {
        qCDebug(MissionControllerLog)
            << "Loading Corridor Scan: nextSequenceNumber"
            << nextSequenceNumber;
        CorridorScanComplexItem *corridorItem = new CorridorScanComplexItem(
            _masterController, _flyView, QString() /* kmlFile */, visualItems);
        if (!corridorItem->load(itemObject, nextSequenceNumber++,
                                errorString)) {
          return false;
        }
        nextSequenceNumber = corridorItem->lastSequenceNumber() + 1;
        qCDebug(MissionControllerLog)
            << "Corridor Scan load complete: nextSequenceNumber"
            << nextSequenceNumber;
        visualItems->append(corridorItem);
      } else if (complexItemType ==
Valentin Platzgummer's avatar
Valentin Platzgummer committed
1065
                 MeasurementComplexItem::jsonComplexItemTypeValue) {
1066
        qCDebug(MissionControllerLog)
Valentin Platzgummer's avatar
Valentin Platzgummer committed
1067
            << "Loading Measurement Complex Item: nextSequenceNumber"
1068
            << nextSequenceNumber;
Valentin Platzgummer's avatar
Valentin Platzgummer committed
1069
        MeasurementComplexItem *survey = new MeasurementComplexItem(
1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105
            _masterController, _flyView, QString() /* kmlFile */, visualItems);
        if (!survey->load(itemObject, nextSequenceNumber++, errorString)) {
          return false;
        }
        nextSequenceNumber = survey->lastSequenceNumber() + 1;
        qCDebug(MissionControllerLog)
            << "Ciruclar Survey load complete: nextSequenceNumber"
            << nextSequenceNumber;
        visualItems->append(survey);
      } else {
        errorString =
            tr("Unsupported complex item type: %1").arg(complexItemType);
      }
    } else {
      errorString = tr("Unknown item type: %1").arg(itemType);
      return false;
    }
  }

  // Fix up the DO_JUMP commands jump sequence number by finding the item with
  // the matching doJumpId
  for (int i = 0; i < visualItems->count(); i++) {
    if (visualItems->value<VisualMissionItem *>(i)->isSimpleItem()) {
      SimpleMissionItem *doJumpItem =
          visualItems->value<SimpleMissionItem *>(i);
      if (doJumpItem->command() == MAV_CMD_DO_JUMP) {
        bool found = false;
        int findDoJumpId = static_cast<int>(doJumpItem->missionItem().param1());
        for (int j = 0; j < visualItems->count(); j++) {
          if (visualItems->value<VisualMissionItem *>(j)->isSimpleItem()) {
            SimpleMissionItem *targetItem =
                visualItems->value<SimpleMissionItem *>(j);
            if (targetItem->missionItem().doJumpId() == findDoJumpId) {
              doJumpItem->missionItem().setParam1(targetItem->sequenceNumber());
              found = true;
              break;
1106
            }
1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232
          }
        }
        if (!found) {
          errorString = tr("Could not find doJumpId: %1").arg(findDoJumpId);
          return false;
        }
      }
    }
  }

  return true;
}

bool MissionController::_loadItemsFromJson(const QJsonObject &json,
                                           QmlObjectListModel *visualItems,
                                           QString &errorString) {
  // V1 file format has no file type key and version key is string. Convert to
  // new format.
  if (!json.contains(JsonHelper::jsonFileTypeKey)) {
    json[JsonHelper::jsonFileTypeKey] = _jsonFileTypeValue;
  }

  int fileVersion;
  JsonHelper::validateExternalQGCJsonFile(
      json,
      _jsonFileTypeValue, // expected file type
      1,                  // minimum supported version
      2,                  // maximum supported version
      fileVersion, errorString);

  if (fileVersion == 1) {
    return _loadJsonMissionFileV1(json, visualItems, errorString);
  } else {
    return _loadJsonMissionFileV2(json, visualItems, errorString);
  }
}

bool MissionController::_loadTextMissionFile(QTextStream &stream,
                                             QmlObjectListModel *visualItems,
                                             QString &errorString) {
  bool firstItem = true;
  bool plannedHomePositionInFile = false;

  QString firstLine = stream.readLine();
  const QStringList &version = firstLine.split(" ");

  bool versionOk = false;
  if (version.size() == 3 && version[0] == "QGC" && version[1] == "WPL") {
    if (version[2] == "110") {
      // ArduPilot file, planned home position is already in position 0
      versionOk = true;
      plannedHomePositionInFile = true;
    } else if (version[2] == "120") {
      // Old QGC file, no planned home position
      versionOk = true;
      plannedHomePositionInFile = false;
    }
  }

  if (versionOk) {
    MissionSettingsItem *settingsItem = _addMissionSettings(visualItems);

    while (!stream.atEnd()) {
      SimpleMissionItem *item = new SimpleMissionItem(
          _masterController, _flyView, true /* forLoad */, visualItems);
      if (item->load(stream)) {
        if (firstItem && plannedHomePositionInFile) {
          settingsItem->setInitialHomePositionFromUser(item->coordinate());
        } else {
          if (TakeoffMissionItem::isTakeoffCommand(
                  static_cast<MAV_CMD>(item->command()))) {
            // This needs to be a TakeoffMissionItem
            TakeoffMissionItem *takeoffItem = new TakeoffMissionItem(
                _masterController, _flyView, settingsItem, true /* forLoad */,
                visualItems);
            takeoffItem->load(stream);
            item->deleteLater();
            item = takeoffItem;
          }
          visualItems->append(item);
        }
        firstItem = false;
      } else {
        errorString = tr("The mission file is corrupted.");
        return false;
      }
    }
  } else {
    errorString =
        tr("The mission file is not compatible with this version of %1.")
            .arg(qgcApp()->applicationName());
    return false;
  }

  if (!plannedHomePositionInFile) {
    // Update sequence numbers in DO_JUMP commands to take into account added
    // home position in index 0
    for (int i = 1; i < visualItems->count(); i++) {
      SimpleMissionItem *item =
          qobject_cast<SimpleMissionItem *>(visualItems->get(i));
      if (item && item->command() == MAV_CMD_DO_JUMP) {
        item->missionItem().setParam1(
            static_cast<int>(item->missionItem().param1()) + 1);
      }
    }
  }

  return true;
}

void MissionController::_initLoadedVisualItems(
    QmlObjectListModel *loadedVisualItems) {
  if (_visualItems) {
    _deinitAllVisualItems();
    _visualItems->deleteLater();
  }
  _settingsItem = nullptr;
  _takeoffMissionItem = nullptr;

  _visualItems = loadedVisualItems;

  if (_visualItems->count() == 0) {
    _addMissionSettings(_visualItems);
  } else {
    _settingsItem = _visualItems->value<MissionSettingsItem *>(0);
  }
1233

1234 1235
  MissionController::_scanForAdditionalSettings(_visualItems,
                                                _masterController);
1236

1237
  _initAllVisualItems();
1238

1239 1240 1241 1242 1243 1244
  if (_visualItems->count() > 1) {
    _firstItemAdded();
  } else {
    _allItemsRemoved();
  }
}
1245

1246 1247 1248 1249
bool MissionController::load(const QJsonObject &json, QString &errorString) {
  QString errorStr;
  QString errorMessage = tr("Mission: %1");
  QmlObjectListModel *loadedVisualItems = new QmlObjectListModel(this);
1250

1251 1252 1253 1254 1255
  if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
    errorString = errorMessage.arg(errorStr);
    return false;
  }
  _initLoadedVisualItems(loadedVisualItems);
1256

1257
  return true;
1258 1259
}

1260 1261 1262 1263 1264
bool MissionController::loadJsonFile(QFile &file, QString &errorString) {
  QString errorStr;
  QString errorMessage = tr("Mission: %1");
  QJsonDocument jsonDoc;
  QByteArray bytes = file.readAll();
1265

1266 1267 1268 1269
  if (!JsonHelper::isJsonFile(bytes, jsonDoc, errorStr)) {
    errorString = errorMessage.arg(errorStr);
    return false;
  }
1270

1271 1272 1273 1274 1275 1276
  QJsonObject json = jsonDoc.object();
  QmlObjectListModel *loadedVisualItems = new QmlObjectListModel(this);
  if (!_loadItemsFromJson(json, loadedVisualItems, errorStr)) {
    errorString = errorMessage.arg(errorStr);
    return false;
  }
1277

1278
  _initLoadedVisualItems(loadedVisualItems);
1279

1280 1281
  return true;
}
1282

1283 1284 1285 1286 1287
bool MissionController::loadTextFile(QFile &file, QString &errorString) {
  QString errorStr;
  QString errorMessage = tr("Mission: %1");
  QByteArray bytes = file.readAll();
  QTextStream stream(bytes);
1288

1289 1290
  setGlobalAltitudeMode(
      QGroundControlQmlGlobal::AltitudeModeNone); // Mixed mode
1291

1292 1293 1294 1295 1296
  QmlObjectListModel *loadedVisualItems = new QmlObjectListModel(this);
  if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
    errorString = errorMessage.arg(errorStr);
    return false;
  }
1297

1298
  _initLoadedVisualItems(loadedVisualItems);
1299

1300
  return true;
1301 1302
}

1303 1304 1305 1306 1307 1308
int MissionController::readyForSaveState(void) const {
  for (int i = 0; i < _visualItems->count(); i++) {
    VisualMissionItem *visualItem =
        qobject_cast<VisualMissionItem *>(_visualItems->get(i));
    if (visualItem->readyForSaveState() != VisualMissionItem::ReadyForSave) {
      return visualItem->readyForSaveState();
1309
    }
1310
  }
1311

1312
  return VisualMissionItem::ReadyForSave;
1313 1314
}

1315 1316
void MissionController::save(QJsonObject &json) {
  json[JsonHelper::jsonVersionKey] = _missionFileVersion;
1317

1318
  // Mission settings
1319

1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530 1531 1532 1533 1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559 1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593 1594 1595 1596 1597 1598 1599 1600 1601 1602 1603 1604 1605 1606 1607 1608 1609 1610 1611 1612 1613 1614 1615 1616 1617 1618 1619 1620 1621 1622 1623 1624 1625 1626 1627 1628 1629 1630 1631 1632 1633 1634
  MissionSettingsItem *settingsItem =
      _visualItems->value<MissionSettingsItem *>(0);
  if (!settingsItem) {
    qWarning() << "First item is not MissionSettingsItem";
    return;
  }
  QJsonValue coordinateValue;
  JsonHelper::saveGeoCoordinate(settingsItem->coordinate(),
                                true /* writeAltitude */, coordinateValue);
  json[_jsonPlannedHomePositionKey] = coordinateValue;
  json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
  json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
  json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
  json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
  json[_jsonGlobalPlanAltitudeModeKey] = _globalAltMode;

  // Save the visual items

  QJsonArray rgJsonMissionItems;
  for (int i = 0; i < _visualItems->count(); i++) {
    VisualMissionItem *visualItem =
        qobject_cast<VisualMissionItem *>(_visualItems->get(i));

    visualItem->save(rgJsonMissionItems);
  }

  // Mission settings has a special case for end mission action
  if (settingsItem) {
    QList<MissionItem *> rgMissionItems;

    if (_convertToMissionItems(_visualItems, rgMissionItems,
                               this /* missionItemParent */)) {
      QJsonObject saveObject;
      MissionItem *missionItem = rgMissionItems[rgMissionItems.count() - 1];
      missionItem->save(saveObject);
      rgJsonMissionItems.append(saveObject);
    }
    for (int i = 0; i < rgMissionItems.count(); i++) {
      rgMissionItems[i]->deleteLater();
    }
  }

  json[_jsonItemsKey] = rgJsonMissionItems;
}

void MissionController::_calcPrevWaypointValues(VisualMissionItem *currentItem,
                                                VisualMissionItem *prevItem,
                                                double *azimuth,
                                                double *distance,
                                                double *altDifference) {
  QGeoCoordinate currentCoord = currentItem->coordinate();
  QGeoCoordinate prevCoord = prevItem->exitCoordinate();

  // Convert to fixed altitudes

  *altDifference = currentItem->amslEntryAlt() - prevItem->amslExitAlt();
  *distance = prevCoord.distanceTo(currentCoord);
  *azimuth = prevCoord.azimuthTo(currentCoord);
}

double MissionController::_calcDistanceToHome(VisualMissionItem *currentItem,
                                              VisualMissionItem *homeItem) {
  QGeoCoordinate currentCoord = currentItem->coordinate();
  QGeoCoordinate homeCoord = homeItem->exitCoordinate();
  bool distanceOk = false;

  distanceOk = true;

  return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
}

FlightPathSegment *
MissionController::_createFlightPathSegmentWorker(VisualItemPair &pair) {
  QGeoCoordinate coord1 = pair.first->isSimpleItem()
                              ? pair.first->coordinate()
                              : pair.first->exitCoordinate();
  QGeoCoordinate coord2 = pair.second->coordinate();
  double coord1Alt = pair.first->isSimpleItem() ? pair.first->amslEntryAlt()
                                                : pair.first->amslExitAlt();
  double coord2Alt = pair.second->amslEntryAlt();

  FlightPathSegment *segment =
      new FlightPathSegment(coord1, coord1Alt, coord2, coord2Alt,
                            !_flyView /* queryTerrainData */, this);

  auto coord1Notifier = pair.first->isSimpleItem()
                            ? &VisualMissionItem::coordinateChanged
                            : &VisualMissionItem::exitCoordinateChanged;
  auto coord2Notifier = &VisualMissionItem::coordinateChanged;
  auto coord1AltNotifier = pair.first->isSimpleItem()
                               ? &VisualMissionItem::amslEntryAltChanged
                               : &VisualMissionItem::amslExitAltChanged;
  auto coord2AltNotifier = &VisualMissionItem::amslEntryAltChanged;

  connect(pair.first, coord1Notifier, segment,
          &FlightPathSegment::setCoordinate1);
  connect(pair.second, coord2Notifier, segment,
          &FlightPathSegment::setCoordinate2);
  connect(pair.first, coord1AltNotifier, segment,
          &FlightPathSegment::setCoord1AMSLAlt);
  connect(pair.second, coord2AltNotifier, segment,
          &FlightPathSegment::setCoord2AMSLAlt);

  connect(pair.second, &VisualMissionItem::coordinateChanged, this,
          &MissionController::_recalcMissionFlightStatusSignal,
          Qt::QueuedConnection);

  connect(segment, &FlightPathSegment::totalDistanceChanged, this,
          &MissionController::recalcTerrainProfile, Qt::QueuedConnection);
  connect(segment, &FlightPathSegment::coord1AMSLAltChanged, this,
          &MissionController::_recalcMissionFlightStatusSignal,
          Qt::QueuedConnection);
  connect(segment, &FlightPathSegment::coord2AMSLAltChanged, this,
          &MissionController::_recalcMissionFlightStatusSignal,
          Qt::QueuedConnection);
  connect(segment, &FlightPathSegment::amslTerrainHeightsChanged, this,
          &MissionController::recalcTerrainProfile, Qt::QueuedConnection);
  connect(segment, &FlightPathSegment::terrainCollisionChanged, this,
          &MissionController::recalcTerrainProfile, Qt::QueuedConnection);

  return segment;
}

FlightPathSegment *MissionController::_addFlightPathSegment(
    FlightPathSegmentHashTable &prevItemPairHashTable, VisualItemPair &pair) {
  FlightPathSegment *segment = nullptr;

  if (prevItemPairHashTable.contains(pair)) {
    // Pair already exists and connected, just re-use
    _flightPathSegmentHashTable[pair] = segment =
        prevItemPairHashTable.take(pair);
  } else {
    segment = _createFlightPathSegmentWorker(pair);
    _flightPathSegmentHashTable[pair] = segment;
  }

  _simpleFlightPathSegments.append(segment);

  return segment;
}

void MissionController::_recalcROISpecialVisuals(void) {
  return;
  VisualMissionItem *lastCoordinateItem =
      qobject_cast<VisualMissionItem *>(_visualItems->get(0));
  bool roiActive = false;

  for (int i = 1; i < _visualItems->count(); i++) {
    VisualMissionItem *visualItem =
        qobject_cast<VisualMissionItem *>(_visualItems->get(i));
    SimpleMissionItem *simpleItem =
        qobject_cast<SimpleMissionItem *>(visualItem);
    VisualItemPair viPair;

    if (simpleItem) {
      if (roiActive) {
        if (_isROICancelItem(simpleItem)) {
          roiActive = false;
        }
      } else {
        if (_isROIBeginItem(simpleItem)) {
          roiActive = true;
        }
      }
    }

    if (visualItem->specifiesCoordinate() &&
        !visualItem->isStandaloneCoordinate()) {
      viPair = VisualItemPair(lastCoordinateItem, visualItem);
      if (_flightPathSegmentHashTable.contains(viPair)) {
        _flightPathSegmentHashTable[viPair]->setSpecialVisual(roiActive);
      }
      lastCoordinateItem = visualItem;
    }
  }
}

void MissionController::_recalcFlightPathSegments(void) {
  VisualItemPair lastSegmentVisualItemPair;
  int segmentCount = 0;
  bool firstCoordinateNotFound = true;
  VisualMissionItem *lastFlyThroughVI =
      qobject_cast<VisualMissionItem *>(_visualItems->get(0));
  bool linkEndToHome = false;
  bool linkStartToHome = _controllerVehicle->rover() ? true : false;
  bool foundRTL = false;
  bool homePositionValid = _settingsItem->coordinate().isValid();
  bool roiActive = false;
  bool previousItemIsIncomplete = false;

  qCDebug(MissionControllerLog)
      << "_recalcFlightPathSegments homePositionValid" << homePositionValid;

  FlightPathSegmentHashTable oldSegmentTable = _flightPathSegmentHashTable;

  _missionContainsVTOLTakeoff = false;
  _flightPathSegmentHashTable.clear();
  _waypointPath.clear();

  // Note: Although visual support _incompleteComplexItemLines is still in the
  // codebase. The support for populating the list is not. This is due to the
  // initial implementation being buggy and incomplete with respect to correctly
  // generating the line set. So for now we leave the code for displaying them
  // in, but none are ever added until we have time to implement the correct
  // support.

  _simpleFlightPathSegments.beginReset();
  _directionArrows.beginReset();
  _incompleteComplexItemLines.beginReset();

  _simpleFlightPathSegments.clear();
  _directionArrows.clear();
  _incompleteComplexItemLines.clearAndDeleteContents();

  // Mission Settings item needs to start with no segment
  lastFlyThroughVI->setSimpleFlighPathSegment(nullptr);

  // Grovel through the list of items keeping track of things needed to
  // correctly draw waypoints lines

  for (int i = 1; i < _visualItems->count(); i++) {
    VisualMissionItem *visualItem =
        qobject_cast<VisualMissionItem *>(_visualItems->get(i));
    SimpleMissionItem *simpleItem =
        qobject_cast<SimpleMissionItem *>(visualItem);
    ComplexMissionItem *complexItem =
        qobject_cast<ComplexMissionItem *>(visualItem);

    visualItem->setSimpleFlighPathSegment(nullptr);

    if (simpleItem) {
      if (roiActive) {
        if (_isROICancelItem(simpleItem)) {
          roiActive = false;
        }
      } else {
        if (_isROIBeginItem(simpleItem)) {
          roiActive = true;
        }
      }

      MAV_CMD command = simpleItem->mavCommand();
      switch (command) {
      case MAV_CMD_NAV_TAKEOFF:
      case MAV_CMD_NAV_VTOL_TAKEOFF:
        _missionContainsVTOLTakeoff = command == MAV_CMD_NAV_VTOL_TAKEOFF;
        if (!linkEndToHome) {
          // If we still haven't found the first coordinate item and we hit a
          // takeoff command this means the mission starts from the ground. Link
          // the first item back to home to show that.
          if (firstCoordinateNotFound) {
            linkStartToHome = true;
          }
        }
        break;
      case MAV_CMD_NAV_RETURN_TO_LAUNCH:
        linkEndToHome = true;
        foundRTL = true;
        break;
      default:
        break;
      }
    }

    // No need to add waypoint segments after an RTL.
    if (foundRTL) {
      break;
    }

    if (visualItem->specifiesCoordinate() &&
        !visualItem->isStandaloneCoordinate()) {
      // Incomplete items are complex items which are waiting for the user to
      // complete setup before there visuals can become valid. They may not yet
      // have valid entry/exit coordinates associated with them while in the
      // incomplete state. For examples a Survey item which has no polygon set
      // yet.
      if (complexItem && complexItem->isIncomplete()) {
        // We don't link lines from a valid item to an incomplete item
        previousItemIsIncomplete = true;
      } else if (previousItemIsIncomplete) {
        // We also don't link lines from an incomplete item to a valid item.
        previousItemIsIncomplete = false;
        firstCoordinateNotFound = false;
        lastFlyThroughVI = visualItem;
      } else {
        if (lastFlyThroughVI != _settingsItem ||
            (homePositionValid && linkStartToHome)) {
          bool addDirectionArrow = false;
          if (i != 1) {
            // Direction arrows are added to the second segment and every 5
            // segments thereafter. The reason for start with second segment is
            // to prevent an arrow being added in between the home position and
            // a takeoff item which may be right over each other. In that case
            // the arrow points in a random direction.
            if (firstCoordinateNotFound || !lastFlyThroughVI->isSimpleItem() ||
                !visualItem->isSimpleItem()) {
              addDirectionArrow = true;
            } else if (segmentCount > 5) {
              segmentCount = 0;
              addDirectionArrow = true;
            }
            segmentCount++;
          }

          lastSegmentVisualItemPair =
              VisualItemPair(lastFlyThroughVI, visualItem);
          if (!_flyView || addDirectionArrow) {
            FlightPathSegment *segment = _addFlightPathSegment(
                oldSegmentTable, lastSegmentVisualItemPair);
            segment->setSpecialVisual(roiActive);
            if (addDirectionArrow) {
              _directionArrows.append(segment);
            }
            lastFlyThroughVI->setSimpleFlighPathSegment(segment);
          }
1635
        }
1636 1637 1638 1639
        firstCoordinateNotFound = false;
        _waypointPath.append(QVariant::fromValue(visualItem->coordinate()));
        lastFlyThroughVI = visualItem;
      }
1640
    }
1641
  }
1642

1643 1644 1645
  if (linkStartToHome && homePositionValid) {
    _waypointPath.prepend(QVariant::fromValue(_settingsItem->coordinate()));
  }
1646

1647 1648 1649 1650 1651 1652 1653 1654 1655 1656 1657 1658 1659 1660 1661 1662 1663 1664 1665 1666 1667 1668 1669 1670 1671 1672 1673 1674 1675 1676 1677 1678 1679 1680 1681 1682 1683 1684 1685 1686 1687 1688 1689 1690 1691 1692 1693 1694 1695 1696 1697 1698 1699 1700 1701 1702 1703 1704 1705 1706 1707 1708 1709 1710 1711 1712 1713 1714 1715 1716 1717 1718 1719 1720 1721 1722 1723 1724 1725 1726 1727 1728 1729 1730 1731 1732 1733 1734 1735 1736 1737 1738 1739 1740 1741 1742 1743 1744 1745 1746 1747 1748 1749 1750 1751 1752 1753
  if (linkEndToHome && lastFlyThroughVI != _settingsItem && homePositionValid) {
    lastSegmentVisualItemPair = VisualItemPair(lastFlyThroughVI, _settingsItem);
    if (_flyView) {
      _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
    }
    FlightPathSegment *segment =
        _addFlightPathSegment(oldSegmentTable, lastSegmentVisualItemPair);
    segment->setSpecialVisual(roiActive);
    lastFlyThroughVI->setSimpleFlighPathSegment(segment);
  }

  // Add direction arrow to last segment
  if (lastSegmentVisualItemPair.first) {
    FlightPathSegment *coordVector = nullptr;

    // The pair may not be in the hash, this can happen in the fly view where
    // only segments with arrows on them are added to hash. check for that first
    // and add if needed

    if (_flightPathSegmentHashTable.contains(lastSegmentVisualItemPair)) {
      // Pair exists in the new table already just reuse it
      coordVector = _flightPathSegmentHashTable[lastSegmentVisualItemPair];
    } else if (oldSegmentTable.contains(lastSegmentVisualItemPair)) {
      // Pair already exists in old table, pull from old to new and reuse
      _flightPathSegmentHashTable[lastSegmentVisualItemPair] = coordVector =
          oldSegmentTable.take(lastSegmentVisualItemPair);
    } else {
      // Create a new segment. Since this is the fly view there is no need to
      // wire change signals.
      coordVector = new FlightPathSegment(
          lastSegmentVisualItemPair.first->isSimpleItem()
              ? lastSegmentVisualItemPair.first->coordinate()
              : lastSegmentVisualItemPair.first->exitCoordinate(),
          lastSegmentVisualItemPair.first->isSimpleItem()
              ? lastSegmentVisualItemPair.first->amslEntryAlt()
              : lastSegmentVisualItemPair.first->amslExitAlt(),
          lastSegmentVisualItemPair.second->coordinate(),
          lastSegmentVisualItemPair.second->amslEntryAlt(),
          !_flyView /* queryTerrainData */, this);
      _flightPathSegmentHashTable[lastSegmentVisualItemPair] = coordVector;
    }

    _directionArrows.append(coordVector);
  }

  _simpleFlightPathSegments.endReset();
  _directionArrows.endReset();
  _incompleteComplexItemLines.endReset();

  // Anything left in the old table is an obsolete line object that can go
  qDeleteAll(oldSegmentTable);

  emit _recalcMissionFlightStatusSignal();

  if (_waypointPath.count() == 0) {
    // MapPolyLine has a bug where if you change from a path which has elements
    // to an empty path the line drawn is not cleared from the map. This hack
    // works around that since it causes the previous lines to be remove as then
    // doesn't draw anything on the map.
    _waypointPath.append(QVariant::fromValue(QGeoCoordinate(0, 0)));
    _waypointPath.append(QVariant::fromValue(QGeoCoordinate(0, 0)));
  }

  emit waypointPathChanged();
  emit recalcTerrainProfile();
}

void MissionController::_updateBatteryInfo(int waypointIndex) {
  if (_missionFlightStatus.mAhBattery != 0) {
    _missionFlightStatus.hoverAmpsTotal =
        (_missionFlightStatus.hoverTime / 60.0) *
        _missionFlightStatus.hoverAmps;
    _missionFlightStatus.cruiseAmpsTotal =
        (_missionFlightStatus.cruiseTime / 60.0) *
        _missionFlightStatus.cruiseAmps;
    _missionFlightStatus.batteriesRequired =
        ceil((_missionFlightStatus.hoverAmpsTotal +
              _missionFlightStatus.cruiseAmpsTotal) /
             _missionFlightStatus.ampMinutesAvailable);
    // FIXME: Battery change point code pretty much doesn't work. The reason is
    // that is treats complex items as a black box. It needs to be able to look
    // inside complex items in order to determine a swap point that is interior
    // to a complex item. Current the swap point display in PlanToolbar is
    // disabled to do this problem.
    if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 &&
        _missionFlightStatus.batteryChangePoint == -1) {
      _missionFlightStatus.batteryChangePoint = waypointIndex - 1;
    }
  }
}

void MissionController::_addHoverTime(double hoverTime, double hoverDistance,
                                      int waypointIndex) {
  _missionFlightStatus.totalTime += hoverTime;
  _missionFlightStatus.hoverTime += hoverTime;
  _missionFlightStatus.hoverDistance += hoverDistance;
  _missionFlightStatus.totalDistance += hoverDistance;
  _updateBatteryInfo(waypointIndex);
}

void MissionController::_addCruiseTime(double cruiseTime, double cruiseDistance,
                                       int waypointIndex) {
  _missionFlightStatus.totalTime += cruiseTime;
  _missionFlightStatus.cruiseTime += cruiseTime;
  _missionFlightStatus.cruiseDistance += cruiseDistance;
  _missionFlightStatus.totalDistance += cruiseDistance;
  _updateBatteryInfo(waypointIndex);
1754 1755
}

1756 1757 1758 1759 1760 1761 1762 1763 1764 1765 1766 1767 1768 1769 1770 1771 1772
/// Adds the specified time to the appropriate hover or cruise time values.
///     @param vtolInHover true: vtol is currrent in hover mode
///     @param hoverTime    Amount of time tp add to hover
///     @param cruiseTime   Amount of time to add to cruise
///     @param extraTime    Amount of additional time to add to hover/cruise
///     @param seqNum       Sequence number of waypoint for these values, -1 for
///     no waypoint associated
void MissionController::_addTimeDistance(bool vtolInHover, double hoverTime,
                                         double cruiseTime, double extraTime,
                                         double distance, int seqNum) {
  if (_controllerVehicle->vtol()) {
    if (vtolInHover) {
      _addHoverTime(hoverTime, distance, seqNum);
      _addHoverTime(extraTime, 0, -1);
    } else {
      _addCruiseTime(cruiseTime, distance, seqNum);
      _addCruiseTime(extraTime, 0, -1);
1773
    }
1774 1775 1776 1777 1778 1779 1780 1781 1782
  } else {
    if (_controllerVehicle->multiRotor()) {
      _addHoverTime(hoverTime, distance, seqNum);
      _addHoverTime(extraTime, 0, -1);
    } else {
      _addCruiseTime(cruiseTime, distance, seqNum);
      _addCruiseTime(extraTime, 0, -1);
    }
  }
1783 1784
}

1785 1786 1787 1788 1789 1790 1791 1792 1793 1794 1795 1796 1797 1798 1799 1800 1801 1802 1803 1804 1805 1806 1807 1808 1809 1810 1811 1812 1813 1814 1815 1816 1817 1818 1819 1820 1821 1822 1823 1824 1825 1826 1827 1828 1829 1830 1831 1832 1833 1834 1835 1836 1837 1838 1839 1840 1841 1842 1843 1844 1845 1846 1847 1848 1849 1850 1851 1852 1853 1854 1855 1856 1857 1858 1859 1860 1861 1862 1863 1864 1865 1866 1867 1868 1869 1870 1871 1872 1873 1874 1875 1876 1877 1878 1879 1880 1881 1882 1883 1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895 1896 1897
void MissionController::_recalcMissionFlightStatus() {
  if (!_visualItems->count()) {
    return;
  }

  bool firstCoordinateItem = true;
  VisualMissionItem *lastFlyThroughVI =
      qobject_cast<VisualMissionItem *>(_visualItems->get(0));

  bool homePositionValid = _settingsItem->coordinate().isValid();

  qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";

  // If home position is valid we can calculate distances between all waypoints.
  // If home position is not valid we can only calculate distances between
  // waypoints which are both relative altitude.

  // No values for first item
  lastFlyThroughVI->setAltDifference(0);
  lastFlyThroughVI->setAzimuth(0);
  lastFlyThroughVI->setDistance(0);
  lastFlyThroughVI->setDistanceFromStart(0);

  _minAMSLAltitude = _maxAMSLAltitude = _settingsItem->coordinate().altitude();

  _resetMissionFlightStatus();

  bool linkStartToHome = false;
  bool foundRTL = false;
  double totalHorizontalDistance = 0;

  for (int i = 0; i < _visualItems->count(); i++) {
    VisualMissionItem *item =
        qobject_cast<VisualMissionItem *>(_visualItems->get(i));
    SimpleMissionItem *simpleItem = qobject_cast<SimpleMissionItem *>(item);
    ComplexMissionItem *complexItem = qobject_cast<ComplexMissionItem *>(item);

    if (simpleItem &&
        simpleItem->mavCommand() == MAV_CMD_NAV_RETURN_TO_LAUNCH) {
      foundRTL = true;
    }

    // Assume the worst
    item->setAzimuth(0);
    item->setDistance(0);
    item->setDistanceFromStart(0);

    // Gimbal states reflect the state AFTER executing the item

    // ROI commands cancel out previous gimbal yaw/pitch
    if (simpleItem) {
      switch (simpleItem->command()) {
      case MAV_CMD_NAV_ROI:
      case MAV_CMD_DO_SET_ROI_LOCATION:
      case MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET:
        _missionFlightStatus.gimbalYaw = qQNaN();
        _missionFlightStatus.gimbalPitch = qQNaN();
        break;
      default:
        break;
      }
    }

    // Look for specific gimbal changes
    double gimbalYaw = item->specifiedGimbalYaw();
    if (!qIsNaN(gimbalYaw) ||
        _planViewSettings->showGimbalOnlyWhenSet()->rawValue().toBool()) {
      _missionFlightStatus.gimbalYaw = gimbalYaw;
    }
    double gimbalPitch = item->specifiedGimbalPitch();
    if (!qIsNaN(gimbalPitch) ||
        _planViewSettings->showGimbalOnlyWhenSet()->rawValue().toBool()) {
      _missionFlightStatus.gimbalPitch = gimbalPitch;
    }

    // We don't need to do any more processing if:
    //  Mission Settings Item
    //  We are after an RTL command
    if (i != 0 && !foundRTL) {
      // We must set the mission flight status prior to querying for any values
      // from the item. This is because things like current speed, gimbal, vtol
      // state  impact the values.
      item->setMissionFlightStatus(_missionFlightStatus);

      // Link back to home if first item is takeoff and we have home position
      if (firstCoordinateItem && simpleItem &&
          (simpleItem->mavCommand() == MAV_CMD_NAV_TAKEOFF ||
           simpleItem->mavCommand() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
        if (homePositionValid) {
          linkStartToHome = true;
          if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
            // We have to special case takeoff, assuming vehicle takes off
            // straight up to specified altitude
            double azimuth, distance, altDifference;
            _calcPrevWaypointValues(_settingsItem, simpleItem, &azimuth,
                                    &distance, &altDifference);
            double takeoffTime =
                qAbs(altDifference) / _appSettings->offlineEditingAscentSpeed()
                                          ->rawValue()
                                          .toDouble();
            _addHoverTime(takeoffTime, 0, -1);
          }
        }
      }

      _addTimeDistance(_missionFlightStatus.vtolMode ==
                           QGCMAVLink::VehicleClassMultiRotor,
                       0, 0, item->additionalTimeDelay(), 0, -1);

      if (item->specifiesCoordinate()) {

        // Keep track of the min/max AMSL altitude for entire mission so we can
        // calculate altitude percentages in terrain status display
1898
        if (simpleItem) {
1899 1900 1901
          double amslAltitude = item->amslEntryAlt();
          _minAMSLAltitude = std::min(_minAMSLAltitude, amslAltitude);
          _maxAMSLAltitude = std::max(_maxAMSLAltitude, amslAltitude);
1902
        } else {
1903 1904 1905 1906 1907 1908 1909 1910 1911 1912 1913 1914 1915 1916 1917 1918 1919 1920 1921 1922 1923 1924 1925 1926 1927 1928 1929 1930 1931 1932 1933 1934 1935 1936 1937 1938 1939 1940 1941 1942 1943 1944 1945 1946 1947 1948 1949 1950 1951 1952 1953 1954 1955 1956 1957 1958 1959 1960 1961 1962 1963 1964 1965 1966 1967 1968 1969 1970 1971 1972 1973 1974 1975 1976 1977 1978 1979 1980 1981 1982 1983 1984 1985 1986 1987 1988 1989 1990 1991 1992 1993 1994 1995 1996 1997 1998 1999 2000 2001 2002 2003 2004 2005 2006 2007 2008 2009 2010 2011 2012 2013 2014 2015 2016 2017 2018 2019 2020 2021 2022 2023 2024 2025 2026 2027 2028 2029 2030 2031 2032 2033 2034 2035 2036 2037 2038 2039 2040 2041 2042 2043 2044 2045 2046 2047 2048 2049 2050 2051 2052 2053 2054 2055 2056 2057 2058 2059 2060 2061 2062 2063 2064 2065 2066 2067 2068 2069 2070 2071 2072 2073 2074 2075 2076 2077
          // Complex item
          double complexMinAMSLAltitude = complexItem->minAMSLAltitude();
          double complexMaxAMSLAltitude = complexItem->maxAMSLAltitude();
          _minAMSLAltitude = std::min(_minAMSLAltitude, complexMinAMSLAltitude);
          _maxAMSLAltitude = std::max(_maxAMSLAltitude, complexMaxAMSLAltitude);
        }

        if (!item->isStandaloneCoordinate()) {
          firstCoordinateItem = false;

          // Update vehicle yaw assuming direction to next waypoint and/or
          // mission item change
          if (simpleItem) {
            double newVehicleYaw = simpleItem->specifiedVehicleYaw();
            if (qIsNaN(newVehicleYaw)) {
              // No specific vehicle yaw set. Current vehicle yaw is determined
              // from flight path segment direction.
              if (simpleItem != lastFlyThroughVI) {
                _missionFlightStatus.vehicleYaw =
                    lastFlyThroughVI->exitCoordinate().azimuthTo(
                        simpleItem->coordinate());
              }
            } else {
              _missionFlightStatus.vehicleYaw = newVehicleYaw;
            }
            simpleItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
          }

          if (lastFlyThroughVI != _settingsItem || linkStartToHome) {
            // This is a subsequent waypoint or we are forcing the first
            // waypoint back to home
            double azimuth, distance, altDifference;

            _calcPrevWaypointValues(item, lastFlyThroughVI, &azimuth, &distance,
                                    &altDifference);
            totalHorizontalDistance += distance;
            item->setAltDifference(altDifference);
            item->setAzimuth(azimuth);
            item->setDistance(distance);
            item->setDistanceFromStart(totalHorizontalDistance);

            _missionFlightStatus.maxTelemetryDistance =
                qMax(_missionFlightStatus.maxTelemetryDistance,
                     _calcDistanceToHome(item, _settingsItem));

            // Calculate time/distance
            double hoverTime = distance / _missionFlightStatus.hoverSpeed;
            double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
            _addTimeDistance(_missionFlightStatus.vtolMode ==
                                 QGCMAVLink::VehicleClassMultiRotor,
                             hoverTime, cruiseTime, 0, distance,
                             item->sequenceNumber());
          }

          if (complexItem) {
            // Add in distance/time inside complex items as well
            double distance = complexItem->complexDistance();
            _missionFlightStatus.maxTelemetryDistance = qMax(
                _missionFlightStatus.maxTelemetryDistance,
                complexItem->greatestDistanceTo(complexItem->exitCoordinate()));

            double hoverTime = distance / _missionFlightStatus.hoverSpeed;
            double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
            _addTimeDistance(_missionFlightStatus.vtolMode ==
                                 QGCMAVLink::VehicleClassMultiRotor,
                             hoverTime, cruiseTime, 0, distance,
                             item->sequenceNumber());

            totalHorizontalDistance += distance;
          }

          lastFlyThroughVI = item;
        }
      }
    }

    // Speed, VTOL states changes are processed last since they take affect on
    // the next item

    double newSpeed = item->specifiedFlightSpeed();
    if (!qIsNaN(newSpeed)) {
      if (_controllerVehicle->multiRotor()) {
        _missionFlightStatus.hoverSpeed = newSpeed;
      } else if (_controllerVehicle->vtol()) {
        if (_missionFlightStatus.vtolMode ==
            QGCMAVLink::VehicleClassMultiRotor) {
          _missionFlightStatus.hoverSpeed = newSpeed;
        } else {
          _missionFlightStatus.cruiseSpeed = newSpeed;
        }
      } else {
        _missionFlightStatus.cruiseSpeed = newSpeed;
      }
      _missionFlightStatus.vehicleSpeed = newSpeed;
    }

    // Update VTOL state
    if (simpleItem && _controllerVehicle->vtol()) {
      switch (simpleItem->command()) {
      case MAV_CMD_NAV_TAKEOFF:      // This will do a fixed wing style takeoff
      case MAV_CMD_NAV_VTOL_TAKEOFF: // Vehicle goes straight up and then
                                     // transitions to FW
      case MAV_CMD_NAV_LAND:
        _missionFlightStatus.vtolMode = QGCMAVLink::VehicleClassFixedWing;
        break;
      case MAV_CMD_NAV_VTOL_LAND:
        _missionFlightStatus.vtolMode = QGCMAVLink::VehicleClassMultiRotor;
        break;
      case MAV_CMD_DO_VTOL_TRANSITION: {
        int transitionState = simpleItem->missionItem().param1();
        if (transitionState == MAV_VTOL_STATE_MC) {
          _missionFlightStatus.vtolMode = QGCMAVLink::VehicleClassMultiRotor;
        } else if (transitionState == MAV_VTOL_STATE_FW) {
          _missionFlightStatus.vtolMode = QGCMAVLink::VehicleClassFixedWing;
        }
      } break;
      default:
        break;
      }
    }
  }
  lastFlyThroughVI->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);

  // Add the information for the final segment back to home
  if (foundRTL && lastFlyThroughVI != _settingsItem && homePositionValid) {
    double azimuth, distance, altDifference;
    _calcPrevWaypointValues(lastFlyThroughVI, _settingsItem, &azimuth,
                            &distance, &altDifference);

    // Calculate time/distance
    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
    double landTime =
        qAbs(altDifference) /
        _appSettings->offlineEditingDescentSpeed()->rawValue().toDouble();
    _addTimeDistance(_missionFlightStatus.vtolMode ==
                         QGCMAVLink::VehicleClassMultiRotor,
                     hoverTime, cruiseTime, distance, landTime, -1);
  }

  if (_missionFlightStatus.mAhBattery != 0 &&
      _missionFlightStatus.batteryChangePoint == -1) {
    _missionFlightStatus.batteryChangePoint = 0;
  }

  emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
  emit missionDistanceChanged(_missionFlightStatus.totalDistance);
  emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
  emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
  emit missionTimeChanged();
  emit missionHoverTimeChanged();
  emit missionCruiseTimeChanged();
  emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
  emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
  emit minAMSLAltitudeChanged(_minAMSLAltitude);
  emit maxAMSLAltitudeChanged(_maxAMSLAltitude);

  // Walk the list again calculating altitude percentages
  double altRange = _maxAMSLAltitude - _minAMSLAltitude;
  for (int i = 0; i < _visualItems->count(); i++) {
    VisualMissionItem *item =
        qobject_cast<VisualMissionItem *>(_visualItems->get(i));

    if (item->specifiesCoordinate()) {
      double amslAlt = item->amslEntryAlt();
      if (altRange == 0.0) {
        item->setAltPercent(0.0);
        item->setTerrainPercent(qQNaN());
        item->setTerrainCollision(false);
      } else {
        item->setAltPercent((amslAlt - _minAMSLAltitude) / altRange);
        double terrainAltitude = item->terrainAltitude();
        if (qIsNaN(terrainAltitude)) {
          item->setTerrainPercent(qQNaN());
          item->setTerrainCollision(false);
2078
        } else {
2079 2080 2081
          item->setTerrainPercent((terrainAltitude - _minAMSLAltitude) /
                                  altRange);
          item->setTerrainCollision(amslAlt < terrainAltitude);
2082
        }
2083
      }
2084
    }
2085
  }
2086

2087
  _updateTimer.start(UPDATE_TIMEOUT);
2088

2089
  emit recalcTerrainProfile();
2090 2091
}

2092 2093 2094 2095 2096 2097
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void) {
  if (_inRecalcSequence) {
    // Don't let this call recurse due to signalling
    return;
  }
2098

2099
  // Setup ascending sequence numbers for all visual items
2100

2101 2102 2103 2104 2105 2106 2107 2108 2109
  _inRecalcSequence = true;
  int sequenceNumber = 0;
  for (int i = 0; i < _visualItems->count(); i++) {
    VisualMissionItem *item =
        qobject_cast<VisualMissionItem *>(_visualItems->get(i));
    item->setSequenceNumber(sequenceNumber);
    sequenceNumber = item->lastSequenceNumber() + 1;
  }
  _inRecalcSequence = false;
2110 2111
}

2112 2113 2114 2115
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void) {
  VisualMissionItem *currentParentItem =
      qobject_cast<VisualMissionItem *>(_visualItems->get(0));
2116

2117
  currentParentItem->childItems()->clear();
2118

2119 2120
  for (int i = 1; i < _visualItems->count(); i++) {
    VisualMissionItem *item = _visualItems->value<VisualMissionItem *>(i);
2121

2122 2123
    item->setParentItem(nullptr);
    item->setHasCurrentChildItem(false);
2124

2125 2126 2127 2128 2129 2130 2131 2132 2133 2134
    // Set up non-coordinate item child hierarchy
    if (item->specifiesCoordinate()) {
      item->childItems()->clear();
      currentParentItem = item;
    } else if (item->isSimpleItem()) {
      item->setParentItem(currentParentItem);
      currentParentItem->childItems()->append(item);
      if (item->isCurrentItem()) {
        currentParentItem->setHasCurrentChildItem(true);
      }
2135
    }
2136
  }
2137 2138
}

2139 2140 2141 2142
void MissionController::_setPlannedHomePositionFromFirstCoordinate(
    const QGeoCoordinate &clickCoordinate) {
  bool foundFirstCoordinate = false;
  QGeoCoordinate firstCoordinate;
2143

2144 2145 2146
  if (_settingsItem->coordinate().isValid()) {
    return;
  }
2147

2148 2149 2150
  // Set the planned home position to be a delta from first coordinate
  for (int i = 1; i < _visualItems->count(); i++) {
    VisualMissionItem *item = _visualItems->value<VisualMissionItem *>(i);
2151

2152 2153 2154 2155
    if (item->specifiesCoordinate() && item->coordinate().isValid()) {
      foundFirstCoordinate = true;
      firstCoordinate = item->coordinate();
      break;
2156
    }
2157
  }
2158

2159 2160 2161 2162 2163
  // No item specifying a coordinate was found, in this case it we have a
  // clickCoordinate use that
  if (!foundFirstCoordinate) {
    firstCoordinate = clickCoordinate;
  }
2164

2165 2166 2167 2168 2169 2170 2171
  if (firstCoordinate.isValid()) {
    QGeoCoordinate plannedHomeCoord =
        firstCoordinate.atDistanceAndAzimuth(30, 0);
    plannedHomeCoord.setAltitude(0);
    _settingsItem->setInitialHomePositionFromUser(plannedHomeCoord);
  }
}
2172

2173 2174 2175 2176 2177 2178 2179 2180 2181
void MissionController::_recalcAllWithCoordinate(
    const QGeoCoordinate &coordinate) {
  if (!_flyView) {
    _setPlannedHomePositionFromFirstCoordinate(coordinate);
  }
  _recalcSequence();
  _recalcChildItems();
  emit _recalcFlightPathSegmentsSignal();
  _updateTimer.start(UPDATE_TIMEOUT);
2182 2183
}

2184 2185 2186
void MissionController::_recalcAll(void) {
  QGeoCoordinate emptyCoord;
  _recalcAllWithCoordinate(emptyCoord);
2187 2188
}

2189 2190 2191
/// Initializes a new set of mission items
void MissionController::_initAllVisualItems(void) {
  // Setup home position at index 0
2192

2193 2194 2195 2196 2197 2198 2199 2200 2201 2202 2203 2204 2205 2206 2207 2208 2209 2210 2211 2212 2213 2214 2215 2216 2217 2218 2219 2220 2221 2222 2223 2224 2225 2226 2227 2228 2229 2230 2231 2232 2233 2234 2235 2236 2237 2238 2239 2240 2241 2242 2243 2244 2245 2246 2247 2248 2249 2250 2251 2252 2253 2254 2255 2256 2257 2258 2259 2260 2261 2262 2263 2264 2265 2266 2267 2268 2269 2270 2271 2272 2273 2274 2275 2276 2277 2278 2279 2280 2281 2282 2283 2284 2285 2286 2287 2288 2289 2290 2291 2292 2293 2294 2295 2296 2297 2298 2299 2300 2301 2302 2303 2304 2305 2306 2307 2308 2309 2310 2311 2312
  if (!_settingsItem) {
    _settingsItem = qobject_cast<MissionSettingsItem *>(_visualItems->get(0));
    if (!_settingsItem) {
      qWarning() << "First item not MissionSettingsItem";
      return;
    }
  }

  connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this,
          &MissionController::_recalcAll);
  connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this,
          &MissionController::plannedHomePositionChanged);

  for (int i = 0; i < _visualItems->count(); i++) {
    VisualMissionItem *item =
        qobject_cast<VisualMissionItem *>(_visualItems->get(i));
    _initVisualItem(item);

    TakeoffMissionItem *takeoffItem = qobject_cast<TakeoffMissionItem *>(item);
    if (takeoffItem) {
      _takeoffMissionItem = takeoffItem;
    }
  }

  _recalcAll();

  connect(_visualItems, &QmlObjectListModel::dirtyChanged, this,
          &MissionController::_visualItemsDirtyChanged);
  connect(_visualItems, &QmlObjectListModel::countChanged, this,
          &MissionController::_updateContainsItems);

  emit visualItemsChanged();
  emit containsItemsChanged(containsItems());
  emit plannedHomePositionChanged(plannedHomePosition());

  if (!_flyView) {
    setCurrentPlanViewSeqNum(0, true);
  }

  setDirty(false);
}

void MissionController::_deinitAllVisualItems(void) {
  disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this,
             &MissionController::_recalcAll);
  disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this,
             &MissionController::plannedHomePositionChanged);

  for (int i = 0; i < _visualItems->count(); i++) {
    _deinitVisualItem(qobject_cast<VisualMissionItem *>(_visualItems->get(i)));
  }

  disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this,
             &MissionController::dirtyChanged);
  disconnect(_visualItems, &QmlObjectListModel::countChanged, this,
             &MissionController::_updateContainsItems);
}

void MissionController::_initVisualItem(VisualMissionItem *visualItem) {
  setDirty(false);

  connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged, this,
          &MissionController::_recalcFlightPathSegmentsSignal,
          Qt::QueuedConnection);
  connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged, this,
          &MissionController::_recalcMissionFlightStatusSignal,
          Qt::QueuedConnection);
  connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged, this,
          &MissionController::_recalcMissionFlightStatusSignal,
          Qt::QueuedConnection);
  connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged, this,
          &MissionController::_recalcMissionFlightStatusSignal,
          Qt::QueuedConnection);
  connect(visualItem, &VisualMissionItem::specifiedVehicleYawChanged, this,
          &MissionController::_recalcMissionFlightStatusSignal,
          Qt::QueuedConnection);
  connect(visualItem, &VisualMissionItem::terrainAltitudeChanged, this,
          &MissionController::_recalcMissionFlightStatusSignal,
          Qt::QueuedConnection);
  connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged, this,
          &MissionController::_recalcMissionFlightStatusSignal,
          Qt::QueuedConnection);
  connect(visualItem, &VisualMissionItem::currentVTOLModeChanged, this,
          &MissionController::_recalcMissionFlightStatusSignal,
          Qt::QueuedConnection);
  connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged, this,
          &MissionController::_recalcSequence);

  if (visualItem->isSimpleItem()) {
    // We need to track commandChanged on simple item since recalc has special
    // handling for takeoff command
    SimpleMissionItem *simpleItem =
        qobject_cast<SimpleMissionItem *>(visualItem);
    if (simpleItem) {
      connect(&simpleItem->missionItem()._commandFact, &Fact::valueChanged,
              this, &MissionController::_itemCommandChanged);
    } else {
      qWarning() << "isSimpleItem == true, yet not SimpleMissionItem";
    }
  } else {
    ComplexMissionItem *complexItem =
        qobject_cast<ComplexMissionItem *>(visualItem);
    if (complexItem) {
      connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this,
              &MissionController::_recalcMissionFlightStatusSignal,
              Qt::QueuedConnection);
      connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged, this,
              &MissionController::_recalcMissionFlightStatusSignal,
              Qt::QueuedConnection);
      connect(complexItem, &ComplexMissionItem::minAMSLAltitudeChanged, this,
              &MissionController::_recalcMissionFlightStatusSignal,
              Qt::QueuedConnection);
      connect(complexItem, &ComplexMissionItem::maxAMSLAltitudeChanged, this,
              &MissionController::_recalcMissionFlightStatusSignal,
              Qt::QueuedConnection);
      connect(complexItem, &ComplexMissionItem::isIncompleteChanged, this,
              &MissionController::_recalcFlightPathSegmentsSignal,
              Qt::QueuedConnection);
    } else {
      qWarning() << "ComplexMissionItem not found";
2313
    }
2314
  }
2315 2316
}

2317 2318 2319
void MissionController::_deinitVisualItem(VisualMissionItem *visualItem) {
  // Disconnect all signals
  disconnect(visualItem, nullptr, nullptr, nullptr);
2320 2321
}

2322 2323 2324
void MissionController::_itemCommandChanged(void) {
  _recalcChildItems();
  emit _recalcFlightPathSegmentsSignal();
2325 2326
}

2327 2328 2329 2330 2331 2332 2333
void MissionController::_managerVehicleChanged(Vehicle *managerVehicle) {
  if (_managerVehicle) {
    _missionManager->disconnect(this);
    _managerVehicle->disconnect(this);
    _managerVehicle = nullptr;
    _missionManager = nullptr;
  }
2334

2335 2336 2337 2338 2339 2340 2341 2342 2343 2344 2345 2346 2347 2348 2349 2350 2351 2352 2353 2354 2355 2356 2357 2358 2359 2360 2361 2362 2363 2364 2365 2366 2367 2368 2369 2370 2371 2372 2373 2374 2375 2376 2377 2378 2379 2380 2381 2382 2383 2384 2385 2386 2387 2388 2389 2390 2391 2392 2393 2394 2395 2396 2397 2398 2399 2400 2401 2402 2403 2404 2405 2406 2407 2408 2409 2410 2411 2412 2413 2414 2415 2416 2417 2418 2419 2420 2421 2422 2423 2424
  _managerVehicle = managerVehicle;
  if (!_managerVehicle) {
    qWarning()
        << "MissionController::managerVehicleChanged managerVehicle=NULL";
    return;
  }

  _missionManager = _managerVehicle->missionManager();
  connect(_missionManager, &MissionManager::newMissionItemsAvailable, this,
          &MissionController::_newMissionItemsAvailableFromVehicle);
  connect(_missionManager, &MissionManager::sendComplete, this,
          &MissionController::_managerSendComplete);
  connect(_missionManager, &MissionManager::removeAllComplete, this,
          &MissionController::_managerRemoveAllComplete);
  connect(_missionManager, &MissionManager::inProgressChanged, this,
          &MissionController::_inProgressChanged);
  connect(_missionManager, &MissionManager::progressPct, this,
          &MissionController::_progressPctChanged);
  connect(_missionManager, &MissionManager::currentIndexChanged, this,
          &MissionController::_currentMissionIndexChanged);
  connect(_missionManager, &MissionManager::lastCurrentIndexChanged, this,
          &MissionController::resumeMissionIndexChanged);
  connect(_missionManager, &MissionManager::resumeMissionReady, this,
          &MissionController::resumeMissionReady);
  connect(_missionManager, &MissionManager::resumeMissionUploadFail, this,
          &MissionController::resumeMissionUploadFail);
  connect(_managerVehicle, &Vehicle::defaultCruiseSpeedChanged, this,
          &MissionController::_recalcMissionFlightStatusSignal,
          Qt::QueuedConnection);
  connect(_managerVehicle, &Vehicle::defaultHoverSpeedChanged, this,
          &MissionController::_recalcMissionFlightStatusSignal,
          Qt::QueuedConnection);
  connect(_managerVehicle, &Vehicle::vehicleTypeChanged, this,
          &MissionController::complexMissionItemNamesChanged);

  emit complexMissionItemNamesChanged();
  emit resumeMissionIndexChanged();
}

void MissionController::_inProgressChanged(bool inProgress) {
  emit syncInProgressChanged(inProgress);
}

bool MissionController::_findPreviousAltitude(int newIndex,
                                              double *prevAltitude,
                                              int *prevAltitudeMode) {
  bool found = false;
  double foundAltitude = 0;
  int foundAltitudeMode = QGroundControlQmlGlobal::AltitudeModeNone;

  if (newIndex > _visualItems->count()) {
    return false;
  }
  newIndex--;

  for (int i = newIndex; i > 0; i--) {
    VisualMissionItem *visualItem =
        qobject_cast<VisualMissionItem *>(_visualItems->get(i));

    if (visualItem->specifiesCoordinate() &&
        !visualItem->isStandaloneCoordinate()) {
      if (visualItem->isSimpleItem()) {
        SimpleMissionItem *simpleItem =
            qobject_cast<SimpleMissionItem *>(visualItem);
        if (simpleItem->specifiesAltitude()) {
          foundAltitude = simpleItem->altitude()->rawValue().toDouble();
          foundAltitudeMode = simpleItem->altitudeMode();
          found = true;
          break;
        }
      }
    }
  }

  if (found) {
    *prevAltitude = foundAltitude;
    *prevAltitudeMode = foundAltitudeMode;
  }

  return found;
}

double MissionController::_normalizeLat(double lat) {
  // Normalize latitude to range: 0 to 180, S to N
  return lat + 90.0;
}

double MissionController::_normalizeLon(double lon) {
  // Normalize longitude to range: 0 to 360, W to E
  return lon + 180.0;
2425 2426
}

2427 2428 2429 2430
/// Add the Mission Settings complex item to the front of the items
MissionSettingsItem *
MissionController::_addMissionSettings(QmlObjectListModel *visualItems) {
  qCDebug(MissionControllerLog) << "_addMissionSettings";
2431

2432 2433 2434
  MissionSettingsItem *settingsItem =
      new MissionSettingsItem(_masterController, _flyView, visualItems);
  visualItems->insert(0, settingsItem);
2435

2436 2437 2438
  if (visualItems == _visualItems) {
    _settingsItem = settingsItem;
  }
2439

2440 2441
  return settingsItem;
}
2442

2443 2444 2445 2446 2447 2448 2449 2450 2451 2452 2453 2454 2455 2456 2457 2458 2459 2460 2461 2462 2463 2464
void MissionController::_centerHomePositionOnMissionItems(
    QmlObjectListModel *visualItems) {
  qCDebug(MissionControllerLog) << "_centerHomePositionOnMissionItems";

  if (visualItems->count() > 1) {
    double north = 0.0;
    double south = 0.0;
    double east = 0.0;
    double west = 0.0;
    bool firstCoordSet = false;

    for (int i = 1; i < visualItems->count(); i++) {
      VisualMissionItem *item =
          qobject_cast<VisualMissionItem *>(visualItems->get(i));
      if (item->specifiesCoordinate()) {
        if (firstCoordSet) {
          double lat = _normalizeLat(item->coordinate().latitude());
          double lon = _normalizeLon(item->coordinate().longitude());
          north = fmax(north, lat);
          south = fmin(south, lat);
          east = fmax(east, lon);
          west = fmin(west, lon);
2465
        } else {
2466 2467 2468 2469 2470
          firstCoordSet = true;
          north = _normalizeLat(item->coordinate().latitude());
          south = north;
          east = _normalizeLon(item->coordinate().longitude());
          west = east;
2471
        }
2472
      }
2473 2474
    }

2475 2476 2477 2478
    if (firstCoordSet) {
      _settingsItem->setInitialHomePositionFromUser(
          QGeoCoordinate((south + ((north - south) / 2)) - 90.0,
                         (west + ((east - west) / 2)) - 180.0, 0.0));
2479
    }
2480
  }
2481 2482
}

2483
int MissionController::resumeMissionIndex(void) const {
2484

2485
  int resumeIndex = 0;
2486

2487 2488 2489 2490 2491 2492 2493 2494 2495 2496 2497 2498 2499 2500 2501
  if (_flyView) {
    resumeIndex =
        _missionManager->lastCurrentIndex() +
        (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0
                                                                           : 1);
    if (resumeIndex > 1 &&
        resumeIndex !=
            _visualItems->value<VisualMissionItem *>(_visualItems->count() - 1)
                ->sequenceNumber()) {
      // Resume at the item previous to the item we were heading towards
      resumeIndex--;
    } else {
      resumeIndex = 0;
    }
  }
2502

2503
  return resumeIndex;
2504 2505
}

2506 2507 2508 2509 2510
int MissionController::currentMissionIndex(void) const {
  if (!_flyView) {
    return -1;
  } else {
    int currentIndex = _missionManager->currentIndex();
2511
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
2512
      currentIndex++;
2513
    }
2514 2515
    return currentIndex;
  }
2516 2517
}

2518 2519 2520 2521
void MissionController::_currentMissionIndexChanged(int sequenceNumber) {
  if (_flyView) {
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
      sequenceNumber++;
2522 2523
    }

2524 2525 2526 2527
    for (int i = 0; i < _visualItems->count(); i++) {
      VisualMissionItem *item =
          qobject_cast<VisualMissionItem *>(_visualItems->get(i));
      item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
2528
    }
2529 2530
    emit currentMissionIndexChanged(currentMissionIndex());
  }
2531 2532
}

2533 2534
bool MissionController::syncInProgress(void) const {
  return _missionManager->inProgress();
2535 2536
}

2537 2538
bool MissionController::dirty(void) const {
  return _visualItems ? _visualItems->dirty() : false;
2539 2540
}

2541 2542 2543 2544
void MissionController::setDirty(bool dirty) {
  if (_visualItems) {
    _visualItems->setDirty(dirty);
  }
2545 2546
}

2547 2548 2549 2550 2551 2552 2553 2554 2555 2556 2557 2558 2559 2560 2561 2562 2563
void MissionController::_scanForAdditionalSettings(
    QmlObjectListModel *visualItems, PlanMasterController *masterController) {
  // First we look for a Landing Patterns which are at the end
  if (!FixedWingLandingComplexItem::scanForItem(visualItems, _flyView,
                                                masterController)) {
    VTOLLandingComplexItem::scanForItem(visualItems, _flyView,
                                        masterController);
  }

  int scanIndex = 0;
  while (scanIndex < visualItems->count()) {
    VisualMissionItem *visualItem =
        visualItems->value<VisualMissionItem *>(scanIndex);

    qCDebug(MissionControllerLog)
        << "MissionController::_scanForAdditionalSettings count:scanIndex"
        << visualItems->count() << scanIndex;
2564

2565 2566 2567 2568 2569 2570 2571 2572 2573 2574 2575 2576 2577 2578 2579 2580 2581 2582
    if (!_flyView) {
      MissionSettingsItem *settingsItem =
          qobject_cast<MissionSettingsItem *>(visualItem);
      if (settingsItem) {
        scanIndex++;
        settingsItem->scanForMissionSettings(visualItems, scanIndex);
        continue;
      }
    }

    SimpleMissionItem *simpleItem =
        qobject_cast<SimpleMissionItem *>(visualItem);
    if (simpleItem) {
      scanIndex++;
      simpleItem->scanForSections(visualItems, scanIndex, masterController);
    } else {
      // Complex item, can't have sections
      scanIndex++;
2583
    }
2584
  }
2585 2586
}

2587 2588
void MissionController::_updateContainsItems(void) {
  emit containsItemsChanged(containsItems());
2589 2590
}

2591 2592
bool MissionController::containsItems(void) const {
  return _visualItems ? _visualItems->count() > 1 : false;
2593 2594
}

2595 2596 2597 2598 2599 2600 2601 2602 2603 2604 2605 2606 2607
void MissionController::removeAllFromVehicle(void) {
  if (_masterController->offline()) {
    qCWarning(MissionControllerLog)
        << "MissionControllerLog::removeAllFromVehicle called while offline";
  } else if (syncInProgress()) {
    qCWarning(MissionControllerLog)
        << "MissionControllerLog::removeAllFromVehicle called while "
           "syncInProgress";
  } else {
    _itemsRequested = true;
    _missionManager->removeAll();
  }
}
2608

2609 2610
QStringList MissionController::complexMissionItemNames(void) const {
  QStringList complexItems;
2611

2612 2613
  complexItems.append(SurveyComplexItem::name);
  complexItems.append(CorridorScanComplexItem::name);
Valentin Platzgummer's avatar
Valentin Platzgummer committed
2614
  complexItems.append(MeasurementComplexItem::name);
2615 2616 2617
  if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
    complexItems.append(StructureScanComplexItem::name);
  }
2618

2619 2620
  // Note: The landing pattern items are not added here since they have there
  // own button which adds them
2621

2622 2623 2624
  return qgcApp()->toolbox()->corePlugin()->complexMissionItemNames(
      _controllerVehicle, complexItems);
}
2625

2626 2627 2628 2629 2630 2631
void MissionController::resumeMission(int resumeIndex) {
  if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
    resumeIndex--;
  }
  _missionManager->generateResumeMission(resumeIndex);
}
2632

2633 2634 2635 2636 2637 2638 2639
QGeoCoordinate MissionController::plannedHomePosition(void) const {
  if (_settingsItem) {
    return _settingsItem->coordinate();
  } else {
    return QGeoCoordinate();
  }
}
2640

2641 2642 2643
void MissionController::applyDefaultMissionAltitude(void) {
  double defaultAltitude =
      _appSettings->defaultMissionItemAltitude()->rawValue().toDouble();
2644

2645 2646 2647 2648 2649
  for (int i = 1; i < _visualItems->count(); i++) {
    VisualMissionItem *item = _visualItems->value<VisualMissionItem *>(i);
    item->applyNewAltitude(defaultAltitude);
  }
}
2650

2651 2652 2653 2654 2655 2656
void MissionController::_progressPctChanged(double progressPct) {
  if (!QGC::fuzzyCompare(progressPct, _progressPct)) {
    _progressPct = progressPct;
    emit progressPctChanged(progressPct);
  }
}
2657

2658 2659 2660 2661 2662
void MissionController::_visualItemsDirtyChanged(bool dirty) {
  // We could connect signal to signal and not need this but this is handy for
  // setting a breakpoint on
  emit dirtyChanged(dirty);
}
2663

2664 2665 2666 2667 2668 2669 2670 2671 2672 2673 2674 2675 2676 2677 2678 2679 2680 2681 2682 2683 2684 2685 2686 2687 2688 2689 2690 2691 2692 2693 2694 2695 2696 2697 2698 2699 2700 2701 2702 2703 2704 2705 2706 2707 2708 2709 2710 2711 2712 2713 2714 2715 2716 2717 2718 2719 2720 2721 2722 2723 2724 2725 2726 2727 2728 2729 2730 2731 2732 2733 2734 2735 2736 2737 2738 2739 2740 2741 2742 2743 2744 2745 2746 2747 2748 2749 2750 2751 2752 2753 2754 2755 2756 2757 2758 2759 2760 2761 2762 2763 2764 2765 2766 2767 2768 2769 2770 2771 2772 2773 2774 2775 2776 2777 2778 2779 2780 2781 2782 2783 2784 2785 2786 2787 2788 2789 2790 2791 2792 2793 2794 2795 2796 2797 2798 2799 2800 2801
bool MissionController::showPlanFromManagerVehicle(void) {
  qCDebug(MissionControllerLog)
      << "showPlanFromManagerVehicle _flyView" << _flyView;
  if (_masterController->offline()) {
    qCWarning(MissionControllerLog)
        << "MissionController::showPlanFromManagerVehicle called while offline";
    return true; // stops further propagation of showPlanFromManagerVehicle due
                 // to error
  } else {
    if (!_managerVehicle->initialPlanRequestComplete()) {
      // The vehicle hasn't completed initial load, we can just wait for
      // newMissionItemsAvailable to be signalled automatically
      qCDebug(MissionControllerLog)
          << "showPlanFromManagerVehicle: !initialPlanRequestComplete, wait "
             "for signal";
      return true;
    } else if (syncInProgress()) {
      // If the sync is already in progress, newMissionItemsAvailable will be
      // signalled automatically when it is done. So no need to do anything.
      qCDebug(MissionControllerLog)
          << "showPlanFromManagerVehicle: syncInProgress wait for signal";
      return true;
    } else {
      // Fake a _newMissionItemsAvailable with the current items
      qCDebug(MissionControllerLog)
          << "showPlanFromManagerVehicle: sync complete simulate signal";
      _itemsRequested = true;
      _newMissionItemsAvailableFromVehicle(false /* removeAllRequested */);
      return false;
    }
  }
}

void MissionController::_managerSendComplete(bool error) {
  // Fly view always reloads on send complete
  if (!error && _flyView) {
    showPlanFromManagerVehicle();
  }
}

void MissionController::_managerRemoveAllComplete(bool error) {
  if (!error) {
    // Remove all from vehicle so we always update
    showPlanFromManagerVehicle();
  }
}

bool MissionController::_isROIBeginItem(SimpleMissionItem *simpleItem) {
  return simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI_LOCATION ||
         simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET ||
         (simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI &&
          static_cast<int>(simpleItem->missionItem().param1()) ==
              MAV_ROI_LOCATION);
}

bool MissionController::_isROICancelItem(SimpleMissionItem *simpleItem) {
  return simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI_NONE ||
         (simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI &&
          static_cast<int>(simpleItem->missionItem().param1()) == MAV_ROI_NONE);
}

void MissionController::setCurrentPlanViewSeqNum(int sequenceNumber,
                                                 bool force) {
  if (_visualItems && (force || sequenceNumber != _currentPlanViewSeqNum)) {
    bool foundLand = false;
    int takeoffSeqNum = -1;
    int landSeqNum = -1;
    int lastFlyThroughSeqNum = -1;

    _splitSegment = nullptr;
    _currentPlanViewItem = nullptr;
    _currentPlanViewSeqNum = -1;
    _currentPlanViewVIIndex = -1;
    _onlyInsertTakeoffValid =
        !_planViewSettings->takeoffItemNotRequired()->rawValue().toBool() &&
        _visualItems->count() == 1; // First item must be takeoff
    _isInsertTakeoffValid = true;
    _isInsertLandValid = true;
    _isROIActive = false;
    _isROIBeginCurrentItem = false;
    _flyThroughCommandsAllowed = true;
    _previousCoordinate = QGeoCoordinate();

    for (int viIndex = 0; viIndex < _visualItems->count(); viIndex++) {
      VisualMissionItem *pVI =
          qobject_cast<VisualMissionItem *>(_visualItems->get(viIndex));
      SimpleMissionItem *simpleItem = qobject_cast<SimpleMissionItem *>(pVI);
      int currentSeqNumber = pVI->sequenceNumber();

      if (sequenceNumber != 0 && currentSeqNumber <= sequenceNumber) {
        if (pVI->specifiesCoordinate() && !pVI->isStandaloneCoordinate()) {
          // Coordinate based flight commands prior to where the takeoff would
          // be inserted
          _isInsertTakeoffValid = false;
        }
      }

      if (qobject_cast<TakeoffMissionItem *>(pVI)) {
        takeoffSeqNum = currentSeqNumber;
        _isInsertTakeoffValid = false;
      }

      if (!foundLand) {
        if (simpleItem) {
          switch (simpleItem->mavCommand()) {
          case MAV_CMD_NAV_LAND:
          case MAV_CMD_NAV_VTOL_LAND:
          case MAV_CMD_DO_LAND_START:
          case MAV_CMD_NAV_RETURN_TO_LAUNCH:
            foundLand = true;
            landSeqNum = currentSeqNumber;
            break;
          default:
            break;
          }
        } else {
          FixedWingLandingComplexItem *fwLanding =
              qobject_cast<FixedWingLandingComplexItem *>(pVI);
          if (fwLanding) {
            foundLand = true;
            landSeqNum = currentSeqNumber;
          }
        }
      }

      if (simpleItem) {
        // Remember previous coordinate
        if (currentSeqNumber < sequenceNumber &&
            simpleItem->specifiesCoordinate() &&
            !simpleItem->isStandaloneCoordinate()) {
          _previousCoordinate = simpleItem->coordinate();
        }

        // ROI state handling
        if (currentSeqNumber <= sequenceNumber) {
          if (_isROIActive) {
            if (_isROICancelItem(simpleItem)) {
              _isROIActive = false;
2802
            }
2803 2804 2805
          } else {
            if (_isROIBeginItem(simpleItem)) {
              _isROIActive = true;
2806
            }
2807 2808 2809 2810 2811 2812 2813 2814 2815 2816 2817 2818 2819 2820 2821 2822 2823 2824 2825 2826 2827 2828 2829 2830 2831 2832 2833 2834 2835 2836 2837 2838 2839 2840
          }
        }
        if (currentSeqNumber == sequenceNumber && _isROIBeginItem(simpleItem)) {
          _isROIBeginCurrentItem = true;
        }
      }

      if (viIndex != 0) {
        // Complex items are assumed to be fly through
        if (!simpleItem || (simpleItem->specifiesCoordinate() &&
                            !simpleItem->isStandaloneCoordinate())) {
          lastFlyThroughSeqNum = currentSeqNumber;
        }
      }

      if (currentSeqNumber == sequenceNumber) {
        pVI->setIsCurrentItem(true);
        pVI->setHasCurrentChildItem(false);

        _currentPlanViewItem = pVI;
        _currentPlanViewSeqNum = sequenceNumber;
        _currentPlanViewVIIndex = viIndex;

        if (pVI->specifiesCoordinate()) {
          if (!pVI->isStandaloneCoordinate()) {
            // Determine split segment used to display line split editing ui.
            for (int j = viIndex - 1; j > 0; j--) {
              VisualMissionItem *pPrev =
                  qobject_cast<VisualMissionItem *>(_visualItems->get(j));
              if (pPrev->specifiesCoordinate() &&
                  !pPrev->isStandaloneCoordinate()) {
                VisualItemPair splitPair(pPrev, pVI);
                if (_flightPathSegmentHashTable.contains(splitPair)) {
                  _splitSegment = _flightPathSegmentHashTable[splitPair];
2841
                }
2842
              }
2843
            }
2844 2845 2846 2847 2848 2849 2850 2851 2852 2853 2854 2855 2856 2857 2858 2859 2860 2861 2862 2863 2864 2865 2866 2867 2868 2869 2870 2871 2872 2873 2874 2875 2876 2877 2878 2879 2880 2881 2882 2883 2884 2885 2886 2887 2888 2889 2890 2891 2892 2893 2894 2895 2896 2897 2898 2899 2900 2901 2902 2903 2904 2905 2906 2907 2908 2909 2910 2911 2912 2913 2914 2915 2916 2917 2918 2919 2920 2921 2922
          }
        } else if (pVI->parentItem()) {
          pVI->parentItem()->setHasCurrentChildItem(true);
        }
      } else {
        pVI->setIsCurrentItem(false);
      }
    }

    if (takeoffSeqNum != -1) {
      // Takeoff item was found which means mission starts from ground
      if (sequenceNumber < takeoffSeqNum) {
        // Land is only valid after the takeoff item.
        _isInsertLandValid = false;
        // Fly through commands are not allowed prior to the takeoff command
        _flyThroughCommandsAllowed = false;
      }
    }

    if (lastFlyThroughSeqNum != -1) {
      // Land item must be after any fly through coordinates
      if (sequenceNumber < lastFlyThroughSeqNum) {
        _isInsertLandValid = false;
      }
    }

    if (foundLand) {
      // Can't have more than one land sequence
      _isInsertLandValid = false;
      if (sequenceNumber >= landSeqNum) {
        // Can't have fly through commands after a land item
        _flyThroughCommandsAllowed = false;
      }
    }

    // These are not valid when only takeoff is allowed
    _isInsertLandValid = _isInsertLandValid && !_onlyInsertTakeoffValid;
    _flyThroughCommandsAllowed =
        _flyThroughCommandsAllowed && !_onlyInsertTakeoffValid;

    emit currentPlanViewSeqNumChanged();
    emit currentPlanViewVIIndexChanged();
    emit currentPlanViewItemChanged();
    emit splitSegmentChanged();
    emit onlyInsertTakeoffValidChanged();
    emit isInsertTakeoffValidChanged();
    emit isInsertLandValidChanged();
    emit isROIActiveChanged();
    emit isROIBeginCurrentItemChanged();
    emit flyThroughCommandsAllowedChanged();
    emit previousCoordinateChanged();
  }
}

void MissionController::_updateTimeout() {
  QGeoCoordinate firstCoordinate;
  QGeoCoordinate takeoffCoordinate;
  QGCGeoBoundingCube boundingCube;
  double north = 0.0;
  double south = 180.0;
  double east = 0.0;
  double west = 360.0;
  double minAlt = QGCGeoBoundingCube::MaxAlt;
  double maxAlt = QGCGeoBoundingCube::MinAlt;
  for (int i = 1; i < _visualItems->count(); i++) {
    VisualMissionItem *item =
        qobject_cast<VisualMissionItem *>(_visualItems->get(i));
    if (item->isSimpleItem()) {
      SimpleMissionItem *pSimpleItem = qobject_cast<SimpleMissionItem *>(item);
      if (pSimpleItem) {
        switch (pSimpleItem->command()) {
        case MAV_CMD_NAV_TAKEOFF:
        case MAV_CMD_NAV_WAYPOINT:
        case MAV_CMD_NAV_LAND:
          if (pSimpleItem->coordinate().isValid()) {
            if ((MAV_CMD)pSimpleItem->command() == MAV_CMD_NAV_TAKEOFF) {
              takeoffCoordinate = pSimpleItem->coordinate();
            } else if (!firstCoordinate.isValid()) {
              firstCoordinate = pSimpleItem->coordinate();
2923
            }
2924 2925 2926 2927 2928 2929 2930 2931 2932 2933 2934 2935 2936 2937 2938 2939 2940 2941 2942 2943 2944 2945 2946 2947 2948 2949 2950 2951 2952 2953 2954 2955 2956 2957 2958 2959 2960 2961 2962 2963 2964
            double lat = pSimpleItem->coordinate().latitude() + 90.0;
            double lon = pSimpleItem->coordinate().longitude() + 180.0;
            double alt = pSimpleItem->coordinate().altitude();
            north = fmax(north, lat);
            south = fmin(south, lat);
            east = fmax(east, lon);
            west = fmin(west, lon);
            minAlt = fmin(minAlt, alt);
            maxAlt = fmax(maxAlt, alt);
          }
          break;
        default:
          break;
        }
      }
    } else {
      ComplexMissionItem *pComplexItem =
          qobject_cast<ComplexMissionItem *>(item);
      if (pComplexItem) {
        QGCGeoBoundingCube bc = pComplexItem->boundingCube();
        if (bc.isValid()) {
          if (!firstCoordinate.isValid() &&
              pComplexItem->coordinate().isValid()) {
            firstCoordinate = pComplexItem->coordinate();
          }
          north = fmax(north, bc.pointNW.latitude() + 90.0);
          south = fmin(south, bc.pointSE.latitude() + 90.0);
          east = fmax(east, bc.pointNW.longitude() + 180.0);
          west = fmin(west, bc.pointSE.longitude() + 180.0);
          minAlt = fmin(minAlt, bc.pointNW.altitude());
          maxAlt = fmax(maxAlt, bc.pointSE.altitude());
        }
      }
    }
  }
  //-- Figure out where this thing is taking off from
  if (!takeoffCoordinate.isValid()) {
    if (firstCoordinate.isValid()) {
      takeoffCoordinate = firstCoordinate;
    } else {
      takeoffCoordinate = plannedHomePosition();
2965
    }
2966 2967 2968 2969 2970 2971 2972 2973 2974 2975 2976 2977 2978 2979
  }
  //-- Build bounding "cube"
  boundingCube =
      QGCGeoBoundingCube(QGeoCoordinate(north - 90.0, west - 180.0, minAlt),
                         QGeoCoordinate(south - 90.0, east - 180.0, maxAlt));
  if (_travelBoundingCube != boundingCube ||
      _takeoffCoordinate != takeoffCoordinate) {
    _takeoffCoordinate = takeoffCoordinate;
    _travelBoundingCube = boundingCube;
    emit missionBoundingCubeChanged();
    qCDebug(MissionControllerLog)
        << "Bounding cube:" << _travelBoundingCube.pointNW
        << _travelBoundingCube.pointSE;
  }
2980 2981
}

2982 2983
void MissionController::_complexBoundingBoxChanged() {
  _updateTimer.start(UPDATE_TIMEOUT);
2984 2985
}

2986 2987
bool MissionController::isEmpty(void) const {
  return _visualItems->count() <= 1;
2988 2989
}

2990 2991 2992
void MissionController::_takeoffItemNotRequiredChanged(void) {
  // Force a recalc of allowed bits
  setCurrentPlanViewSeqNum(_currentPlanViewSeqNum, true /* force */);
2993 2994
}

2995 2996
QString MissionController::surveyComplexItemName(void) const {
  return SurveyComplexItem::name;
2997 2998
}

2999 3000
QString MissionController::corridorScanComplexItemName(void) const {
  return CorridorScanComplexItem::name;
3001 3002
}

3003 3004
QString MissionController::structureScanComplexItemName(void) const {
  return StructureScanComplexItem::name;
3005 3006
}

3007 3008 3009 3010
void MissionController::_allItemsRemoved(void) {
  // When there are no mission items we track changes to firmware/vehicle type.
  // This allows a vehicle connection to adjust these items.
  _controllerVehicle->trackFirmwareVehicleTypeChanges();
3011 3012
}

3013 3014 3015 3016 3017
void MissionController::_firstItemAdded(void) {
  // As soon as the first item is added we lock the firmware/vehicle type to
  // current values. So if you then connect a vehicle it will not affect these
  // values.
  _controllerVehicle->stopTrackingFirmwareVehicleTypeChanges();
3018 3019
}

3020 3021 3022 3023 3024 3025 3026 3027 3028 3029 3030 3031 3032 3033 3034
MissionController::SendToVehiclePreCheckState
MissionController::sendToVehiclePreCheck(void) {
  if (_managerVehicle->isOfflineEditingVehicle()) {
    return SendToVehiclePreCheckStateNoActiveVehicle;
  }
  if (_managerVehicle->armed() &&
      _managerVehicle->flightMode() == _managerVehicle->missionFlightMode()) {
    return SendToVehiclePreCheckStateActiveMission;
  }
  if (_controllerVehicle->firmwareType() != _managerVehicle->firmwareType() ||
      QGCMAVLink::vehicleClass(_controllerVehicle->vehicleType()) !=
          QGCMAVLink::vehicleClass(_managerVehicle->vehicleType())) {
    return SendToVehiclePreCheckStateFirwmareVehicleMismatch;
  }
  return SendToVehiclePreCheckStateOk;
3035 3036
}

3037 3038 3039
QGroundControlQmlGlobal::AltitudeMode
MissionController::globalAltitudeMode(void) {
  return _globalAltMode;
3040 3041
}

3042 3043 3044 3045 3046 3047 3048
QGroundControlQmlGlobal::AltitudeMode
MissionController::globalAltitudeModeDefault(void) {
  if (_globalAltMode == QGroundControlQmlGlobal::AltitudeModeNone) {
    return QGroundControlQmlGlobal::AltitudeModeRelative;
  } else {
    return _globalAltMode;
  }
3049 3050
}

3051 3052 3053 3054 3055 3056
void MissionController::setGlobalAltitudeMode(
    QGroundControlQmlGlobal::AltitudeMode altMode) {
  if (_globalAltMode != altMode) {
    _globalAltMode = altMode;
    emit globalAltitudeModeChanged();
  }
3057
}