MissionController.cc 102 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * 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
#include "AppSettings.h"
12
#include "CoordinateVector.h"
13
#include "CorridorScanComplexItem.h"
14
#include "FirmwarePlugin.h"
15
#include "FixedWingLandingComplexItem.h"
16
#include "JsonHelper.h"
17 18 19
#include "KML.h"
#include "MissionCommandUIInfo.h"
#include "MissionManager.h"
20
#include "MissionSettingsItem.h"
21 22
#include "MultiVehicleManager.h"
#include "ParameterManager.h"
23
#include "PlanMasterController.h"
24
#include "QGCApplication.h"
25
#include "QGCCorePlugin.h"
26 27 28 29 30 31
#include "QGCQGeoCoordinate.h"
#include "QGroundControlQmlGlobal.h"
#include "SettingsManager.h"
#include "SimpleMissionItem.h"
#include "StructureScanComplexItem.h"
#include "SurveyComplexItem.h"
32

33
#include "src/Wima/CircularSurvey.h"
34

35
#ifndef __mobile__
36 37 38
#include "MainWindow.h"
#include "QGCQFileDialog.h"
#endif
39

40 41 42
#define UPDATE_TIMEOUT 5000 ///< How often we check for bounding box changes
#define REMAINING_DIST_TIME_UPDATE_INTERVAL                                    \
  300 ///< How often we check for bounding box changes
43

44
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")
45

46 47 48 49 50 51 52 53 54 55
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";
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
// Deprecated V1 format keys
const char *MissionController::_jsonComplexItemsKey = "complexItems";
const char *MissionController::_jsonMavAutopilotKey = "MAV_AUTOPILOT";

const int MissionController::_missionFileVersion = 2;

const QString MissionController::patternFWLandingName(
    QT_TRANSLATE_NOOP("MissionController", "Fixed Wing Landing"));
const QString MissionController::patternStructureScanName(
    QT_TRANSLATE_NOOP("MissionController", "Structure Scan"));
const QString MissionController::patternCorridorScanName(
    QT_TRANSLATE_NOOP("MissionController", "Corridor Scan"));

MissionController::MissionController(PlanMasterController *masterController,
                                     QObject *parent)
    : PlanElementController(masterController, parent),
      _missionManager(_managerVehicle->missionManager()), _missionItemCount(0),
      _visualItems(nullptr), _settingsItem(nullptr),
      _firstItemsFromVehicle(false), _itemsRequested(false),
      _inRecalcSequence(false), _surveyMissionItemName(tr("Survey")),
      _circularSurveyMissionItemName(tr("Circular Survey")),
      _appSettings(qgcApp()->toolbox()->settingsManager()->appSettings()),
      _progressPct(0), _currentPlanViewIndex(-1), _currentPlanViewItem(nullptr),
      _remainingTime(-1), _remainingDistance(-1) {
  _resetMissionFlightStatus();
  managerVehicleChanged(_managerVehicle);
  _updateTimer.setSingleShot(true);
  connect(&_updateTimer, &QTimer::timeout, this,
          &MissionController::_updateTimeout);

  _remainingDistanceTimeTimer.setInterval(REMAINING_DIST_TIME_UPDATE_INTERVAL);
  connect(&_remainingDistanceTimeTimer, &QTimer::timeout, this,
          &MissionController::_updateRemainingDistanceTime);
}

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 = 0.0;
  _missionFlightStatus.gimbalYaw = std::numeric_limits<double>::quiet_NaN();
  _missionFlightStatus.gimbalPitch = std::numeric_limits<double>::quiet_NaN();

  // Battery information

  _missionFlightStatus.mAhBattery = 0;
  _missionFlightStatus.hoverAmps = 0;
  _missionFlightStatus.cruiseAmps = 0;
  _missionFlightStatus.ampMinutesAvailable = 0;
  _missionFlightStatus.hoverAmpsTotal = 0;
  _missionFlightStatus.cruiseAmpsTotal = 0;
  _missionFlightStatus.batteryChangePoint = -1;
  _missionFlightStatus.batteriesRequired = -1;

  _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;

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

void MissionController::_init(void) {
  // We start with an empty mission
  _visualItems = new QmlObjectListModel(this);
  _addMissionSettings(_visualItems, false /* addToCenter */);
  _initAllVisualItems();
}
164

165 166 167 168 169 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
// 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 on _loadComplete if specifically requested
  if (_flyView || removeAllRequested || _itemsRequested ||
      _visualItems->count() <= 1) {
    // 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

    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);

    int i = 0;
    if (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() &&
        newMissionItems.count() != 0) {
      // First item is fake home position
      _addMissionSettings(newControllerMissionItems, false /* addToCenter */);
      MissionSettingsItem *settingsItem =
          newControllerMissionItems->value<MissionSettingsItem *>(0);
      if (!settingsItem) {
        qWarning() << "First item is not settings item";
        return;
      }
      MissionItem *fakeHomeItem = newMissionItems[0];
      if (fakeHomeItem->coordinate().latitude() != 0 ||
          fakeHomeItem->coordinate().longitude() != 0) {
        settingsItem->setCoordinate(fakeHomeItem->coordinate());
      }
      i = 1;
    }
214

215 216 217 218 219
    for (; i < newMissionItems.count(); i++) {
      const MissionItem *missionItem = newMissionItems[i];
      newControllerMissionItems->append(new SimpleMissionItem(
          _controllerVehicle, _flyView, *missionItem, this));
    }
220

221 222 223 224 225 226 227 228
    _deinitAllVisualItems();
    _visualItems->deleteLater();
    _settingsItem = nullptr;
    _visualItems = nullptr;
    _updateContainsItems(); // This will clear containsItems which will be set
                            // again below. This will re-pop Start Mission
                            // confirmation.
    _visualItems = newControllerMissionItems;
229

230 231 232 233
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ||
        _visualItems->count() == 0) {
      _addMissionSettings(_visualItems, !_flyView && _visualItems->count() >
                                                         0 /* addToCenter */);
234
    }
235

236 237
    MissionController::_scanForAdditionalSettings(_visualItems,
                                                  _controllerVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
238

239 240 241 242 243 244 245 246 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 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310
    _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::_warnIfTerrainFrameUsed(void) {
  for (int i = 1; i < _visualItems->count(); i++) {
    SimpleMissionItem *simpleItem =
        qobject_cast<SimpleMissionItem *>(_visualItems->get(i));
    if (simpleItem && simpleItem->altitudeMode() ==
                          QGroundControlQmlGlobal::AltitudeModeTerrainFrame) {
      qgcApp()->showMessage(
          tr("Warning: You are using MAV_FRAME_GLOBAL_TERRAIN_ALT in a "
             "mission. %1 does not support sending terrain tiles to vehicle.")
              .arg(qgcApp()->applicationName()));
      break;
    }
  }
}

void MissionController::_setRemainingDistance(double dist) {
  if (qFuzzyCompare(dist, _remainingDistance) == false) {
    _remainingDistance = dist;

    emit remainingDistanceChanged();
  }
}

void MissionController::_setRemainingTime(double time) {
  if (qFuzzyCompare(time, _remainingTime) == false) {
    _remainingTime = time;

    emit remainingTimeChanged();
  }
}

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";
    _warnIfTerrainFrameUsed();
    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);
  }
}
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
/// Converts from visual items to MissionItems
///     @param missionItemParent QObject parent for newly allocated
///     MissionItems, _surveyMissionItemName    (tr("Survey"))
/// @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::convertToKMLDocument(QDomDocument &document) {
  QObject *deleteParent = new QObject();
  QList<MissionItem *> rgMissionItems;

  convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
  if (rgMissionItems.count() == 0) {
    return;
  }

  const double homePositionAltitude = _settingsItem->coordinate().altitude();

  QString coord;
  QStringList coords;
  // Drop home position
  bool dropPoint = true;
  for (const auto &item : rgMissionItems) {
    if (dropPoint) {
      dropPoint = false;
      continue;
    }
    const MissionCommandUIInfo *uiInfo =
        qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle,
                                                             item->command());

    if (uiInfo && uiInfo->specifiesCoordinate() &&
        !uiInfo->isStandaloneCoordinate()) {
      double amslAltitude =
          item->param7() +
          (item->frame() == MAV_FRAME_GLOBAL ? 0 : homePositionAltitude);
      coord = QString::number(item->param6(), 'f', 7) + "," +
              QString::number(item->param5(), 'f', 7) + "," +
              QString::number(amslAltitude, 'f', 2);
      coords.append(coord);
    }
  }

  deleteParent->deleteLater();

  Kml kml;
  kml.points(coords);
  kml.save(document);
}

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;
  }
}

