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


11
#include "MissionCommandUIInfo.h"
12 13 14 15
#include "MissionController.h"
#include "MultiVehicleManager.h"
#include "MissionManager.h"
#include "CoordinateVector.h"
16
#include "FirmwarePlugin.h"
17
#include "QGCApplication.h"
18
#include "SimpleMissionItem.h"
19
#include "SurveyComplexItem.h"
20
#include "FixedWingLandingComplexItem.h"
21
#include "StructureScanComplexItem.h"
22
#include "CorridorScanComplexItem.h"
23
#include "JsonHelper.h"
24
#include "ParameterManager.h"
25
#include "QGroundControlQmlGlobal.h"
26
#include "SettingsManager.h"
27
#include "AppSettings.h"
28
#include "MissionSettingsItem.h"
29
#include "QGCQGeoCoordinate.h"
30
#include "PlanMasterController.h"
31
#include "KML.h"
32
#include "QGCCorePlugin.h"
33

34 35
#include "src/Wima/CircularSurveyComplexItem.h"

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

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

44 45
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

46
const char* MissionController::_settingsGroup =                 "MissionController";
Don Gagne's avatar
Don Gagne committed
47 48
const char* MissionController::_jsonFileTypeValue =             "Mission";
const char* MissionController::_jsonItemsKey =                  "items";
49
const char* MissionController::_jsonPlannedHomePositionKey =    "plannedHomePosition";
Don Gagne's avatar
Don Gagne committed
50
const char* MissionController::_jsonFirmwareTypeKey =           "firmwareType";
51 52 53
const char* MissionController::_jsonVehicleTypeKey =            "vehicleType";
const char* MissionController::_jsonCruiseSpeedKey =            "cruiseSpeed";
const char* MissionController::_jsonHoverSpeedKey =             "hoverSpeed";
Don Gagne's avatar
Don Gagne committed
54 55 56 57 58 59 60
const char* MissionController::_jsonParamsKey =                 "params";

// Deprecated V1 format keys
const char* MissionController::_jsonComplexItemsKey =           "complexItems";
const char* MissionController::_jsonMavAutopilotKey =           "MAV_AUTOPILOT";

const int   MissionController::_missionFileVersion =            2;
61

62 63 64
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"));
65

66
MissionController::MissionController(PlanMasterController* masterController, QObject *parent)
67 68 69 70 71 72 73 74 75 76 77 78 79 80
    : 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)
81 82
    , _remainingTime                (-1)
    , _remainingDistance            (-1)
83
{
84
    _resetMissionFlightStatus();
85
    managerVehicleChanged(_managerVehicle);
86 87
    _updateTimer.setSingleShot(true);
    connect(&_updateTimer, &QTimer::timeout, this, &MissionController::_updateTimeout);
88

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

92 93 94 95
}

MissionController::~MissionController()
{
Don Gagne's avatar
Don Gagne committed
96

97 98
}

99 100 101 102 103 104 105 106 107
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;
108 109 110
    _missionFlightStatus.cruiseSpeed =          _controllerVehicle->defaultCruiseSpeed();
    _missionFlightStatus.hoverSpeed =           _controllerVehicle->defaultHoverSpeed();
    _missionFlightStatus.vehicleSpeed =         _controllerVehicle->multiRotor() || _managerVehicle->vtol() ? _missionFlightStatus.hoverSpeed : _missionFlightStatus.cruiseSpeed;
111
    _missionFlightStatus.vehicleYaw =           0.0;
112
    _missionFlightStatus.gimbalYaw =            std::numeric_limits<double>::quiet_NaN();
113
    _missionFlightStatus.gimbalPitch =          std::numeric_limits<double>::quiet_NaN();
114 115 116 117 118 119 120 121 122 123 124 125

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

126 127 128
    _controllerVehicle->firmwarePlugin()->batteryConsumptionData(_controllerVehicle, _missionFlightStatus.mAhBattery, _missionFlightStatus.hoverAmps, _missionFlightStatus.cruiseAmps);
    if (_missionFlightStatus.mAhBattery != 0) {
        double batteryPercentRemainingAnnounce = qgcApp()->toolbox()->settingsManager()->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toDouble();
129
        _missionFlightStatus.ampMinutesAvailable = static_cast<double>(_missionFlightStatus.mAhBattery) / 1000.0 * 60.0 * ((100.0 - batteryPercentRemainingAnnounce) / 100.0);
130
    }
131 132 133 134 135 136 137 138 139 140 141

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

142 143
}

144
void MissionController::start(bool flyView)
145
{
146
    qCDebug(MissionControllerLog) << "start flyView" << flyView;
147

148
    PlanElementController::start(flyView);
149 150 151 152 153
    _init();
}

void MissionController::_init(void)
{
154
    // We start with an empty mission
155
    _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
156
    _addMissionSettings(_visualItems, false /* addToCenter */);
157
    _initAllVisualItems();
158 159
}

160
// Called when new mission items have completed downloading from Vehicle
161
void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllRequested)
162
{
163
    qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle flyView:count" << _flyView << _missionManager->missionItems().count();
164

DonLakeFlyer's avatar
DonLakeFlyer committed
165 166
    // Fly view always reloads on _loadComplete
    // Plan view only reloads on _loadComplete if specifically requested
167
    if (_flyView || removeAllRequested || _itemsRequested || _visualItems->count() <= 1) {
168
        // Fly Mode (accept if):
Don Gagne's avatar
Don Gagne committed
169
        //      - Always accepts new items from the vehicle so Fly view is kept up to date
170
        // Edit Mode (accept if):
171 172
        //      - Remove all was requested from Fly view (clear mission on flight end)
        //      - A load from vehicle was manually requested
Don Gagne's avatar
Don Gagne committed
173
        //      - The initial automatic load from a vehicle completed and the current editor is empty
174

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

179 180 181
        _missionItemCount = newMissionItems.count();
        emit missionItemCountChanged(_missionItemCount);

182
        int i = 0;
183
        if (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() && newMissionItems.count() != 0) {
184
            // First item is fake home position
DonLakeFlyer's avatar
DonLakeFlyer committed
185
            _addMissionSettings(newControllerMissionItems, false /* addToCenter */);
186
            MissionSettingsItem* settingsItem = newControllerMissionItems->value<MissionSettingsItem*>(0);
187 188 189 190
            if (!settingsItem) {
                qWarning() << "First item is not settings item";
                return;
            }
191 192 193 194
            MissionItem* fakeHomeItem = newMissionItems[0];
            if (fakeHomeItem->coordinate().latitude() != 0 || fakeHomeItem->coordinate().longitude() != 0) {
                settingsItem->setCoordinate(fakeHomeItem->coordinate());
            }
195 196
            i = 1;
        }
197

198
        for (; i < newMissionItems.count(); i++) {
199
            const MissionItem* missionItem = newMissionItems[i];
200
            newControllerMissionItems->append(new SimpleMissionItem(_controllerVehicle, _flyView, *missionItem, this));
201 202 203
        }

        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
204
        _visualItems->deleteLater();
205 206
        _settingsItem = nullptr;
        _visualItems  = nullptr;
207
        _updateContainsItems(); // This will clear containsItems which will be set again below. This will re-pop Start Mission confirmation.
208 209
        _visualItems = newControllerMissionItems;

210
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
211
            _addMissionSettings(_visualItems, !_flyView && _visualItems->count() > 0 /* addToCenter */);
212 213
        }

214
        MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
215

216
        _initAllVisualItems();
217
        _updateContainsItems();
218
        emit newItemsFromVehicle();
219
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
220
    _itemsRequested = false;
221 222
}