int MissionController::insertSimpleMissionItem(const QGeoCoordinate &coordinate,
                                               int i) {
  int sequenceNumber = _nextSequenceNumber();
  SimpleMissionItem *newItem =
      new SimpleMissionItem(_controllerVehicle, _flyView, this);
  newItem->setSequenceNumber(sequenceNumber);
  newItem->setCoordinate(coordinate);
  newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
  _initVisualItem(newItem);
  if (_visualItems->count() == 1 &&
      (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() ||
       _controllerVehicle->multiRotor())) {
    MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF
                                                    : MAV_CMD_NAV_TAKEOFF;
    if (_controllerVehicle->firmwarePlugin()
            ->supportedMissionCommands()
            .contains(takeoffCmd)) {
      newItem->setCommand(takeoffCmd);
    }
  }
  if (newItem->specifiesAltitude()) {
    double prevAltitude;
    int prevAltitudeMode;
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 531 532 533 534 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 578 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 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 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 768 769 770 771 772 773 774 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 1065 1066 1067 1068 1069 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 1106 1107 1108 1109 1110
    if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
      newItem->altitude()->setRawValue(prevAltitude);
      newItem->setAltitudeMode(
          static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
    }
  }
  newItem->setMissionFlightStatus(_missionFlightStatus);
  _visualItems->insert(i, newItem);

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

  return newItem->sequenceNumber();
}

int MissionController::insertSimpleMissionItems(
    const QList<QGeoCoordinate> &coordinates, int idx) {
  MAV_CMD mavCmd = MAV_CMD_NAV_WAYPOINT;
  if (_visualItems->count() == 1 &&
      (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() ||
       _controllerVehicle->multiRotor())) {
    mavCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF
                                        : MAV_CMD_NAV_TAKEOFF;
    if (!_controllerVehicle->firmwarePlugin()
             ->supportedMissionCommands()
             .contains(mavCmd)) {
      mavCmd = MAV_CMD_NAV_WAYPOINT;
    }
  }

  int sequenceNumber = _nextSequenceNumber();
  int size = coordinates.size();

  SimpleMissionItem *newItem = nullptr;
  bool firstItem = true;
  double prevAltitude = 0.0;
  int prevAltitudeMode = 0;
  for (int i = 0; i < size; ++i) {
    newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
    newItem->setSequenceNumber(sequenceNumber);
    newItem->setCoordinate(coordinates[i]);
    newItem->setCommand(mavCmd);
    _initSimpleItem(newItem);
    if (!firstItem ||
        (newItem->specifiesAltitude() &&
         _findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode))) {
      newItem->altitude()->setRawValue(prevAltitude);
      newItem->setAltitudeMode(
          static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
    }
    newItem->setMissionFlightStatus(_missionFlightStatus);
    _visualItems->insert(idx++, newItem);
    sequenceNumber = newItem->lastSequenceNumber() + 1;
    mavCmd = MAV_CMD_NAV_WAYPOINT;
    firstItem = false;
  }

  _recalcSequence();
  _recalcChildItems();
  _recalcWaypointLines();
  _updateTimer.start(UPDATE_TIMEOUT);

  if (newItem == nullptr)
    return -1;
  return newItem->sequenceNumber();
}

int MissionController::insertSimpleMissionItem(const MissionItem &missionItem,
                                               int i) {
  int sequenceNumber = _nextSequenceNumber();
  SimpleMissionItem *newItem =
      new SimpleMissionItem(_controllerVehicle, _flyView, missionItem, this);
  newItem->setSequenceNumber(sequenceNumber);
  _initVisualItem(newItem);
  MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF
                                                  : MAV_CMD_NAV_TAKEOFF;
  if (newItem->command() == takeoffCmd) {
    if (!_controllerVehicle->firmwarePlugin()
             ->supportedMissionCommands()
             .contains(takeoffCmd)) {
      newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
      return -1; // can not add this takeoff command for this vehicle
    }
  }
  if (newItem->specifiesAltitude()) {
    newItem->altitude()->setRawValue(missionItem.relativeAltitude());
    newItem->setAltitudeMode(
        QGroundControlQmlGlobal::AltitudeMode::AltitudeModeRelative);
  }
  newItem->setMissionFlightStatus(_missionFlightStatus);
  _visualItems->insert(i, newItem);

  return newItem->sequenceNumber();
}

int MissionController::insertSimpleMissionItem(
    const SimpleMissionItem &missionItem, int i) {
  int sequenceNumber = _nextSequenceNumber();
  SimpleMissionItem *newItem =
      new SimpleMissionItem(missionItem, _flyView, this);
  newItem->setSequenceNumber(sequenceNumber);
  _initVisualItem(newItem);
  MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF
                                                  : MAV_CMD_NAV_TAKEOFF;
  if (newItem->command() == takeoffCmd) {
    if (!_controllerVehicle->firmwarePlugin()
             ->supportedMissionCommands()
             .contains(takeoffCmd)) {
      newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
      return -1; // can not add this takeoff command for this vehicle
    }
  }
  newItem->setMissionFlightStatus(_missionFlightStatus);
  _visualItems->insert(i, newItem);

  return newItem->sequenceNumber();
}

int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i) {
  int sequenceNumber = _nextSequenceNumber();
  SimpleMissionItem *newItem =
      new SimpleMissionItem(_controllerVehicle, _flyView, this);
  newItem->setSequenceNumber(sequenceNumber);
  newItem->setCommand((
      _controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(
          MAV_CMD_DO_SET_ROI_LOCATION)
          ? MAV_CMD_DO_SET_ROI_LOCATION
          : MAV_CMD_DO_SET_ROI));
  _initVisualItem(newItem);
  newItem->setCoordinate(coordinate);

  double prevAltitude;
  int prevAltitudeMode;

  if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
    newItem->altitude()->setRawValue(prevAltitude);
    newItem->setAltitudeMode(
        static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
  }
  _visualItems->insert(i, newItem);

  _recalcAll();

  return newItem->sequenceNumber();
}

int MissionController::insertComplexMissionItem(
    QString itemName, QGeoCoordinate mapCenterCoordinate, int i) {
  ComplexMissionItem *newItem;

  int sequenceNumber = _nextSequenceNumber();
  if (itemName == _surveyMissionItemName) {
    newItem = new SurveyComplexItem(_controllerVehicle, _flyView,
                                    QString() /* kmlFile */,
                                    _visualItems /* parent */);
    newItem->setCoordinate(mapCenterCoordinate);
  } else if (itemName == patternFWLandingName) {
    newItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView,
                                              _visualItems /* parent */);
  } else if (itemName == patternStructureScanName) {
    newItem = new StructureScanComplexItem(_controllerVehicle, _flyView,
                                           QString() /* kmlFile */,
                                           _visualItems /* parent */);
  } else if (itemName == patternCorridorScanName) {
    newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView,
                                          QString() /* kmlFile */,
                                          _visualItems /* parent */);
  } else if (itemName == _circularSurveyMissionItemName) {
    newItem =
        new CircularSurvey(_controllerVehicle, _flyView,
                           QString() /* kmlFile */, _visualItems /* parent */);
  } else {
    qWarning() << "Internal error: Unknown complex item:" << itemName;
    return sequenceNumber;
  }

  return _insertComplexMissionItemWorker(newItem, i);
}

int MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName,
                                                            QString file,
                                                            int i) {
  ComplexMissionItem *newItem;

  if (itemName == _surveyMissionItemName) {
    newItem =
        new SurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
  } else if (itemName == patternStructureScanName) {
    newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, file,
                                           _visualItems);
  } else if (itemName == patternCorridorScanName) {
    newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, file,
                                          _visualItems);
  } else {
    qWarning() << "Internal error: Unknown complex item:" << itemName;
    return _nextSequenceNumber();
  }

  return _insertComplexMissionItemWorker(newItem, i);
}