223
void MissionController::loadFromVehicle(void)
224
{
DonLakeFlyer's avatar
DonLakeFlyer committed
225 226 227 228 229 230 231 232
    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();
    }
233 234
}

235 236 237 238
void MissionController::_warnIfTerrainFrameUsed(void)
{
    for (int i=1; i<_visualItems->count(); i++) {
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(i));
239
        if (simpleItem && simpleItem->altitudeMode() == QGroundControlQmlGlobal::AltitudeModeTerrainFrame) {
240 241 242 243 244 245
            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;
        }
    }
}

246
void MissionController::sendToVehicle(void)
247
{
DonLakeFlyer's avatar
DonLakeFlyer committed
248 249 250 251 252
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::sendToVehicle called while offline";
    } else if (syncInProgress()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::sendToVehicle called while syncInProgress";
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
253
        qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
254
        _warnIfTerrainFrameUsed();
DonLakeFlyer's avatar
DonLakeFlyer committed
255 256 257 258 259 260 261 262 263
        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);
    }
Don Gagne's avatar
Don Gagne committed
264 265
}

266
/// Converts from visual items to MissionItems
267
///     @param missionItemParent QObject parent for newly allocated MissionItems, _surveyMissionItemName    (tr("Survey"))
268
/// @return true: Mission end action was added to end of list
269
bool MissionController::convertToMissionItems(QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent)
270
{
DonLakeFlyer's avatar
DonLakeFlyer committed
271 272 273 274
    if (visualMissionItems->count() == 0) {
        return false;
    }

275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290
    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
291
    MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
292 293 294 295 296 297 298
    if (settingsItem) {
        endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
    }

    return endActionSet;
}

299 300
void MissionController::convertToKMLDocument(QDomDocument& document)
{
301 302
    QObject*            deleteParent = new QObject();
    QList<MissionItem*> rgMissionItems;
303

304
    convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
305
    if (rgMissionItems.count() == 0) {
306 307
        return;
    }
308

309
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
310 311 312 313 314

    QString coord;
    QStringList coords;
    // Drop home position
    bool dropPoint = true;
315
    for(const auto& item : rgMissionItems) {
316 317 318 319 320
        if(dropPoint) {
            dropPoint = false;
            continue;
        }
        const MissionCommandUIInfo* uiInfo = \
321
                qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, item->command());
322 323

        if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
324
            double amslAltitude = item->param7() + (item->frame() == MAV_FRAME_GLOBAL ? 0 : homePositionAltitude);
yaoling's avatar
yaoling committed
325
            coord = QString::number(item->param6(),'f',7) \
326 327 328
                    + "," \
                    + QString::number(item->param5(),'f',7) \
                    + "," \
329
                    + QString::number(amslAltitude,'f',2);
330 331 332
            coords.append(coord);
        }
    }
333 334 335

    deleteParent->deleteLater();

336 337 338 339 340
    Kml kml;
    kml.points(coords);
    kml.save(document);
}

Don Gagne's avatar
Don Gagne committed
341 342 343
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
344
        QList<MissionItem*> rgMissionItems;
345

346
        convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
347

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

353 354 355 356 357 358
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
359 360
        VisualMissionItem* lastItem = _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1);
        return lastItem->lastSequenceNumber() + 1;
361 362 363
    }
}

364
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
365
{
366
    int sequenceNumber = _nextSequenceNumber();
367
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
368
    newItem->setSequenceNumber(sequenceNumber);
369
    newItem->setCoordinate(coordinate);
370
    newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
371
    _initVisualItem(newItem);
372
    if (_visualItems->count() == 1 && (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() || _controllerVehicle->multiRotor())) {
373
        MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
374
        if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) {
375 376
            newItem->setCommand(takeoffCmd);
        }
377
    }
378 379 380
    if (newItem->specifiesAltitude()) {
        double  prevAltitude;
        int     prevAltitudeMode;
381

382 383
        if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
            newItem->altitude()->setRawValue(prevAltitude);
384
            newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
385
        }
386
    }
387
    newItem->setMissionFlightStatus(_missionFlightStatus);
388
    _visualItems->insert(i, newItem);
389

390 391
    // 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);
392

393
    return newItem->sequenceNumber();
394 395
}

396 397 398 399 400 401 402 403 404
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)) {
405
            newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
406 407 408
            return -1; // can not add this takeoff command for this vehicle
        }
    }
409 410 411 412 413 414
    if (newItem->specifiesAltitude()) {        
        newItem->altitude()->setRawValue(missionItem.relativeAltitude());
        newItem->setAltitudeMode(QGroundControlQmlGlobal::AltitudeMode::AltitudeModeRelative);
    }
    newItem->setMissionFlightStatus(_missionFlightStatus);
    _visualItems->insert(i, newItem);
415

416 417 418
    return newItem->sequenceNumber();
}

419
int MissionController::insertSimpleMissionItem(SimpleMissionItem &missionItem, int i)
420 421 422 423 424 425 426 427 428 429
{
    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
430 431
        }
    }
Valentin Platzgummer's avatar
Valentin Platzgummer committed
432
    newItem->setMissionFlightStatus(_missionFlightStatus);
433 434 435
    _visualItems->insert(i, newItem);

    return newItem->sequenceNumber();
436
}
437

438 439 440
int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
{
    int sequenceNumber = _nextSequenceNumber();
441
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
442
    newItem->setSequenceNumber(sequenceNumber);
443
    newItem->setCommand((_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_DO_SET_ROI_LOCATION) ?
444 445
        MAV_CMD_DO_SET_ROI_LOCATION :
        MAV_CMD_DO_SET_ROI));
446
    _initVisualItem(newItem);
447
    newItem->setCoordinate(coordinate);
448

449 450
    double  prevAltitude;
    int     prevAltitudeMode;
451

452 453
    if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
        newItem->altitude()->setRawValue(prevAltitude);
454
        newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
455 456 457 458 459 460 461 462
    }
    _visualItems->insert(i, newItem);

    _recalcAll();

    return newItem->sequenceNumber();
}

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

467
    int sequenceNumber = _nextSequenceNumber();
468
    if (itemName == _surveyMissionItemName) {
469
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
470
        newItem->setCoordinate(mapCenterCoordinate);
471
    } else if (itemName == patternFWLandingName) {
472
        newItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, _visualItems /* parent */);