int MissionController::_insertComplexMissionItemWorker(
    ComplexMissionItem *complexItem, int i) {
  int sequenceNumber = _nextSequenceNumber();
  bool surveyStyleItem = qobject_cast<SurveyComplexItem *>(complexItem) ||
                         qobject_cast<CorridorScanComplexItem *>(complexItem) ||
                         qobject_cast<CircularSurvey *>(complexItem);

  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);
  _initVisualItem(complexItem);

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

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

  return complexItem->sequenceNumber();
}

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

  bool removeSurveyStyle =
      _visualItems->value<SurveyComplexItem *>(index) ||
      _visualItems->value<CorridorScanComplexItem *>(index) ||
      _visualItems->value<CircularSurvey *>(index);
  VisualMissionItem *item =
      qobject_cast<VisualMissionItem *>(_visualItems->removeAt(index));

  _deinitVisualItem(item);
  item->deleteLater();

  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) ||
          _visualItems->value<CircularSurvey *>(i)) {
        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;
      MissionSettingsItem *settingsItem =
          _visualItems->value<MissionSettingsItem *>(0);
      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();
  setDirty(true);
}

void MissionController::removeAll(void) {
  if (_visualItems) {
    _deinitAllVisualItems();
    _visualItems->clearAndDeleteContents();
    _visualItems->deleteLater();
    _settingsItem = nullptr;
    _visualItems = new QmlObjectListModel(this);
    _addMissionSettings(_visualItems, false /* addToCenter */);
    _initAllVisualItems();
    setDirty(true);
    _resetMissionFlightStatus();
  }
}

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;
  }

  // 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(
        _controllerVehicle, _flyView, QString() /* kmlFile */,
        visualItems /* parent */);
    const QJsonObject itemObject = itemValue.toObject();
    if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
      surveyItems.append(item);
    } else {
      return false;
    }
  }

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

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

  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(_controllerVehicle, _flyView, visualItems);
      if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
        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());

  if (json.contains(_jsonPlannedHomePositionKey)) {
    SimpleMissionItem *item =
        new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);

    if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0,
                   errorString)) {
      MissionSettingsItem *settingsItem =
          new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
      settingsItem->setCoordinate(item->coordinate());
      visualItems->insert(0, settingsItem);
      item->deleteLater();
    } else {
      return false;
    }
  } else {
    _addMissionSettings(visualItems, true /* addToCenter */);
  }

  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},
  };
  if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
    return false;
  }

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

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

  if (_masterController->offline()) {
    // We only update if offline since if we are online we use the online
    // vehicle settings
    appSettings->offlineEditingFirmwareType()->setRawValue(
        AppSettings::offlineEditingFirmwareTypeFromFirmwareType(
            static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt())));
    if (json.contains(_jsonVehicleTypeKey)) {
      appSettings->offlineEditingVehicleType()->setRawValue(
          AppSettings::offlineEditingVehicleTypeFromVehicleType(
              static_cast<MAV_TYPE>(json[_jsonVehicleTypeKey].toInt())));
    }
  }
  if (json.contains(_jsonCruiseSpeedKey)) {
    appSettings->offlineEditingCruiseSpeed()->setRawValue(
        json[_jsonCruiseSpeedKey].toDouble());
  }
  if (json.contains(_jsonHoverSpeedKey)) {
    appSettings->offlineEditingHoverSpeed()->setRawValue(
        json[_jsonHoverSpeedKey].toDouble());
  }

  QGeoCoordinate homeCoordinate;
  if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey],
                                     true /* altitudeRequired */,
                                     homeCoordinate, errorString)) {
    return false;
  }
  MissionSettingsItem *settingsItem =
      new MissionSettingsItem(_controllerVehicle, _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(_controllerVehicle, _flyView, visualItems);
      if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
        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(
            _controllerVehicle, _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(_controllerVehicle, _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 ==
                 StructureScanComplexItem::jsonComplexItemTypeValue) {
        qCDebug(MissionControllerLog)
            << "Loading Structure Scan: nextSequenceNumber"
            << nextSequenceNumber;
        StructureScanComplexItem *structureItem = new StructureScanComplexItem(
            _controllerVehicle, _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(
            _controllerVehicle, _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 == CircularSurvey::CircularSurveyName) {
        qCDebug(MissionControllerLog)
            << "Loading Circular Survey: nextSequenceNumber"
            << nextSequenceNumber;
        CircularSurvey *circularSurvey = new CircularSurvey(
            _controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
        if (!circularSurvey->load(itemObject, nextSequenceNumber++,
                                  errorString)) {
          return false;
        }
        nextSequenceNumber = circularSurvey->lastSequenceNumber() + 1;
        qCDebug(MissionControllerLog)
            << "Circular Survey load complete: nextSequenceNumber"
            << nextSequenceNumber;
        visualItems->append(circularSurvey);
      } else if (complexItemType ==
                 MissionSettingsItem::jsonComplexItemTypeValue) {
        qCDebug(MissionControllerLog)
            << "Loading Mission Settings: nextSequenceNumber"
            << nextSequenceNumber;
        MissionSettingsItem *settingsItem =
            new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
        if (!settingsItem->load(itemObject, nextSequenceNumber++,
                                errorString)) {
          return false;
        }
        nextSequenceNumber = settingsItem->lastSequenceNumber() + 1;
        qCDebug(MissionControllerLog)
            << "Mission Settings load complete: nextSequenceNumber"
            << nextSequenceNumber;
        visualItems->append(settingsItem);
      } 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;
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
          }
        }
        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::validateQGCJsonFile(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) {
    // Start with planned home in center
    _addMissionSettings(visualItems, true /* addToCenter */);
    MissionSettingsItem *settingsItem =
        visualItems->value<MissionSettingsItem *>(0);

    while (!stream.atEnd()) {
      SimpleMissionItem *item =
          new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);

      if (item->load(stream)) {
        if (firstItem && plannedHomePositionInFile) {
          settingsItem->setCoordinate(item->coordinate());
        } else {
          visualItems->append(item);
Don Gagne's avatar
Don Gagne committed
1185
        }
1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197
        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;
  }
Don Gagne's avatar
Don Gagne committed
1198

1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210
  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);
      }
    }
  }
1211

1212 1213
  return true;
}
1214

1215 1216 1217 1218 1219 1220 1221
void MissionController::_initLoadedVisualItems(
    QmlObjectListModel *loadedVisualItems) {
  if (_visualItems) {
    _deinitAllVisualItems();
    _visualItems->deleteLater();
    _settingsItem = nullptr;
  }
1222

1223
  _visualItems = loadedVisualItems;
1224

1225 1226 1227
  if (_visualItems->count() == 0) {
    _addMissionSettings(_visualItems, true /* addToCenter */);
  }
1228

1229 1230
  MissionController::_scanForAdditionalSettings(_visualItems,
                                                _controllerVehicle);
1231

1232 1233
  _initAllVisualItems();
}
1234

1235 1236 1237 1238
bool MissionController::load(const QJsonObject &json, QString &errorString) {
  QString errorStr;
  QString errorMessage = tr("Mission: %1");
  QmlObjectListModel *loadedVisualItems = new QmlObjectListModel(this);
1239

1240 1241 1242 1243 1244
  if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
    errorString = errorMessage.arg(errorStr);
    return false;
  }
  _initLoadedVisualItems(loadedVisualItems);
1245

1246 1247
  return true;
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1248

1249 1250 1251 1252 1253
bool MissionController::loadJsonFile(QFile &file, QString &errorString) {
  QString errorStr;
  QString errorMessage = tr("Mission: %1");
  QJsonDocument jsonDoc;
  QByteArray bytes = file.readAll();
DonLakeFlyer's avatar
DonLakeFlyer committed
1254

1255 1256 1257 1258
  if (!JsonHelper::isJsonFile(bytes, jsonDoc, errorStr)) {
    errorString = errorMessage.arg(errorStr);
    return false;
  }
DonLakeFlyer's avatar
DonLakeFlyer committed
1259

1260 1261 1262 1263 1264 1265
  QJsonObject json = jsonDoc.object();
  QmlObjectListModel *loadedVisualItems = new QmlObjectListModel(this);
  if (!_loadItemsFromJson(json, loadedVisualItems, errorStr)) {
    errorString = errorMessage.arg(errorStr);
    return false;
  }
1266

1267
  _initLoadedVisualItems(loadedVisualItems);
1268

1269 1270
  return true;
}
1271