473
    } else if (itemName == patternStructureScanName) {
474
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
475
    } else if (itemName == patternCorridorScanName) {
476
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
477 478
    } else if (itemName == _circularSurveyMissionItemName) {
        newItem = new CircularSurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
479 480 481 482 483
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }

484 485 486
    return _insertComplexMissionItemWorker(newItem, i);
}

487
int MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int i)
488 489 490 491
{
    ComplexMissionItem* newItem;

    if (itemName == _surveyMissionItemName) {
492
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
493 494
    } else if (itemName == _circularSurveyMissionItemName) {
        newItem = new CircularSurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
495
    } else if (itemName == patternStructureScanName) {
496
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
497
    } else if (itemName == patternCorridorScanName) {
498
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
499 500 501 502 503 504 505 506 507 508 509
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return _nextSequenceNumber();
    }

    return _insertComplexMissionItemWorker(newItem, i);
}

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

514
    if (surveyStyleItem) {
515
        bool rollSupported  = false;
516
        bool pitchSupported = false;
517
        bool yawSupported   = false;
518 519 520

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

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

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

530
        // Point gimbal straight down
531
        if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
532 533 534
            // If the user already specified a gimbal angle leave it alone
            if (!cameraSection->specifyGimbal()) {
                cameraSection->setSpecifyGimbal(true);
535
                cameraSection->gimbalPitch()->setRawValue(-90.0);
536 537
            }
        }
538
    }
539

540 541
    complexItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(complexItem);
542

543 544 545 546 547
    if (i == -1) {
        _visualItems->append(complexItem);
    } else {
        _visualItems->insert(i, complexItem);
    }
548

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

555
    return complexItem->sequenceNumber();
556 557
}

558 559
void MissionController::removeMissionItem(int index)
{
560 561 562 563 564
    if (index <= 0 || index >= _visualItems->count()) {
        qWarning() << "MissionController::removeMissionItem called with bad index - count:index" << _visualItems->count() << index;
        return;
    }

565 566 567
    bool removeSurveyStyle =    _visualItems->value<SurveyComplexItem*>(index)
                             || _visualItems->value<CorridorScanComplexItem*>(index)
                             || _visualItems->value<CircularSurveyComplexItem*>(index);
568
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
569

570
    _deinitVisualItem(item);
571
    item->deleteLater();
572

573 574
    if (removeSurveyStyle) {
        // Determine if the mission still has another survey style item in it
575 576
        bool foundSurvey = false;
        for (int i=1; i<_visualItems->count(); i++) {
577 578 579
            if (    _visualItems->value<SurveyComplexItem*>(i)
                 || _visualItems->value<CorridorScanComplexItem*>(i)
                 || _visualItems->value<CircularSurveyComplexItem*>(i)) {
580 581 582 583 584
                foundSurvey = true;
                break;
            }
        }

585
        // If there is no longer a survey item in the mission remove added commands
586 587 588 589
        if (!foundSurvey) {
            bool rollSupported = false;
            bool pitchSupported = false;
            bool yawSupported = false;
590 591
            MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
            CameraSection* cameraSection = settingsItem->cameraSection();
592
            if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
593
                if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
594 595 596
                    cameraSection->setSpecifyGimbal(false);
                }
            }
597
            if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
598 599
                cameraSection->setSpecifyCameraMode(false);
            }
600 601 602
        }
    }

603
    _recalcAll();
604
    setDirty(true);
605 606
}

607
void MissionController::removeAll(void)
608
{
609 610
    if (_visualItems) {
        _deinitAllVisualItems();
DonLakeFlyer's avatar
DonLakeFlyer committed
611
        _visualItems->clearAndDeleteContents();
Don Gagne's avatar
Don Gagne committed
612
        _visualItems->deleteLater();
613
        _settingsItem = nullptr;
614
        _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
615
        _addMissionSettings(_visualItems, false /* addToCenter */);
616
        _initAllVisualItems();
617
        setDirty(true);
618
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
619 620 621
    }
}

622
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
623 624 625 626 627 628 629 630 631
{
    // 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)) {
632 633 634
        return false;
    }

635
    // Read complex items
636
    QList<SurveyComplexItem*> surveyItems;
637 638 639 640
    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];
641

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

647
        SurveyComplexItem* item = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems /* parent */);
Don Gagne's avatar
Don Gagne committed
648 649
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
650
            surveyItems.append(item);
651 652
        } else {
            return false;
653
        }
654
    }
655

656 657 658 659 660
    // 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
Don Gagne's avatar
Don Gagne committed
661
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
662

663
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
664 665 666 667
    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
668
        if (nextComplexItemIndex < surveyItems.count()) {
669
            SurveyComplexItem* complexItem = surveyItems[nextComplexItemIndex];
670 671 672 673 674 675 676 677 678 679 680 681 682 683

            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++];

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

Don Gagne's avatar
Don Gagne committed
689
            const QJsonObject itemObject = itemValue.toObject();
690
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
Don Gagne's avatar
Don Gagne committed
691
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
692
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
693
                nextSequenceNumber = item->lastSequenceNumber() + 1;
694
                visualItems->append(item);
695 696 697 698
            } else {
                return false;
            }
        }
699
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
700 701

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

Don Gagne's avatar
Don Gagne committed
704
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
705
            MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
706 707 708
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
709 710 711 712
        } else {
            return false;
        }
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
713
        _addMissionSettings(visualItems, true /* addToCenter */);
714 715 716 717 718
    }

    return true;
}

719
bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
720 721 722 723 724 725
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
726
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
727 728
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
729 730 731 732 733 734 735
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

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

739 740
    if (_masterController->offline()) {
        // We only update if offline since if we are online we use the online vehicle settings
741
        appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType(static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt())));
742
        if (json.contains(_jsonVehicleTypeKey)) {
743
            appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType(static_cast<MAV_TYPE>(json[_jsonVehicleTypeKey].toInt())));
744
        }
745
    }
746
    if (json.contains(_jsonCruiseSpeedKey)) {
747
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
748 749
    }
    if (json.contains(_jsonHoverSpeedKey)) {
750
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
751 752
    }

753 754 755 756
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
757
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
758 759
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
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
    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) {
786
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
787
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
788
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
789
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
790 791 792 793 794 795 796 797 798 799 800 801 802
                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();

803
            if (complexItemType == SurveyComplexItem::jsonComplexItemTypeValue) {
Don Gagne's avatar
Don Gagne committed
804
                qCDebug(MissionControllerLog) << "Loading Survey: nextSequenceNumber" << nextSequenceNumber;
805
                SurveyComplexItem* surveyItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
Don Gagne's avatar
Don Gagne committed
806 807 808 809 810 811
                if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(surveyItem);
812
            } else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
813
                qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
814
                FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
815 816 817 818 819 820
                if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(landingItem);
821 822
            } else if (complexItemType == StructureScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Structure Scan: nextSequenceNumber" << nextSequenceNumber;
823
                StructureScanComplexItem* structureItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
824 825 826 827 828 829
                if (!structureItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = structureItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Structure Scan load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(structureItem);
830 831
            } else if (complexItemType == CorridorScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Corridor Scan: nextSequenceNumber" << nextSequenceNumber;
832
                CorridorScanComplexItem* corridorItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
833 834 835 836 837 838
                if (!corridorItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = corridorItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Corridor Scan load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(corridorItem);
Valentin Platzgummer's avatar
Valentin Platzgummer committed
839 840 841 842 843 844 845 846 847
            } else if (complexItemType == CircularSurveyComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Circular Survey: nextSequenceNumber" << nextSequenceNumber;
                CircularSurveyComplexItem* circularSurvey = new CircularSurveyComplexItem(_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);
848
            } else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
849
                qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
850
                MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
851 852 853 854 855 856
                if (!settingsItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = settingsItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Mission Settings load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(settingsItem);
Don Gagne's avatar
Don Gagne committed
857 858 859 860 861 862 863 864 865 866 867 868 869
            } 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);
870
            if (doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
871
                bool found = false;
872
                int findDoJumpId = static_cast<int>(doJumpItem->missionItem().param1());
Don Gagne's avatar
Don Gagne committed
873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893
                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;
                        }
                    }
                }
                if (!found) {
                    errorString = tr("Could not find doJumpId: %1").arg(findDoJumpId);
                    return false;
                }
            }
        }
    }

    return true;
}

894 895 896 897 898 899 900 901
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;
902 903 904 905 906 907
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
908 909

    if (fileVersion == 1) {
910
        return _loadJsonMissionFileV1(json, visualItems, errorString);
911
    } else {
912
        return _loadJsonMissionFileV2(json, visualItems, errorString);
913 914 915
    }
}

916
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
917
{
918 919
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
920 921 922 923 924 925 926 927 928

    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;
929
            plannedHomePositionInFile = true;
930 931 932
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
933
            plannedHomePositionInFile = false;
934 935 936 937
        }
    }

    if (versionOk) {
938
        // Start with planned home in center
DonLakeFlyer's avatar
DonLakeFlyer committed
939
        _addMissionSettings(visualItems, true /* addToCenter */);
940 941
        MissionSettingsItem* settingsItem = visualItems->value<MissionSettingsItem*>(0);

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

            if (item->load(stream)) {
946 947 948 949 950 951
                if (firstItem && plannedHomePositionInFile) {
                    settingsItem->setCoordinate(item->coordinate());
                } else {
                    visualItems->append(item);
                }
                firstItem = false;
952
            } else {
953
                errorString = tr("The mission file is corrupted.");
954 955 956 957
                return false;
            }
        }
    } else {
958
        errorString = tr("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
959 960 961
        return false;
    }

962
    if (!plannedHomePositionInFile) {
963 964 965
        // 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));
966
            if (item && item->command() == MAV_CMD_DO_JUMP) {
967
                item->missionItem().setParam1(static_cast<int>(item->missionItem().param1()) + 1);
Don Gagne's avatar
Don Gagne committed
968 969
            }
        }
970 971 972
    }

    return true;
973 974
}

975
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
976
{
Don Gagne's avatar
Don Gagne committed
977 978 979
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
980
        _settingsItem = nullptr;
Don Gagne's avatar
Don Gagne committed
981 982
    }

983
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
984 985

    if (_visualItems->count() == 0) {
DonLakeFlyer's avatar
DonLakeFlyer committed
986
        _addMissionSettings(_visualItems, true /* addToCenter */);
Don Gagne's avatar
Don Gagne committed
987 988
    }

989
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
990

Don Gagne's avatar
Don Gagne committed
991
    _initAllVisualItems();
992
}
993

994 995 996 997 998 999
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

1000
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
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
        errorString = errorMessage.arg(errorStr);
        return false;
    }
    _initLoadedVisualItems(loadedVisualItems);

    return true;
}

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

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

    QJsonObject json = jsonDoc.object();
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);
    if (!_loadItemsFromJson(json, loadedVisualItems, errorStr)) {
        errorString = errorMessage.arg(errorStr);
        return false;
1026
    }
1027

1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040
    _initLoadedVisualItems(loadedVisualItems);

    return true;
}

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

    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);
1041
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
1042 1043 1044 1045 1046 1047
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
1048
    return true;
1049 1050
}

1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062
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;
        }
    }

    return true;
}

1063
bool MissionController::setTakeoffCommand(SimpleMissionItem &missionItem)
1064
{
1065
    if (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() || _controllerVehicle->multiRotor()) {
1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076
        MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
        if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) {
            missionItem.setCommand(takeoffCmd);
        }
    }
    else
       return false;

    return true;
}

1077
bool MissionController::setLandCommand(SimpleMissionItem &missionItem)
1078
{
1079 1080
    MAV_CMD landCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_LAND;
    if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(landCmd)) {
1081 1082 1083 1084 1085 1086 1087
        missionItem.setCommand(landCmd);
    } else
        return false;

    return true;
}

1088
void MissionController::save(QJsonObject& json)
1089
{
1090
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
1091

1092
    // Mission settings
1093

1094 1095 1096 1097 1098 1099 1100
    MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsItem";
        return;
    }
    QJsonValue coordinateValue;
    JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
1101 1102 1103 1104 1105
    json[_jsonPlannedHomePositionKey]   = coordinateValue;
    json[_jsonFirmwareTypeKey]          = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey]           = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey]           = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey]            = _controllerVehicle->defaultHoverSpeed();
1106

1107
    // Save the visual items
1108

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

1113 1114
        visualItem->save(rgJsonMissionItems);
    }
1115

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

1120
        if (convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
1121 1122 1123 1124
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
1125
        }
1126 1127
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
1128 1129 1130
        }
    }

1131
    json[_jsonItemsKey] = rgJsonMissionItems;
1132 1133
}

1134
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
1135
{
Don Gagne's avatar
Don Gagne committed
1136
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
1137
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
1138 1139 1140 1141
    bool            distanceOk =    false;

    // Convert to fixed altitudes

1142
    distanceOk = true;
1143
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
1144 1145
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
1146
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
1147
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
1148 1149 1150
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
1151 1152 1153
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
1154
    } else {
Don Gagne's avatar
Don Gagne committed
1155
        *altDifference = 0.0;
1156
        *azimuth = 0.0;
1157
        *distance = 0.0;
1158 1159 1160
    }
}

1161
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
1162 1163 1164 1165 1166 1167 1168
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

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

1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193
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;
    }
}

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

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

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

Nate Weibley's avatar
Nate Weibley committed
1203 1204
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
1205
    _waypointLines.clear();
1206
    _waypointPath.clear();
1207

1208 1209 1210 1211 1212 1213 1214 1215 1216
    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;
1217 1218 1219
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));