1272 1273 1274 1275 1276
bool MissionController::loadTextFile(QFile &file, QString &errorString) {
  QString errorStr;
  QString errorMessage = tr("Mission: %1");
  QByteArray bytes = file.readAll();
  QTextStream stream(bytes);
1277

1278 1279 1280 1281 1282
  QmlObjectListModel *loadedVisualItems = new QmlObjectListModel(this);
  if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
    errorString = errorMessage.arg(errorStr);
    return false;
  }
1283

1284
  _initLoadedVisualItems(loadedVisualItems);
1285

1286 1287
  return true;
}
1288

1289 1290 1291 1292 1293 1294
bool MissionController::readyForSaveSend(void) const {
  for (int i = 0; i < _visualItems->count(); i++) {
    VisualMissionItem *visualItem =
        qobject_cast<VisualMissionItem *>(_visualItems->get(i));
    if (!visualItem->readyForSave()) {
      return false;
1295
    }
1296
  }
1297

1298
  return true;
1299 1300
}

1301 1302 1303 1304 1305 1306 1307 1308 1309
bool MissionController::setTakeoffCommand(SimpleMissionItem &missionItem) {
  if (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() ||
      _controllerVehicle->multiRotor()) {
    MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF
                                                    : MAV_CMD_NAV_TAKEOFF;
    if (_controllerVehicle->firmwarePlugin()
            ->supportedMissionCommands()
            .contains(takeoffCmd)) {
      missionItem.setCommand(takeoffCmd);
1310
    }
1311 1312
  } else
    return false;
1313

1314
  return true;
1315 1316
}

1317 1318 1319 1320 1321 1322 1323 1324
bool MissionController::setLandCommand(SimpleMissionItem &missionItem) {
  MAV_CMD landCmd =
      _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_LAND;
  if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(
          landCmd)) {
    missionItem.setCommand(landCmd);
  } else
    return false;
1325

1326
  return true;
1327 1328
}

1329 1330
void MissionController::save(QJsonObject &json) {
  json[JsonHelper::jsonVersionKey] = _missionFileVersion;
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
  // Mission settings

  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();

  // 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(
    double homeAlt, VisualMissionItem *currentItem, VisualMissionItem *prevItem,
    double *azimuth, double *distance, double *altDifference) {
  QGeoCoordinate currentCoord = currentItem->coordinate();
  QGeoCoordinate prevCoord = prevItem->exitCoordinate();
  bool distanceOk = false;

  // Convert to fixed altitudes

  distanceOk = true;
  if (currentItem != _settingsItem &&
      currentItem->coordinateHasRelativeAltitude()) {
    currentCoord.setAltitude(homeAlt + currentCoord.altitude());
  }
  if (prevItem != _settingsItem &&
      prevItem->exitCoordinateHasRelativeAltitude()) {
    prevCoord.setAltitude(homeAlt + prevCoord.altitude());
  }

  if (distanceOk) {
    *altDifference = currentCoord.altitude() - prevCoord.altitude();
    *distance = prevCoord.distanceTo(currentCoord);
    *azimuth = prevCoord.azimuthTo(currentCoord);
  } else {
    *altDifference = 0.0;
    *azimuth = 0.0;
    *distance = 0.0;
  }
}

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;
}

void MissionController::_addWaypointLineSegment(
    CoordVectHashTable &prevItemPairHashTable, VisualItemPair &pair) {
  if (prevItemPairHashTable.contains(pair)) {
    // Pair already exists and connected, just re-use
    _linesTable[pair] = prevItemPairHashTable.take(pair);
  } else {
    // Create a new segment and wire update notifiers
    auto linevect = new CoordinateVector(pair.first->isSimpleItem()
                                             ? pair.first->coordinate()
                                             : pair.first->exitCoordinate(),
                                         pair.second->coordinate(), this);
    auto originNotifier = pair.first->isSimpleItem()
                              ? &VisualMissionItem::coordinateChanged
                              : &VisualMissionItem::exitCoordinateChanged;
    auto endNotifier = &VisualMissionItem::coordinateChanged;

    // Use signals/slots to update the coordinate endpoints
    connect(pair.first, originNotifier, linevect,
            &CoordinateVector::setCoordinate1);
    connect(pair.second, endNotifier, linevect,
            &CoordinateVector::setCoordinate2);

    // FIXME: We should ideally have signals for 2D position change, alt change,
    // and 3D position change Not optimal, but still pretty fast, do a full
    // update of range/bearing/altitudes
    connect(pair.second, &VisualMissionItem::coordinateChanged, this,
            &MissionController::_recalcMissionFlightStatus);
    _linesTable[pair] = linevect;
  }
}

void MissionController::_recalcWaypointLines(void) {
  bool firstCoordinateItem = true;
  VisualMissionItem *lastCoordinateItem =
      qobject_cast<VisualMissionItem *>(_visualItems->get(0));

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

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

  CoordVectHashTable old_table = _linesTable;
  _linesTable.clear();
  _waypointLines.clear();
  _waypointPath.clear();

  bool linkEndToHome;
  SimpleMissionItem *lastItem =
      _visualItems->value<SimpleMissionItem *>(_visualItems->count() - 1);
  if (lastItem && (int)lastItem->command() == MAV_CMD_NAV_RETURN_TO_LAUNCH) {
    linkEndToHome = true;
  } else {
    linkEndToHome = _settingsItem->missionEndRTL();
  }

  bool linkStartToHome = false;
  for (int i = 1; i < _visualItems->count(); i++) {
    VisualMissionItem *item =
        qobject_cast<VisualMissionItem *>(_visualItems->get(i));

    // 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 (firstCoordinateItem && item->isSimpleItem()) {
      MAV_CMD command =
          (MAV_CMD)qobject_cast<SimpleMissionItem *>(item)->command();
      if (command == MAV_CMD_NAV_TAKEOFF ||
          command == MAV_CMD_NAV_VTOL_TAKEOFF) {
        linkStartToHome = true;
      }
    }

    if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
      firstCoordinateItem = false;
      if (lastCoordinateItem != _settingsItem ||
          (homePositionValid && linkStartToHome)) {
        if (!_flyView) {
          VisualItemPair pair(lastCoordinateItem, item);
          _addWaypointLineSegment(old_table, pair);
1498
        }
1499 1500 1501
      }
      _waypointPath.append(QVariant::fromValue(item->coordinate()));
      lastCoordinateItem = item;
1502
    }
1503
  }
1504

1505 1506 1507
  if (linkStartToHome && homePositionValid) {
    _waypointPath.prepend(QVariant::fromValue(_settingsItem->coordinate()));
  }
1508

1509 1510
  if (linkEndToHome && lastCoordinateItem != _settingsItem &&
      homePositionValid) {
1511
    if (!_flyView) {
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
      VisualItemPair pair(lastCoordinateItem, _settingsItem);
      _addWaypointLineSegment(old_table, pair);
    } else {
      _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
    }
  }

  {
    // Create a temporary QObjectList and replace the model data
    QObjectList objs;
    objs.reserve(_linesTable.count());
    for (CoordinateVector *vect : _linesTable.values()) {
      objs.append(vect);
    }

    // We don't delete here because many links may still be valid
    _waypointLines.swapObjectList(objs);
  }

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

  _recalcMissionFlightStatus();

  if (_waypointPath.count() == 0) {
    // MapPolyLine has a bug where if you can 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 waypointLinesChanged();
  emit waypointPathChanged();
}

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);
1589 1590
}

1591 1592 1593 1594 1595 1596 1597 1598 1599 1600 1601 1602 1603 1604
/// 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);
1605
    } else {
1606 1607
      _addCruiseTime(cruiseTime, distance, seqNum);
      _addCruiseTime(extraTime, 0, -1);
1608
    }
1609 1610 1611 1612
  } else {
    if (_controllerVehicle->multiRotor()) {
      _addHoverTime(hoverTime, distance, seqNum);
      _addHoverTime(extraTime, 0, -1);
1613
    } else {
1614 1615
      _addCruiseTime(cruiseTime, distance, seqNum);
      _addCruiseTime(extraTime, 0, -1);
1616
    }
1617
  }
1618 1619
}