1220 1221 1222 1223 1224 1225
        // 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;
1226
            }
1227 1228
        }

1229 1230 1231
        if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
            firstCoordinateItem = false;
            if (lastCoordinateItem != _settingsItem || (homePositionValid && linkStartToHome)) {
1232
                if (!_flyView) {
1233 1234
                    VisualItemPair pair(lastCoordinateItem, item);
                    _addWaypointLineSegment(old_table, pair);
1235 1236
                }
            }
1237 1238
            _waypointPath.append(QVariant::fromValue(item->coordinate()));
            lastCoordinateItem = item;
1239 1240
        }
    }
1241 1242 1243 1244 1245 1246

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

    if (linkEndToHome && lastCoordinateItem != _settingsItem && homePositionValid) {
1247
        if (!_flyView) {
1248 1249 1250 1251 1252
            VisualItemPair pair(lastCoordinateItem, _settingsItem);
            _addWaypointLineSegment(old_table, pair);
        } else {
            _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
        }
1253
    }
1254 1255 1256 1257

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1258
        objs.reserve(_linesTable.count());
1259
        for(CoordinateVector *vect: _linesTable.values()) {
1260 1261 1262 1263 1264 1265 1266 1267 1268 1269
            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);

DonLakeFlyer's avatar
DonLakeFlyer committed
1270
    _recalcMissionFlightStatus();
1271

1272 1273 1274 1275 1276 1277 1278 1279
    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)));
    }

1280
    emit waypointLinesChanged();
1281
    emit waypointPathChanged();
1282 1283
}

1284 1285 1286 1287 1288 1289
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);
1290 1291 1292
        // 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.
1293
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316
            _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);
}

1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343
/// Adds the specified time to the appropriate hover or cruise time values.
///     @param vtolInHover true: vtol is currrent in hover mode
///     @param hoverTime    Amount of time tp add to hover
///     @param cruiseTime   Amount of time to add to cruise
///     @param extraTime    Amount of additional time to add to hover/cruise
///     @param seqNum       Sequence number of waypoint for these values, -1 for no waypoint associated
void MissionController::_addTimeDistance(bool vtolInHover, double hoverTime, double cruiseTime, double extraTime, double distance, int seqNum)
{
    if (_controllerVehicle->vtol()) {
        if (vtolInHover) {
            _addHoverTime(hoverTime, distance, seqNum);
            _addHoverTime(extraTime, 0, -1);
        } else {
            _addCruiseTime(cruiseTime, distance, seqNum);
            _addCruiseTime(extraTime, 0, -1);
        }
    } else {
        if (_controllerVehicle->multiRotor()) {
            _addHoverTime(hoverTime, distance, seqNum);
            _addHoverTime(extraTime, 0, -1);
        } else {
            _addCruiseTime(cruiseTime, distance, seqNum);
            _addCruiseTime(extraTime, 0, -1);
        }
    }
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1344
void MissionController::_recalcMissionFlightStatus()
1345
{
1346
    if (!_visualItems->count()) {
1347
        return;
1348
    }
1349 1350 1351 1352

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

1353
    bool showHomePosition = _settingsItem->coordinate().isValid();
1354

DonLakeFlyer's avatar
DonLakeFlyer committed
1355
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1356

1357 1358 1359
    // 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.
1360

1361
    // No values for first item
1362
    lastCoordinateItem->setAltDifference(0.0);
1363
    lastCoordinateItem->setAzimuth(0.0);
1364
    lastCoordinateItem->setDistance(0.0);
1365

1366 1367
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1368 1369
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1370

1371
    _resetMissionFlightStatus();
1372

DonLakeFlyer's avatar
DonLakeFlyer committed
1373
    bool vtolInHover = true;
1374
    bool linkStartToHome = false;
1375 1376 1377 1378 1379 1380 1381 1382 1383 1384
    bool linkEndToHome = false;

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1386
    for (int i=0; i<_visualItems->count(); i++) {
1387
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1388 1389 1390
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1391 1392
        // Assume the worst
        item->setAzimuth(0.0);
1393
        item->setDistance(0.0);
1394

DonLakeFlyer's avatar
DonLakeFlyer committed
1395 1396 1397
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1398
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1399
                _missionFlightStatus.hoverSpeed = newSpeed;
1400
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1401 1402
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1403
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1404
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1405
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1406 1407
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1408
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1409 1410 1411 1412
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1413 1414 1415 1416 1417 1418 1419
        double gimbalYaw = item->specifiedGimbalYaw();
        if (!qIsNaN(gimbalYaw)) {
            _missionFlightStatus.gimbalYaw = gimbalYaw;
        }
        double gimbalPitch = item->specifiedGimbalPitch();
        if (!qIsNaN(gimbalPitch)) {
            _missionFlightStatus.gimbalPitch = gimbalPitch;
DonLakeFlyer's avatar
DonLakeFlyer committed
1420 1421 1422 1423 1424
        }

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

1427
        // Link back to home if first item is takeoff and we have home position
1428
        if (firstCoordinateItem && simpleItem && (simpleItem->command() == MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
1429
            if (showHomePosition) {
1430
                linkStartToHome = true;
1431 1432 1433 1434 1435 1436 1437
                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);
                }
1438 1439 1440 1441
            }
        }

        // Update VTOL state
1442
        if (simpleItem && _controllerVehicle->vtol()) {
1443
            switch (simpleItem->command()) {
1444
            case MAV_CMD_NAV_TAKEOFF:
1445 1446
                vtolInHover = false;
                break;
1447
            case MAV_CMD_NAV_VTOL_TAKEOFF:
DonLakeFlyer's avatar
DonLakeFlyer committed
1448 1449
                vtolInHover = true;
                break;
1450
            case MAV_CMD_NAV_LAND:
1451 1452
                vtolInHover = false;
                break;
1453
            case MAV_CMD_NAV_VTOL_LAND:
DonLakeFlyer's avatar
DonLakeFlyer committed
1454 1455
                vtolInHover = true;
                break;
1456
            case MAV_CMD_DO_VTOL_TRANSITION:
1457 1458 1459 1460 1461 1462
            {
                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;
1463 1464
                }
            }
1465 1466 1467
                break;
            default:
                break;
1468
            }
Don Gagne's avatar
Don Gagne committed
1469 1470
        }

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

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

1476
            double absoluteAltitude = item->coordinate().altitude();
1477
            if (item->coordinateHasRelativeAltitude()) {
1478 1479 1480 1481 1482
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1483 1484 1485 1486
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1487 1488 1489
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1490
                firstCoordinateItem = false;
1491 1492 1493 1494 1495 1496 1497

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

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

1502
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1503 1504 1505
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1506

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1509 1510 1511
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1512
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1513
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1514

1515
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1516 1517
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1518
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1519

1520 1521
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1522
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1523
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1524 1525

                item->setMissionFlightStatus(_missionFlightStatus);
1526

1527 1528
                lastCoordinateItem = item;
            }
1529 1530
        }
    }
1531
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1532

1533 1534 1535 1536 1537 1538 1539 1540
    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();
1541
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1542 1543
    }

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1548 1549 1550 1551 1552 1553 1554
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1555 1556
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1557

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

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1565
            if (item->coordinateHasRelativeAltitude()) {
1566 1567 1568 1569
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1570
                item->setTerrainPercent(qQNaN());
1571
                item->setTerrainCollision(false);
1572 1573
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1574 1575 1576 1577 1578 1579 1580
                double terrainAltitude = item->terrainAltitude();
                if (qIsNaN(terrainAltitude)) {
                    item->setTerrainPercent(qQNaN());
                    item->setTerrainCollision(false);
                } else {
                    item->setTerrainPercent((terrainAltitude - minAltSeen) / altRange);
                    item->setTerrainCollision(absoluteAltitude < terrainAltitude);
1581
                }
1582
            }
1583 1584
        }
    }
1585 1586

    _updateTimer.start(UPDATE_TIMEOUT);
1587 1588
}

1589 1590 1591
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1592 1593 1594 1595 1596
    if (_inRecalcSequence) {
        // Don't let this call recurse due to signalling
        return;
    }

1597 1598
    // Setup ascending sequence numbers for all visual items

1599
    _inRecalcSequence = true;
1600 1601 1602
    int sequenceNumber = 0;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1603 1604
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1605 1606
    }    
    _inRecalcSequence = false;
1607 1608
}

1609 1610 1611
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1612
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1613 1614 1615

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

1616 1617
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1618 1619 1620 1621 1622

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

1629
void MissionController::_setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate)
1630
{
1631 1632
    QGeoCoordinate firstCoordinate;

1633 1634 1635 1636
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1637
    // Set the planned home position to be a delta from first coordinate
1638 1639 1640 1641
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

        if (item->specifiesCoordinate()) {
1642 1643
            firstCoordinate = item->coordinate();
            break;
1644 1645 1646
        }
    }

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

1652 1653 1654 1655 1656 1657 1658 1659 1660
    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(QGeoCoordinate& clickCoordinate)
1661
{
1662
    if (!_flyView) {
1663
        _setPlannedHomePositionFromFirstCoordinate(clickCoordinate);
1664
    }
1665
    _recalcSequence();
1666 1667
    _recalcChildItems();
    _recalcWaypointLines();
1668
    _updateTimer.start(UPDATE_TIMEOUT);
1669 1670
}

1671 1672 1673 1674 1675 1676
void MissionController::_recalcAll(void)
{
    QGeoCoordinate emptyCoord;
    _recalcAllWithClickCoordinate(emptyCoord);
}

1677 1678 1679 1680 1681 1682
void MissionController::_enableDisableRemainingDistTimeCalculation(bool flying)
{
    if (flying) {
        _remainingDistanceTimeTimer.start();
    } else {
        _remainingDistanceTimeTimer.stop();
1683 1684 1685 1686 1687
        _remainingTime = -1;
        _remainingDistance = -1;

        emit remainingTimeChanged();
        emit remainingDistanceChanged();
1688 1689 1690 1691 1692 1693 1694
    }
}

void MissionController::_updateRemainingDistanceTime()
{
    double dist = 0;
    double time = 0;
1695
    bool success = distanceTimeToMissionEnd(dist, time, _missionManager->currentIndex() /*missionIndex >= 1*/, true /* useVehiclePostion */);
1696 1697 1698 1699 1700 1701 1702 1703 1704
    if (success) {
        _remainingTime      = time;
        _remainingDistance  = dist;

        emit remainingTimeChanged();
        emit remainingDistanceChanged();
    }
}

1705
/// Initializes a new set of mission items
1706
void MissionController::_initAllVisualItems(void)
1707
{
1708 1709
    // Setup home position at index 0

1710 1711 1712
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1713 1714
        return;
    }
1715
    if (!_flyView) {
1716 1717
        _settingsItem->setIsCurrentItem(true);
    }
1718

1719
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1720
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1721
    }
1722

1723 1724 1725
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1726

1727 1728 1729 1730
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1731

1732
    _recalcAll();
1733

1734
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1735 1736 1737
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1738
    emit containsItemsChanged(containsItems());
1739
    emit plannedHomePositionChanged(plannedHomePosition());
1740

1741
    setDirty(false);
1742 1743
}

1744
void MissionController::_deinitAllVisualItems(void)
1745
{
1746 1747 1748
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

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

1753
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1754
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1755 1756
}

1757
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1758
{
1759
    setDirty(false);
1760

1761
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1762 1763
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1764 1765
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1766
    connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged,                this, &MissionController::_recalcMissionFlightStatus);
1767
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1768
    connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged,                 this, &MissionController::_recalcMissionFlightStatus);
1769
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1770

1771 1772 1773 1774 1775 1776 1777 1778
    if (visualItem->isSimpleItem()) {
        // We need to track commandChanged on simple item since recalc has special handling for takeoff command
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
        if (simpleItem) {
            connect(&simpleItem->missionItem()._commandFact, &Fact::valueChanged, this, &MissionController::_itemCommandChanged);
        } else {
            qWarning() << "isSimpleItem == true, yet not SimpleMissionItem";
        }
1779 1780
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1781
        if (complexItem) {
1782
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
1783
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
1784 1785 1786
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1787
    }
1788 1789
}

1790
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1791
{
1792 1793
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1794 1795
}

1796
void MissionController::_itemCommandChanged(void)
1797
{
1798 1799
    _recalcChildItems();
    _recalcWaypointLines();
1800 1801
}

1802
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1803
{
1804 1805 1806 1807 1808 1809
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1810

1811 1812
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1813
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1814 1815
        return;
    }
1816

1817 1818
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1819 1820
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1821 1822 1823 1824 1825
    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);
1826
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1827 1828 1829 1830
    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);
1831
    connect(_managerVehicle, &Vehicle::flyingChanged,                   this, &MissionController::_enableDisableRemainingDistTimeCalculation);
1832

1833 1834
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1835
    }
1836

1837
    emit complexMissionItemNamesChanged();
1838
    emit resumeMissionIndexChanged();
1839 1840
}

1841
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1842
{
1843
    if (_visualItems) {
1844 1845
        bool currentDirtyBit = dirty();

1846
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1847
        if (settingsItem) {
1848
            settingsItem->setHomePositionFromVehicle(homePosition);
1849
        } else {
1850
            qWarning() << "First item is not MissionSettingsItem";
1851
        }
1852 1853 1854 1855 1856 1857

        if (!currentDirtyBit) {
            // Don't let this trip the dirty bit. Otherwise plan will keep getting marked dirty if vehicle home
            // changes.
            _visualItems->setDirty(false);
        }
1858
    }
1859 1860 1861
}

void MissionController::_inProgressChanged(bool inProgress)
1862
{
1863
    emit syncInProgressChanged(inProgress);
1864
}
1865