1620 1621 1622 1623
void MissionController::_recalcMissionFlightStatus() {
  if (!_visualItems->count()) {
    return;
  }
1624

1625 1626 1627
  bool firstCoordinateItem = true;
  VisualMissionItem *lastCoordinateItem =
      qobject_cast<VisualMissionItem *>(_visualItems->get(0));
1628

1629
  bool showHomePosition = _settingsItem->coordinate().isValid();
1630

1631
  qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1632

1633 1634 1635
  // 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.
1636

1637 1638 1639 1640
  // No values for first item
  lastCoordinateItem->setAltDifference(0.0);
  lastCoordinateItem->setAzimuth(0.0);
  lastCoordinateItem->setDistance(0.0);
1641

1642 1643 1644 1645
  double minAltSeen = 0.0;
  double maxAltSeen = 0.0;
  const double homePositionAltitude = _settingsItem->coordinate().altitude();
  minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1646

1647
  _resetMissionFlightStatus();
1648

1649 1650 1651
  bool vtolInHover = true;
  bool linkStartToHome = false;
  bool linkEndToHome = false;
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
  if (showHomePosition) {
    SimpleMissionItem *lastItem =
        _visualItems->value<SimpleMissionItem *>(_visualItems->count() - 1);
    if (lastItem && (int)lastItem->command() == MAV_CMD_NAV_RETURN_TO_LAUNCH) {
      linkEndToHome = true;
    } else {
      linkEndToHome = _settingsItem->missionEndRTL();
    }
  }

  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);

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

    // Look for speed changed
    double newSpeed = item->specifiedFlightSpeed();
    if (!qIsNaN(newSpeed)) {
      if (_controllerVehicle->multiRotor()) {
        _missionFlightStatus.hoverSpeed = newSpeed;
      } else if (_controllerVehicle->vtol()) {
        if (vtolInHover) {
          _missionFlightStatus.hoverSpeed = newSpeed;
1681
        } else {
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 1754 1755 1756 1757 1758 1759 1760 1761 1762 1763 1764 1765 1766 1767 1768 1769 1770 1771 1772 1773 1774 1775 1776 1777 1778 1779 1780 1781 1782 1783 1784 1785 1786 1787 1788 1789 1790 1791 1792 1793 1794 1795 1796 1797 1798 1799 1800 1801 1802 1803 1804 1805
          _missionFlightStatus.cruiseSpeed = newSpeed;
        }
      } else {
        _missionFlightStatus.cruiseSpeed = newSpeed;
      }
      _missionFlightStatus.vehicleSpeed = newSpeed;
    }

    // Look for gimbal change
    double gimbalYaw = item->specifiedGimbalYaw();
    if (!qIsNaN(gimbalYaw)) {
      _missionFlightStatus.gimbalYaw = gimbalYaw;
    }
    double gimbalPitch = item->specifiedGimbalPitch();
    if (!qIsNaN(gimbalPitch)) {
      _missionFlightStatus.gimbalPitch = gimbalPitch;
    }

    if (i == 0) {
      // We only process speed and gimbal from Mission Settings item
      continue;
    }

    // Link back to home if first item is takeoff and we have home position
    if (firstCoordinateItem && simpleItem &&
        (simpleItem->command() == MAV_CMD_NAV_TAKEOFF ||
         simpleItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
      if (showHomePosition) {
        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(homePositionAltitude, _settingsItem,
                                  simpleItem, &azimuth, &distance,
                                  &altDifference);
          double takeoffTime =
              qAbs(altDifference) /
              _appSettings->offlineEditingAscentSpeed()->rawValue().toDouble();
          _addHoverTime(takeoffTime, 0, -1);
        }
      }
    }

    // Update VTOL state
    if (simpleItem && _controllerVehicle->vtol()) {
      switch (simpleItem->command()) {
      case MAV_CMD_NAV_TAKEOFF:
        vtolInHover = false;
        break;
      case MAV_CMD_NAV_VTOL_TAKEOFF:
        vtolInHover = true;
        break;
      case MAV_CMD_NAV_LAND:
        vtolInHover = false;
        break;
      case MAV_CMD_NAV_VTOL_LAND:
        vtolInHover = true;
        break;
      case MAV_CMD_DO_VTOL_TRANSITION: {
        int transitionState = simpleItem->missionItem().param1();
        if (transitionState == MAV_VTOL_STATE_TRANSITION_TO_MC) {
          vtolInHover = true;
        } else if (transitionState == MAV_VTOL_STATE_TRANSITION_TO_FW) {
          vtolInHover = false;
        }
      } break;
      default:
        break;
      }
    }

    _addTimeDistance(vtolInHover, 0, 0, item->additionalTimeDelay(), 0, -1);

    if (item->specifiesCoordinate()) {
      // Keep track of the min/max altitude for all waypoints so we can show
      // altitudes as a percentage

      double absoluteAltitude = item->coordinate().altitude();
      if (item->coordinateHasRelativeAltitude()) {
        absoluteAltitude += homePositionAltitude;
      }
      minAltSeen = std::min(minAltSeen, absoluteAltitude);
      maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

      double terrainAltitude = item->terrainAltitude();
      if (!qIsNaN(terrainAltitude)) {
        minAltSeen = std::min(minAltSeen, terrainAltitude);
        maxAltSeen = std::max(maxAltSeen, terrainAltitude);
      }

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

        // Update vehicle yaw assuming direction to next waypoint
        if (item != lastCoordinateItem) {
          _missionFlightStatus.vehicleYaw =
              lastCoordinateItem->exitCoordinate().azimuthTo(
                  item->coordinate());
          lastCoordinateItem->setMissionVehicleYaw(
              _missionFlightStatus.vehicleYaw);
        }

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

          _calcPrevWaypointValues(homePositionAltitude, item,
                                  lastCoordinateItem, &azimuth, &distance,
                                  &altDifference);
          item->setAltDifference(altDifference);
          item->setAzimuth(azimuth);
          item->setDistance(distance);

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

          // Calculate time/distance
          double hoverTime = distance / _missionFlightStatus.hoverSpeed;
          double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
          _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance,
                           item->sequenceNumber());
1806
        }
1807

1808
        if (complexItem) {
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
          // 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(vtolInHover, hoverTime, cruiseTime, 0, distance,
                           item->sequenceNumber());
        }

        item->setMissionFlightStatus(_missionFlightStatus);

        lastCoordinateItem = item;
      }
    }
  }
  lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);

  if (linkEndToHome && lastCoordinateItem != _settingsItem) {
    double azimuth, distance, altDifference;
    _calcPrevWaypointValues(homePositionAltitude, lastCoordinateItem,
                            _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(vtolInHover, 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);

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

    if (item->specifiesCoordinate()) {
      double absoluteAltitude = item->coordinate().altitude();
      if (item->coordinateHasRelativeAltitude()) {
        absoluteAltitude += homePositionAltitude;
      }
      if (altRange == 0.0) {
        item->setAltPercent(0.0);
        item->setTerrainPercent(qQNaN());
        item->setTerrainCollision(false);
      } else {
        item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
        double terrainAltitude = item->terrainAltitude();
        if (qIsNaN(terrainAltitude)) {
          item->setTerrainPercent(qQNaN());
          item->setTerrainCollision(false);
1880
        } else {
1881 1882
          item->setTerrainPercent((terrainAltitude - minAltSeen) / altRange);
          item->setTerrainCollision(absoluteAltitude < terrainAltitude);
1883
        }
1884
      }
1885
    }
1886
  }
1887

1888 1889
  _updateTimer.start(UPDATE_TIMEOUT);
}
1890

1891 1892 1893 1894 1895 1896
// 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;
  }
1897

1898
  // Setup ascending sequence numbers for all visual items
1899

1900 1901 1902 1903 1904 1905 1906 1907 1908
  _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;
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
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void) {
  VisualMissionItem *currentParentItem =
      qobject_cast<VisualMissionItem *>(_visualItems->get(0));

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

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

    // Set up non-coordinate item child hierarchy
    if (item->specifiesCoordinate()) {
      item->childItems()->clear();
      currentParentItem = item;
    } else if (item->isSimpleItem()) {
      currentParentItem->childItems()->append(item);
    }
  }
}

void MissionController::_setPlannedHomePositionFromFirstCoordinate(
    const QGeoCoordinate &clickCoordinate) {
  QGeoCoordinate firstCoordinate;

  if (_settingsItem->coordinate().isValid()) {
    return;
  }

  // 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);

    if (item->specifiesCoordinate()) {
      firstCoordinate = item->coordinate();
      break;
    }
  }

  // No item specifying a coordinate was found, in this case it we have a
  // clickCoordinate use that
  if (!firstCoordinate.isValid()) {
    firstCoordinate = clickCoordinate;
  }

  if (firstCoordinate.isValid()) {
    QGeoCoordinate plannedHomeCoord =
        firstCoordinate.atDistanceAndAzimuth(30, 0);
    plannedHomeCoord.setAltitude(0);
    _settingsItem->setCoordinate(plannedHomeCoord);
  }
}