1866
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1867
{
1868 1869
    bool        found = false;
    double      foundAltitude;
1870
    int         foundAltitudeMode;
1871

1872 1873 1874 1875 1876 1877
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1880 1881 1882
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1883 1884 1885
                if (simpleItem->specifiesAltitude()) {
                    foundAltitude = simpleItem->altitude()->rawValue().toDouble();
                    foundAltitudeMode = simpleItem->altitudeMode();
1886
                    found = true;
1887
                    break;
1888 1889
                }
            }
1890 1891 1892
        }
    }

1893
    if (found) {
1894
        *prevAltitude = foundAltitude;
1895
        *prevAltitudeMode = foundAltitudeMode;
1896 1897 1898
    }

    return found;
1899
}
1900 1901 1902 1903 1904 1905 1906 1907 1908 1909 1910 1911 1912

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

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

1913
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1914
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1915
{
1916
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
1917

Don Gagne's avatar
Don Gagne committed
1918 1919
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1920
    visualItems->insert(0, settingsItem);
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
    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;
                    }
1947 1948
                }
            }
1949

1950 1951 1952
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1953
        }
Don Gagne's avatar
Don Gagne committed
1954 1955
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1956 1957
    }
}
1958

1959
int MissionController::resumeMissionIndex(void) const
1960
{
1961

1962
    int resumeIndex = 0;
1963

1964
    if (_flyView) {
1965
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1966
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1967 1968
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1969 1970
        } else {
            resumeIndex = 0;
1971 1972 1973 1974 1975
        }
    }

    return resumeIndex;
}
1976

1977 1978
int MissionController::currentMissionIndex(void) const
{
1979
    if (!_flyView) {
1980 1981 1982 1983 1984 1985 1986 1987 1988 1989
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

1990
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1991
{
1992
    if (_flyView) {
1993
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1994 1995 1996
            sequenceNumber++;
        }

1997 1998
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1999 2000
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
2001
        emit currentMissionIndexChanged(currentMissionIndex());
2002 2003
    }
}
2004

2005
bool MissionController::syncInProgress(void) const
2006
{
2007
    return _missionManager->inProgress();
2008 2009 2010 2011 2012 2013 2014 2015 2016 2017 2018 2019
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
2020
    }
2021
}
2022

2023 2024
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
2025 2026
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, vehicle);
2027

2028 2029 2030 2031 2032 2033
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

2034
        if (!_flyView) {
2035 2036 2037 2038 2039 2040
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
2041 2042 2043
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
2044
        if (simpleItem) {
2045 2046 2047 2048 2049
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
2050 2051 2052
        }
    }
}
2053 2054 2055 2056 2057 2058 2059 2060 2061 2062 2063 2064 2065

void MissionController::_updateContainsItems(void)
{
    emit containsItemsChanged(containsItems());
}

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

void MissionController::removeAllFromVehicle(void)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
2066 2067 2068 2069 2070 2071 2072 2073
    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();
    }
2074
}
2075 2076 2077 2078 2079

QStringList MissionController::complexMissionItemNames(void) const
{
    QStringList complexItems;

2080
    complexItems.append(_circularSurveyMissionItemName);
2081
    complexItems.append(_surveyMissionItemName);
2082
    complexItems.append(patternCorridorScanName);
2083
    if (_controllerVehicle->fixedWing()) {
2084
        complexItems.append(patternFWLandingName);
2085
    }
2086
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
2087
        complexItems.append(patternStructureScanName);
2088
    }
2089

2090
    return qgcApp()->toolbox()->corePlugin()->complexMissionItemNames(_controllerVehicle, complexItems);
2091
}
2092

2093 2094
void MissionController::resumeMission(int resumeIndex)
{
2095
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
2096 2097
        resumeIndex--;
    }
2098
    _missionManager->generateResumeMission(resumeIndex);
2099
}
2100 2101 2102 2103 2104 2105 2106 2107 2108

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
2109 2110 2111 2112 2113 2114 2115 2116 2117 2118

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

2120 2121 2122 2123 2124 2125 2126
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
2127 2128 2129 2130 2131 2132

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);
}
DonLakeFlyer's avatar
DonLakeFlyer committed
2133 2134 2135

bool MissionController::showPlanFromManagerVehicle (void)
{
2136
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
DonLakeFlyer's avatar
DonLakeFlyer committed
2137 2138
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
2139
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
2140 2141 2142 2143 2144 2145 2146 2147 2148 2149 2150 2151 2152 2153 2154 2155 2156 2157 2158
    } else {
        if (!_managerVehicle->initialPlanRequestComplete()) {
            // The vehicle hasn't completed initial load, we can just wait for newMissionItemsAvailable to be signalled automatically
            qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle: !initialPlanRequestComplete, wait for signal";
            return true;
        } else if (syncInProgress()) {
            // If the sync is already in progress, newMissionItemsAvailable will be signalled automatically when it is done. So no need to do anything.
            qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle: syncInProgress wait for signal";
            return true;
        } else {
            // Fake a _newMissionItemsAvailable with the current items
            qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle: sync complete simulate signal";
            _itemsRequested = true;
            _newMissionItemsAvailableFromVehicle(false /* removeAllRequested */);
            return false;
        }
    }
}

2159
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2160
{
2161
    // Fly view always reloads on send complete
2162
    if (!error && _flyView) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2163 2164 2165 2166
        showPlanFromManagerVehicle();
    }
}

2167
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2168
{
2169 2170 2171 2172
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2173
}
2174 2175 2176 2177 2178 2179

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

2180
bool MissionController::distanceTimeToMissionEnd(double &remainingDistance, double &remainingTime, int missionIndex, bool useVehiclePosition) const
2181
{
2182
    // input check
2183 2184 2185 2186
    if (   _visualItems == nullptr
        || _visualItems->count() < 1
        || !_flyView
        || missionIndex < 1
2187
        || missionIndex > _visualItems->count()) {
2188 2189
        return false;
    }
2190 2191 2192 2193 2194 2195 2196 2197 2198 2199 2200
    // 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.");
        }
    }

2201 2202 2203 2204 2205 2206 2207 2208 2209 2210 2211 2212 2213 2214 2215 2216 2217 2218 2219 2220 2221 2222 2223 2224 2225 2226 2227 2228 2229 2230 2231 2232
    remainingDistance = 0;
    remainingTime = 0;

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


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

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

    // No values for first item
    lastCoordinateItem->setAltDifference(0.0);
    lastCoordinateItem->setAzimuth(0.0);
    lastCoordinateItem->setDistance(0.0);

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

    bool linkStartToHome    = false;
    bool linkEndToHome      = false;

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

2233
    // determine speed at waypoint with index missionIndex
2234 2235
    double currentSpeed = _settingsItem->specifiedFlightSpeed();
    currentSpeed = !qIsNaN(currentSpeed) ? currentSpeed : 5;