/// @param clickCoordinate The location of the user click when inserting a new
/// item
void MissionController::_recalcAllWithClickCoordinate(
    const QGeoCoordinate &clickCoordinate) {
  if (!_flyView) {
    _setPlannedHomePositionFromFirstCoordinate(clickCoordinate);
  }
  _recalcSequence();
  _recalcChildItems();
  _recalcWaypointLines();
  _updateTimer.start(UPDATE_TIMEOUT);
}

void MissionController::_recalcAll(void) {
  QGeoCoordinate emptyCoord;
  _recalcAllWithClickCoordinate(emptyCoord);
}

void MissionController::_enableDisableRemainingDistTimeCalculation(
    bool flying) {
  if (flying) {
    _remainingDistanceTimeTimer.start();
  } else {
    _remainingDistanceTimeTimer.stop();
    _setRemainingTime(-1);
    _setRemainingDistance(-1);
  }
}

void MissionController::_updateRemainingDistanceTime() {
  double dist = 0;
  double time = 0;
  bool success = distanceTimeToMissionEnd(
      dist, time, _missionManager->currentIndex() /*missionIndex >= 1*/,
      true /* useVehiclePostion */);
  if (success) {
    _setRemainingTime(time);
    _setRemainingDistance(dist);
  } else {
    _setRemainingTime(-1);
    _setRemainingDistance(-1);
  }
}
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 2078 2079 2080 2081 2082 2083 2084 2085 2086 2087 2088 2089 2090 2091 2092 2093 2094 2095 2096 2097 2098 2099 2100 2101 2102 2103 2104 2105 2106 2107 2108 2109 2110 2111 2112 2113 2114 2115 2116 2117 2118 2119 2120 2121 2122 2123 2124 2125 2126 2127 2128 2129 2130 2131 2132 2133 2134 2135 2136 2137 2138 2139 2140 2141 2142 2143 2144 2145 2146 2147 2148 2149 2150 2151 2152 2153 2154 2155 2156 2157 2158 2159 2160 2161 2162 2163 2164 2165 2166 2167 2168 2169 2170 2171 2172 2173 2174 2175 2176 2177 2178 2179 2180 2181 2182 2183 2184 2185 2186 2187 2188 2189 2190 2191 2192 2193 2194 2195 2196 2197 2198 2199 2200 2201 2202
/// Initializes a new set of mission items
void MissionController::_initAllVisualItems(void) {
  // Setup home position at index 0

  _settingsItem = qobject_cast<MissionSettingsItem *>(_visualItems->get(0));
  if (!_settingsItem) {
    qWarning() << "First item not MissionSettingsItem";
    return;
  }
  if (!_flyView) {
    _settingsItem->setIsCurrentItem(true);
  }

  if (_managerVehicle->homePosition().isValid()) {
    _settingsItem->setCoordinate(_managerVehicle->homePosition());
  }

  connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this,
          &MissionController::_recalcAll);
  connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged, 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);
  }

  _recalcAll();

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

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

  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) {
  if (visualItem->isSimpleItem()) {
    SimpleMissionItem *simpleItem =
        qobject_cast<SimpleMissionItem *>(visualItem);
    if (simpleItem) {
      _initSimpleItem(simpleItem);
    } else {
      qWarning() << "isSimpleItem == true, yet not SimpleMissionItem";
    }
  } else {
    ComplexMissionItem *complexItem =
        qobject_cast<ComplexMissionItem *>(visualItem);
    if (complexItem) {
      _initComplexItem(complexItem);
    } else {
      qWarning() << "ComplexMissionItem not found";
    }
  }
}

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

  connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged, this,
          &MissionController::_recalcWaypointLines);
  connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,
          this, &MissionController::_recalcWaypointLines);
  connect(visualItem,
          &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged, this,
          &MissionController::_recalcWaypointLines);
  connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged, this,
          &MissionController::_recalcMissionFlightStatus);
  connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged, this,
          &MissionController::_recalcMissionFlightStatus);
  connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged, this,
          &MissionController::_recalcMissionFlightStatus);
  connect(visualItem, &VisualMissionItem::terrainAltitudeChanged, this,
          &MissionController::_recalcMissionFlightStatus);
  connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged, this,
          &MissionController::_recalcMissionFlightStatus);
  connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged, this,
          &MissionController::_recalcSequence);
}

void MissionController::_initSimpleItem(SimpleMissionItem *item) {
  _initVisualItemCommon(item);
  // We need to track commandChanged on simple item since recalc has special
  // handling for takeoff command
  connect(&item->missionItem()._commandFact, &Fact::valueChanged, this,
          &MissionController::_itemCommandChanged);
}

void MissionController::_initComplexItem(ComplexMissionItem *item) {
  _initVisualItemCommon(item);
  connect(item, &ComplexMissionItem::complexDistanceChanged, this,
          &MissionController::_recalcMissionFlightStatus);
  connect(item, &ComplexMissionItem::greatestDistanceToChanged, this,
          &MissionController::_recalcMissionFlightStatus);
}

void MissionController::_deinitVisualItem(VisualMissionItem *visualItem) {
  // Disconnect all signals
  disconnect(visualItem, 0, 0, 0);
}

void MissionController::_itemCommandChanged(void) {
  _recalcChildItems();
  _recalcWaypointLines();
}

void MissionController::managerVehicleChanged(Vehicle *managerVehicle) {
  if (_managerVehicle) {
    _missionManager->disconnect(this);
    _managerVehicle->disconnect(this);
    _managerVehicle = NULL;
    _missionManager = NULL;
  }

  _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::homePositionChanged, this,
          &MissionController::_managerVehicleHomePositionChanged);
  connect(_managerVehicle, &Vehicle::defaultCruiseSpeedChanged, this,
          &MissionController::_recalcMissionFlightStatus);
  connect(_managerVehicle, &Vehicle::defaultHoverSpeedChanged, this,
          &MissionController::_recalcMissionFlightStatus);
  connect(_managerVehicle, &Vehicle::vehicleTypeChanged, this,
          &MissionController::complexMissionItemNamesChanged);
  connect(_managerVehicle, &Vehicle::flyingChanged, this,
          &MissionController::_enableDisableRemainingDistTimeCalculation);

  if (!_masterController->offline()) {
    _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
  }

  emit complexMissionItemNamesChanged();
  emit resumeMissionIndexChanged();
}

void MissionController::_managerVehicleHomePositionChanged(
    const QGeoCoordinate &homePosition) {
  if (_visualItems) {
    bool currentDirtyBit = dirty();

    MissionSettingsItem *settingsItem =
        qobject_cast<MissionSettingsItem *>(_visualItems->get(0));
    if (settingsItem) {
      settingsItem->setHomePositionFromVehicle(homePosition);
    } else {
      qWarning() << "First item is not MissionSettingsItem";
    }
2203

2204 2205 2206 2207
    if (!currentDirtyBit) {
      // Don't let this trip the dirty bit. Otherwise plan will keep getting
      // marked dirty if vehicle home changes.
      _visualItems->setDirty(false);
2208
    }
2209
  }
2210 2211
}

2212 2213
void MissionController::_inProgressChanged(bool inProgress) {
  emit syncInProgressChanged(inProgress);
2214
}
2215

2216 2217 2218 2219 2220 2221
bool MissionController::_findPreviousAltitude(int newIndex,
                                              double *prevAltitude,
                                              int *prevAltitudeMode) {
  bool found = false;
  double foundAltitude;
  int foundAltitudeMode;
2222

2223 2224 2225 2226
  if (newIndex > _visualItems->count()) {
    return false;
  }
  newIndex--;
2227

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

2232 2233 2234 2235 2236 2237 2238 2239 2240 2241
    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;
2242
        }
2243
      }
2244
    }
2245
  }
2246

2247 2248 2249 2250
  if (found) {
    *prevAltitude = foundAltitude;
    *prevAltitudeMode = foundAltitudeMode;
  }
2251

2252
  return found;
2253
}
2254

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

2260 2261 2262
double MissionController::_normalizeLon(double lon) {
  // Normalize longitude to range: 0 to 360, W to E
  return lon + 180.0;
2263 2264
}

2265
/// Add the Mission Settings complex item to the front of the items
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 2313 2314 2315 2316 2317 2318 2319 2320 2321 2322 2323 2324 2325 2326 2327 2328 2329 2330 2331 2332
void MissionController::_addMissionSettings(QmlObjectListModel *visualItems,
                                            bool addToCenter) {
  MissionSettingsItem *settingsItem =
      new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);

  qCDebug(MissionControllerLog)
      << "_addMissionSettings addToCenter" << addToCenter;

  visualItems->insert(0, settingsItem);

  if (addToCenter) {
    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);
          } else {
            firstCoordSet = true;
            north = _normalizeLat(item->coordinate().latitude());
            south = north;
            east = _normalizeLon(item->coordinate().longitude());
            west = east;
          }
        }
      }

      if (firstCoordSet) {
        settingsItem->setCoordinate(
            QGeoCoordinate((south + ((north - south) / 2)) - 90.0,
                           (west + ((east - west) / 2)) - 180.0, 0.0));
      }
    }
  } else if (_managerVehicle->homePosition().isValid()) {
    settingsItem->setCoordinate(_managerVehicle->homePosition());
  }
}

int MissionController::resumeMissionIndex(void) const {

  int resumeIndex = 0;

  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;
2333
    }
2334
  }
2335

2336
  return resumeIndex;
2337
}
2338

2339 2340 2341 2342 2343 2344 2345
int MissionController::currentMissionIndex(void) const {
  if (!_flyView) {
    return -1;
  } else {
    int currentIndex = _missionManager->currentIndex();
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
      currentIndex++;
2346
    }
2347 2348
    return currentIndex;
  }
2349 2350
}

2351 2352 2353 2354 2355
void MissionController::_currentMissionIndexChanged(int sequenceNumber) {
  if (_flyView) {
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
      sequenceNumber++;
    }
2356

2357 2358 2359 2360
    for (int i = 0; i < _visualItems->count(); i++) {
      VisualMissionItem *item =
          qobject_cast<VisualMissionItem *>(_visualItems->get(i));
      item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
2361
    }
2362 2363
    emit currentMissionIndexChanged(currentMissionIndex());
  }
2364
}
2365

2366 2367
bool MissionController::syncInProgress(void) const {
  return _missionManager->inProgress();
2368 2369
}

2370 2371
bool MissionController::dirty(void) const {
  return _visualItems ? _visualItems->dirty() : false;
2372 2373
}

2374 2375 2376 2377
void MissionController::setDirty(bool dirty) {
  if (_visualItems) {
    _visualItems->setDirty(dirty);
  }
2378
}
2379

2380 2381 2382 2383
void MissionController::_scanForAdditionalSettings(
    QmlObjectListModel *visualItems, Vehicle *vehicle) {
  // First we look for a Fixed Wing Landing Pattern which is at the end
  FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, vehicle);
2384

2385 2386 2387 2388
  int scanIndex = 0;
  while (scanIndex < visualItems->count()) {
    VisualMissionItem *visualItem =
        visualItems->value<VisualMissionItem *>(scanIndex);
2389

2390 2391 2392
    qCDebug(MissionControllerLog)
        << "MissionController::_scanForAdditionalSettings count:scanIndex"
        << visualItems->count() << scanIndex;
2393

2394 2395 2396 2397 2398 2399 2400 2401 2402 2403 2404 2405 2406 2407 2408
    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, vehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
2409
    } else {
2410 2411
      // Complex item, can't have sections
      scanIndex++;
DonLakeFlyer's avatar
DonLakeFlyer committed
2412
    }
2413
  }
2414
}
2415

2416 2417
void MissionController::_updateContainsItems(void) {
  emit containsItemsChanged(containsItems());
2418
}
2419

2420 2421
bool MissionController::containsItems(void) const {
  return _visualItems ? _visualItems->count() > 1 : false;
2422
}
2423

2424 2425 2426 2427 2428 2429 2430 2431 2432 2433 2434 2435
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();
  }
2436
}
DonLakeFlyer's avatar
DonLakeFlyer committed
2437

2438 2439
QStringList MissionController::complexMissionItemNames(void) const {
  QStringList complexItems;
DonLakeFlyer's avatar
DonLakeFlyer committed
2440

2441 2442
  complexItems.append(_surveyMissionItemName);
  complexItems.append(patternCorridorScanName);
2443 2444
  // Circular Survey not added here, as it can only be used together with
  // WimaView.
2445 2446 2447 2448 2449 2450
  if (_controllerVehicle->fixedWing()) {
    complexItems.append(patternFWLandingName);
  }
  if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
    complexItems.append(patternStructureScanName);
  }
2451

2452 2453
  return qgcApp()->toolbox()->corePlugin()->complexMissionItemNames(
      _controllerVehicle, complexItems);
2454
}
2455

2456 2457 2458 2459 2460
void MissionController::resumeMission(int resumeIndex) {
  if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
    resumeIndex--;
  }
  _missionManager->generateResumeMission(resumeIndex);
2461
}
DonLakeFlyer's avatar
DonLakeFlyer committed
2462

2463 2464 2465 2466 2467 2468
QGeoCoordinate MissionController::plannedHomePosition(void) const {
  if (_settingsItem) {
    return _settingsItem->coordinate();
  } else {
    return QGeoCoordinate();
  }
DonLakeFlyer's avatar
DonLakeFlyer committed
2469 2470
}

2471 2472 2473 2474 2475 2476 2477 2478
void MissionController::applyDefaultMissionAltitude(void) {
  double defaultAltitude =
      _appSettings->defaultMissionItemAltitude()->rawValue().toDouble();

  for (int i = 1; i < _visualItems->count(); i++) {
    VisualMissionItem *item = _visualItems->value<VisualMissionItem *>(i);
    item->applyNewAltitude(defaultAltitude);
  }
DonLakeFlyer's avatar
DonLakeFlyer committed
2479 2480
}

2481 2482 2483 2484 2485
void MissionController::_progressPctChanged(double progressPct) {
  if (!qFuzzyCompare(progressPct, _progressPct)) {
    _progressPct = progressPct;
    emit progressPctChanged(progressPct);
  }
DonLakeFlyer's avatar
DonLakeFlyer committed
2486
}
2487

2488 2489 2490 2491
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);
2492 2493
}

2494 2495 2496 2497 2498 2499 2500 2501 2502 2503 2504 2505 2506 2507 2508 2509 2510 2511 2512 2513 2514 2515
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;
2516
    } else {
2517 2518 2519 2520 2521 2522 2523 2524 2525 2526 2527 2528 2529 2530 2531 2532 2533 2534 2535 2536 2537 2538 2539 2540 2541 2542 2543 2544 2545 2546 2547 2548 2549 2550 2551 2552 2553 2554 2555 2556 2557 2558 2559 2560 2561 2562
      // 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();
  }
}

int MissionController::currentPlanViewIndex(void) const {
  return _currentPlanViewIndex;
}