2236
    for (int i = 1; i < missionIndex; ++i) {
2237 2238 2239 2240 2241 2242 2243 2244 2245
        SimpleMissionItem* simpleItem = _visualItems->value<SimpleMissionItem*>(i);

        if (simpleItem != nullptr) {
            double speed = simpleItem->specifiedFlightSpeed();
            if (!qIsNaN(speed))
                currentSpeed = speed;
        }
    }

2246
    // calculate dist and time from current vehicle pos. to mission item with index missionIndex
2247
    if (useVehiclePosition) {
2248 2249 2250 2251 2252 2253 2254 2255 2256 2257 2258
        // 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;

                remainingDistance   += dist;
                remainingTime       += time;
                break;
            }
2259 2260 2261
        }
    }

2262
    // iterate over mission items starting at currentMissionIdx-1 and determine time and distance
2263
    for (int i=missionIndex; i<_visualItems->count(); i++) {
2264 2265 2266 2267 2268 2269 2270 2271 2272 2273 2274 2275 2276 2277 2278 2279 2280 2281 2282 2283 2284 2285 2286 2287 2288 2289 2290 2291 2292 2293 2294 2295 2296 2297 2298 2299 2300 2301 2302 2303 2304 2305 2306 2307 2308 2309 2310 2311 2312 2313 2314 2315 2316 2317 2318 2319 2320 2321 2322 2323 2324
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);

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

        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
            currentSpeed = newSpeed;
        }

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

                    QGeoCoordinate itemCoordinate = item->exitCoordinate();
                    QGeoCoordinate settingsCoordinate = _settingsItem->coordinate();
                    if (item->exitCoordinateHasRelativeAltitude()) {
                        itemCoordinate.setAltitude(homePositionAltitude + settingsCoordinate.altitude());
                    }

                    double altDifference = settingsCoordinate.altitude() - itemCoordinate.altitude();

                    double takeoffTime = qAbs(altDifference) / _appSettings->offlineEditingAscentSpeed()->rawValue().toDouble();
                    remainingTime += takeoffTime;
                }
            }
        }

        remainingTime += item->additionalTimeDelay();

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

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

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

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

2326 2327 2328 2329
        if (    simpleItem != nullptr
            && (   simpleItem->command() == MAV_CMD_NAV_LAND
                || simpleItem->command() == MAV_CMD_NAV_LAND_LOCAL
                || simpleItem->command() == MAV_CMD_NAV_VTOL_LAND)) {
2330

2331 2332 2333 2334 2335 2336 2337 2338 2339 2340 2341 2342 2343 2344 2345 2346
            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;
        }
2347 2348 2349 2350 2351 2352 2353 2354 2355 2356 2357 2358 2359 2360 2361 2362 2363 2364 2365 2366 2367 2368 2369
    }

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

2370 2371 2372 2373 2374 2375 2376 2377
VisualMissionItem* MissionController::currentPlanViewItem(void) const
{
    return _currentPlanViewItem;
}

void MissionController::setCurrentPlanViewIndex(int sequenceNumber, bool force)
{
    if(_visualItems && (force || sequenceNumber != _currentPlanViewIndex)) {
2378
        _currentPlanViewItem  = nullptr;
2379 2380 2381 2382 2383 2384 2385 2386 2387 2388 2389 2390 2391 2392 2393
        _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();
    }
}
2394 2395 2396

void MissionController::_updateTimeout()
{
Gus Grubba's avatar
Gus Grubba committed
2397
    QGeoCoordinate firstCoordinate;
2398
    QGeoCoordinate takeoffCoordinate;
2399
    QGCGeoBoundingCube boundingCube;
2400 2401 2402 2403
    double north = 0.0;
    double south = 180.0;
    double east  = 0.0;
    double west  = 360.0;
2404 2405
    double minAlt = QGCGeoBoundingCube::MaxAlt;
    double maxAlt = QGCGeoBoundingCube::MinAlt;
2406 2407 2408 2409 2410 2411
    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()) {
2412
                case MAV_CMD_NAV_TAKEOFF:
2413 2414 2415
                case MAV_CMD_NAV_WAYPOINT:
                case MAV_CMD_NAV_LAND:
                if(pSimpleItem->coordinate().isValid()) {
2416
                    if((MAV_CMD)pSimpleItem->command() == MAV_CMD_NAV_TAKEOFF) {
Gus Grubba's avatar
Gus Grubba committed
2417 2418 2419 2420
                        takeoffCoordinate = pSimpleItem->coordinate();
                    } else if(!firstCoordinate.isValid()) {
                        firstCoordinate = pSimpleItem->coordinate();
                    }
2421 2422
                    double lat = pSimpleItem->coordinate().latitude()  + 90.0;
                    double lon = pSimpleItem->coordinate().longitude() + 180.0;
2423
                    double alt = pSimpleItem->coordinate().altitude();
2424 2425 2426 2427
                    north  = fmax(north, lat);
                    south  = fmin(south, lat);
                    east   = fmax(east,  lon);
                    west   = fmin(west,  lon);
2428 2429
                    minAlt = fmin(minAlt, alt);
                    maxAlt = fmax(maxAlt, alt);
2430 2431 2432 2433 2434 2435 2436 2437 2438
                }
                break;
                default:
                    break;
                }
            }
        } else {
            ComplexMissionItem* pComplexItem = qobject_cast<ComplexMissionItem*>(item);
            if(pComplexItem) {
2439 2440
                QGCGeoBoundingCube bc = pComplexItem->boundingCube();
                if(bc.isValid()) {
Gus Grubba's avatar
Gus Grubba committed
2441 2442 2443
                    if(!firstCoordinate.isValid() && pComplexItem->coordinate().isValid()) {
                        firstCoordinate = pComplexItem->coordinate();
                    }
2444 2445 2446 2447 2448 2449
                    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());
2450 2451 2452 2453
                }
            }
        }
    }
Gus Grubba's avatar
Gus Grubba committed
2454 2455 2456 2457 2458 2459 2460 2461 2462
    //-- Figure out where this thing is taking off from
    if(!takeoffCoordinate.isValid()) {
        if(firstCoordinate.isValid()) {
            takeoffCoordinate = firstCoordinate;
        } else {
            takeoffCoordinate = plannedHomePosition();
        }
    }
    //-- Build bounding "cube"
2463 2464 2465
    boundingCube = QGCGeoBoundingCube(
        QGeoCoordinate(north - 90.0, west - 180.0, minAlt),
        QGeoCoordinate(south - 90.0, east - 180.0, maxAlt));
2466 2467
    if(_travelBoundingCube != boundingCube || _takeoffCoordinate != takeoffCoordinate) {
        _takeoffCoordinate  = takeoffCoordinate;
2468
        _travelBoundingCube = boundingCube;
2469
        emit missionBoundingCubeChanged();
2470
        qCDebug(MissionControllerLog) << "Bounding cube:" << _travelBoundingCube.pointNW << _travelBoundingCube.pointSE;
2471 2472 2473 2474 2475 2476 2477
    }
}

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