bool MissionController::distanceTimeToMissionEnd(
    double &remainingDistance, double &remainingTime, int missionIndex,
    bool useVehiclePosition) const {
  // input check
  if (_visualItems == nullptr || _visualItems->count() < 1 || !_flyView ||
      missionIndex < 1 || missionIndex > _visualItems->count()) {
    return false;
  }
  // check if vehicle is flying and fetch vehicle coordinate
  QGeoCoordinate vehiclePosition;
  if (_managerVehicle && _managerVehicle->flying() && useVehiclePosition) {
    vehiclePosition = _managerVehicle->coordinate();
  } else {
    if (useVehiclePosition) {
      useVehiclePosition = false;
      qWarning(
          "MissionController::distanceTimeToMissionEnd(): vehicle position "
          "can't be used. Either no vehicle connected, or vehicle not flying.");
2563
    }
2564
  }
2565

2566 2567
  remainingDistance = 0;
  remainingTime = 0;
2568

2569 2570 2571
  bool firstCoordinateItem = true;
  VisualMissionItem *lastCoordinateItem =
      qobject_cast<VisualMissionItem *>(_visualItems->get(0));
2572

2573
  bool showHomePosition = _settingsItem->coordinate().isValid();
2574

2575 2576 2577
  // 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.
2578

2579 2580 2581 2582
  // No values for first item
  lastCoordinateItem->setAltDifference(0.0);
  lastCoordinateItem->setAzimuth(0.0);
  lastCoordinateItem->setDistance(0.0);
2583

2584
  const double homePositionAltitude = _settingsItem->coordinate().altitude();
2585

2586 2587
  bool linkStartToHome = false;
  bool linkEndToHome = false;
2588

2589 2590 2591 2592 2593 2594 2595
  if (showHomePosition) {
    SimpleMissionItem *lastItem =
        _visualItems->value<SimpleMissionItem *>(_visualItems->count() - 1);
    if (lastItem && int(lastItem->command()) == MAV_CMD_NAV_RETURN_TO_LAUNCH) {
      linkEndToHome = true;
    } else {
      linkEndToHome = _settingsItem->missionEndRTL();
2596
    }
2597
  }
2598

2599 2600 2601 2602 2603
  // determine speed at waypoint with index missionIndex
  double currentSpeed = _settingsItem->specifiedFlightSpeed();
  currentSpeed = !qIsNaN(currentSpeed) ? currentSpeed : 5;
  for (int i = 1; i < missionIndex; ++i) {
    SimpleMissionItem *simpleItem = _visualItems->value<SimpleMissionItem *>(i);
2604

2605 2606 2607 2608
    if (simpleItem != nullptr) {
      double speed = simpleItem->specifiedFlightSpeed();
      if (!qIsNaN(speed))
        currentSpeed = speed;
2609
    }
2610
  }
2611

2612 2613 2614 2615 2616 2617 2618 2619 2620 2621
  // calculate dist and time from current vehicle pos. to mission item with
  // index missionIndex
  if (useVehiclePosition) {
    // find valid coordinate
    for (int i = missionIndex; i < _visualItems->count(); ++i) {
      SimpleMissionItem *simpleItem =
          _visualItems->value<SimpleMissionItem *>(missionIndex);
      if (simpleItem != nullptr && simpleItem->specifiesCoordinate()) {
        double dist = vehiclePosition.distanceTo(simpleItem->coordinate());
        double time = dist / currentSpeed;
2622

2623 2624 2625 2626 2627 2628
        remainingDistance += dist;
        remainingTime += time;
        break;
      }
    }
  }
2629

2630 2631 2632 2633 2634 2635
  // iterate over mission items starting at currentMissionIdx-1 and determine
  // time and distance
  for (int i = missionIndex; i < _visualItems->count(); i++) {
    VisualMissionItem *item =
        qobject_cast<VisualMissionItem *>(_visualItems->get(i));
    SimpleMissionItem *simpleItem = qobject_cast<SimpleMissionItem *>(item);
2636

2637 2638 2639
    // Assume the worst
    item->setAzimuth(0.0);
    item->setDistance(0.0);
2640

2641 2642 2643 2644 2645
    // Look for speed changed
    double newSpeed = item->specifiedFlightSpeed();
    if (!qIsNaN(newSpeed)) {
      currentSpeed = newSpeed;
    }
2646

2647 2648 2649 2650 2651 2652 2653 2654 2655
    // Link back to home if first item is takeoff and we have home position
    if (firstCoordinateItem && simpleItem &&
        (simpleItem->command() == MAV_CMD_NAV_TAKEOFF ||
         simpleItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
      if (showHomePosition) {
        linkStartToHome = true;
        if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
          // We have to special case takeoff, assuming vehicle takes off
          // straight up to specified altitude
2656

2657 2658 2659 2660 2661 2662
          QGeoCoordinate itemCoordinate = item->exitCoordinate();
          QGeoCoordinate settingsCoordinate = _settingsItem->coordinate();
          if (item->exitCoordinateHasRelativeAltitude()) {
            itemCoordinate.setAltitude(homePositionAltitude +
                                       settingsCoordinate.altitude());
          }
2663

2664 2665
          double altDifference =
              settingsCoordinate.altitude() - itemCoordinate.altitude();
2666

2667 2668 2669 2670
          double takeoffTime =
              qAbs(altDifference) /
              _appSettings->offlineEditingAscentSpeed()->rawValue().toDouble();
          remainingTime += takeoffTime;
2671
        }
2672
      }
2673 2674
    }

2675
    remainingTime += item->additionalTimeDelay();
2676

2677 2678
    if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
      firstCoordinateItem = false;
2679

2680 2681 2682
      if (lastCoordinateItem != _settingsItem || linkStartToHome) {
        // This is a subsequent waypoint or we are forcing the first waypoint
        // back to home
2683

2684 2685
        QGeoCoordinate currentCoord = item->coordinate();
        QGeoCoordinate prevCoord = lastCoordinateItem->exitCoordinate();
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
        if (item != _settingsItem && item->coordinateHasRelativeAltitude()) {
          currentCoord.setAltitude(homePositionAltitude +
                                   currentCoord.altitude());
        }
        if (lastCoordinateItem != _settingsItem &&
            lastCoordinateItem->exitCoordinateHasRelativeAltitude()) {
          prevCoord.setAltitude(homePositionAltitude + prevCoord.altitude());
        }

        double distance = prevCoord.distanceTo(currentCoord);
        double time = distance / currentSpeed;

        remainingDistance += distance;
        remainingTime += time;
      }

      lastCoordinateItem = item;
    }

    if (simpleItem != nullptr &&
        (simpleItem->command() == MAV_CMD_NAV_LAND ||
         simpleItem->command() == MAV_CMD_NAV_LAND_LOCAL ||
         simpleItem->command() == MAV_CMD_NAV_VTOL_LAND)) {

      double alt = 0;
      if (i == missionIndex) {
        alt = _managerVehicle->altitudeRelative()->rawValue().toDouble();
      } else {
        QGeoCoordinate currentCoord = simpleItem->coordinate();

        if (simpleItem->coordinateHasRelativeAltitude()) {
          currentCoord.setAltitude(homePositionAltitude +
                                   currentCoord.altitude());
        }

        alt = currentCoord.altitude() - homePositionAltitude;
      }
      double landTime =
          qAbs(alt) /
          _appSettings->offlineEditingDescentSpeed()->rawValue().toDouble();

      remainingTime += landTime;
    }
  }

  if (linkEndToHome && lastCoordinateItem != _settingsItem) {

    QGeoCoordinate currentCoord = lastCoordinateItem->coordinate();
    QGeoCoordinate prevCoord = _settingsItem->exitCoordinate();

    if (lastCoordinateItem != _settingsItem &&
        lastCoordinateItem->coordinateHasRelativeAltitude()) {
      currentCoord.setAltitude(homePositionAltitude + currentCoord.altitude());
    }

    double altDifference = currentCoord.altitude() - prevCoord.altitude();
    double distance = currentCoord.distanceTo(prevCoord);

    double time = distance / currentSpeed;
    double landTime =
        qAbs(altDifference) /
        _appSettings->offlineEditingDescentSpeed()->rawValue().toDouble();

    remainingDistance += distance;
    remainingTime += time + landTime;
  }
  return true;
}
2755

2756 2757 2758
VisualMissionItem *MissionController::currentPlanViewItem(void) const {
  return _currentPlanViewItem;
}
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 2802 2803 2804 2805
void MissionController::setCurrentPlanViewIndex(int sequenceNumber,
                                                bool force) {
  if (_visualItems && (force || sequenceNumber != _currentPlanViewIndex)) {
    _currentPlanViewItem = nullptr;
    _currentPlanViewIndex = -1;
    for (int i = 0; i < _visualItems->count(); i++) {
      VisualMissionItem *pVI =
          qobject_cast<VisualMissionItem *>(_visualItems->get(i));
      if (pVI && pVI->sequenceNumber() == sequenceNumber) {
        pVI->setIsCurrentItem(true);
        _currentPlanViewItem = pVI;
        _currentPlanViewIndex = sequenceNumber;
      } else {
        pVI->setIsCurrentItem(false);
      }
    }
    emit currentPlanViewIndexChanged();
    emit currentPlanViewItemChanged();
  }
}

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();
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 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
            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();
    }
  }
  //-- 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;
  }
}

void MissionController::_complexBoundingBoxChanged() {
  _updateTimer.start(UPDATE_TIMEOUT);
2867
}