MissionController.cc 103 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
}

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

96 97
}

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

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

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

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

141 142
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262
void MissionController::_setRemainingDistance(double dist)
{
    if (qFuzzyCompare(dist, _remainingDistance) == false) {
        _remainingDistance = dist;

        emit remainingDistanceChanged();
    }
}

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

        emit remainingTimeChanged();
    }
}

263
void MissionController::sendToVehicle(void)
264
{
DonLakeFlyer's avatar
DonLakeFlyer committed
265 266 267 268 269
    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
270
        qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
271
        _warnIfTerrainFrameUsed();
DonLakeFlyer's avatar
DonLakeFlyer committed
272 273 274 275 276 277 278 279 280
        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
281 282
}

283
/// Converts from visual items to MissionItems
284
///     @param missionItemParent QObject parent for newly allocated MissionItems, _surveyMissionItemName    (tr("Survey"))
285
/// @return true: Mission end action was added to end of list
286
bool MissionController::convertToMissionItems(QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent)
287
{
DonLakeFlyer's avatar
DonLakeFlyer committed
288 289 290 291
    if (visualMissionItems->count() == 0) {
        return false;
    }

292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307
    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
308
    MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
309 310 311 312 313 314 315
    if (settingsItem) {
        endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
    }

    return endActionSet;
}

316 317
void MissionController::convertToKMLDocument(QDomDocument& document)
{
318 319
    QObject*            deleteParent = new QObject();
    QList<MissionItem*> rgMissionItems;
320

321
    convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
322
    if (rgMissionItems.count() == 0) {
323 324
        return;
    }
325

326
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
327 328 329 330 331

    QString coord;
    QStringList coords;
    // Drop home position
    bool dropPoint = true;
332
    for(const auto& item : rgMissionItems) {
333 334 335 336 337
        if(dropPoint) {
            dropPoint = false;
            continue;
        }
        const MissionCommandUIInfo* uiInfo = \
338
                qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, item->command());
339 340

        if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
341
            double amslAltitude = item->param7() + (item->frame() == MAV_FRAME_GLOBAL ? 0 : homePositionAltitude);
yaoling's avatar
yaoling committed
342
            coord = QString::number(item->param6(),'f',7) \
343 344 345
                    + "," \
                    + QString::number(item->param5(),'f',7) \
                    + "," \
346
                    + QString::number(amslAltitude,'f',2);
347 348 349
            coords.append(coord);
        }
    }
350 351 352

    deleteParent->deleteLater();

353 354 355 356 357
    Kml kml;
    kml.points(coords);
    kml.save(document);
}

Don Gagne's avatar
Don Gagne committed
358 359 360
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
361
        QList<MissionItem*> rgMissionItems;
362

363
        convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
364

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

370 371 372 373 374 375
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
376 377
        VisualMissionItem* lastItem = _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1);
        return lastItem->lastSequenceNumber() + 1;
378 379 380
    }
}

381
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
382
{
383
    int sequenceNumber = _nextSequenceNumber();
384
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
385
    newItem->setSequenceNumber(sequenceNumber);
386
    newItem->setCoordinate(coordinate);
387
    newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
388
    _initVisualItem(newItem);
389
    if (_visualItems->count() == 1 && (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() || _controllerVehicle->multiRotor())) {
390
        MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
391
        if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) {
392 393
            newItem->setCommand(takeoffCmd);
        }
394
    }
395 396 397
    if (newItem->specifiesAltitude()) {
        double  prevAltitude;
        int     prevAltitudeMode;
398

399 400
        if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
            newItem->altitude()->setRawValue(prevAltitude);
401
            newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
402
        }
403
    }
404
    newItem->setMissionFlightStatus(_missionFlightStatus);
405
    _visualItems->insert(i, newItem);
406

407 408
    // 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);
409

410
    return newItem->sequenceNumber();
411 412
}

413 414 415 416 417 418 419 420 421
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)) {
422
            newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
423 424 425
            return -1; // can not add this takeoff command for this vehicle
        }
    }
426 427 428 429 430 431
    if (newItem->specifiesAltitude()) {        
        newItem->altitude()->setRawValue(missionItem.relativeAltitude());
        newItem->setAltitudeMode(QGroundControlQmlGlobal::AltitudeMode::AltitudeModeRelative);
    }
    newItem->setMissionFlightStatus(_missionFlightStatus);
    _visualItems->insert(i, newItem);
432

433 434 435
    return newItem->sequenceNumber();
}

436
int MissionController::insertSimpleMissionItem(SimpleMissionItem &missionItem, int i)
437 438 439 440 441 442 443 444 445 446
{
    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
447 448
        }
    }
Valentin Platzgummer's avatar
Valentin Platzgummer committed
449
    newItem->setMissionFlightStatus(_missionFlightStatus);
450 451 452
    _visualItems->insert(i, newItem);

    return newItem->sequenceNumber();
453
}
454

455 456 457
int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
{
    int sequenceNumber = _nextSequenceNumber();
458
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
459
    newItem->setSequenceNumber(sequenceNumber);
460
    newItem->setCommand((_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_DO_SET_ROI_LOCATION) ?
461 462
        MAV_CMD_DO_SET_ROI_LOCATION :
        MAV_CMD_DO_SET_ROI));
463
    _initVisualItem(newItem);
464
    newItem->setCoordinate(coordinate);
465

466 467
    double  prevAltitude;
    int     prevAltitudeMode;
468

469 470
    if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
        newItem->altitude()->setRawValue(prevAltitude);
471
        newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
472 473 474 475 476 477 478 479
    }
    _visualItems->insert(i, newItem);

    _recalcAll();

    return newItem->sequenceNumber();
}

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

484
    int sequenceNumber = _nextSequenceNumber();
485
    if (itemName == _surveyMissionItemName) {
486
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
487
        newItem->setCoordinate(mapCenterCoordinate);
488
    } else if (itemName == patternFWLandingName) {
489
        newItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, _visualItems /* parent */);
490
    } else if (itemName == patternStructureScanName) {
491
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
492
    } else if (itemName == patternCorridorScanName) {
493
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
494 495
    } else if (itemName == _circularSurveyMissionItemName) {
        newItem = new CircularSurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
496 497 498 499 500
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }

501 502 503
    return _insertComplexMissionItemWorker(newItem, i);
}

504
int MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int i)
505 506 507 508
{
    ComplexMissionItem* newItem;

    if (itemName == _surveyMissionItemName) {
509
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
510 511
    } else if (itemName == _circularSurveyMissionItemName) {
        newItem = new CircularSurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
512
    } else if (itemName == patternStructureScanName) {
513
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
514
    } else if (itemName == patternCorridorScanName) {
515
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
516 517 518 519 520 521 522 523 524 525 526
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return _nextSequenceNumber();
    }

    return _insertComplexMissionItemWorker(newItem, i);
}

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

531
    if (surveyStyleItem) {
532
        bool rollSupported  = false;
533
        bool pitchSupported = false;
534
        bool yawSupported   = false;
535 536 537

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

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

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

547
        // Point gimbal straight down
548
        if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
549 550 551
            // If the user already specified a gimbal angle leave it alone
            if (!cameraSection->specifyGimbal()) {
                cameraSection->setSpecifyGimbal(true);
552
                cameraSection->gimbalPitch()->setRawValue(-90.0);
553 554
            }
        }
555
    }
556

557 558
    complexItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(complexItem);
559

560 561 562 563 564
    if (i == -1) {
        _visualItems->append(complexItem);
    } else {
        _visualItems->insert(i, complexItem);
    }
565

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

572
    return complexItem->sequenceNumber();
573 574
}

575 576
void MissionController::removeMissionItem(int index)
{
577 578 579 580 581
    if (index <= 0 || index >= _visualItems->count()) {
        qWarning() << "MissionController::removeMissionItem called with bad index - count:index" << _visualItems->count() << index;
        return;
    }

582 583 584
    bool removeSurveyStyle =    _visualItems->value<SurveyComplexItem*>(index)
                             || _visualItems->value<CorridorScanComplexItem*>(index)
                             || _visualItems->value<CircularSurveyComplexItem*>(index);
585
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
586

587
    _deinitVisualItem(item);
588
    item->deleteLater();
589

590 591
    if (removeSurveyStyle) {
        // Determine if the mission still has another survey style item in it
592 593
        bool foundSurvey = false;
        for (int i=1; i<_visualItems->count(); i++) {
594 595 596
            if (    _visualItems->value<SurveyComplexItem*>(i)
                 || _visualItems->value<CorridorScanComplexItem*>(i)
                 || _visualItems->value<CircularSurveyComplexItem*>(i)) {
597 598 599 600 601
                foundSurvey = true;
                break;
            }
        }

602
        // If there is no longer a survey item in the mission remove added commands
603 604 605 606
        if (!foundSurvey) {
            bool rollSupported = false;
            bool pitchSupported = false;
            bool yawSupported = false;
607 608
            MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
            CameraSection* cameraSection = settingsItem->cameraSection();
609
            if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
610
                if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
611 612 613
                    cameraSection->setSpecifyGimbal(false);
                }
            }
614
            if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
615 616
                cameraSection->setSpecifyCameraMode(false);
            }
617 618 619
        }
    }

620
    _recalcAll();
621
    setDirty(true);
622 623
}

624
void MissionController::removeAll(void)
625
{
626 627
    if (_visualItems) {
        _deinitAllVisualItems();
DonLakeFlyer's avatar
DonLakeFlyer committed
628
        _visualItems->clearAndDeleteContents();
Don Gagne's avatar
Don Gagne committed
629
        _visualItems->deleteLater();
630
        _settingsItem = nullptr;
631
        _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
632
        _addMissionSettings(_visualItems, false /* addToCenter */);
633
        _initAllVisualItems();
634
        setDirty(true);
635
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
636 637 638
    }
}

639
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
640 641 642 643 644 645 646 647 648
{
    // 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)) {
649 650 651
        return false;
    }

652
    // Read complex items
653
    QList<SurveyComplexItem*> surveyItems;
654 655 656 657
    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];
658

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

664
        SurveyComplexItem* item = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems /* parent */);
Don Gagne's avatar
Don Gagne committed
665 666
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
667
            surveyItems.append(item);
668 669
        } else {
            return false;
670
        }
671
    }
672

673 674 675 676 677
    // 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
678
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
679

680
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
681 682 683 684
    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
685
        if (nextComplexItemIndex < surveyItems.count()) {
686
            SurveyComplexItem* complexItem = surveyItems[nextComplexItemIndex];
687 688 689 690 691 692 693 694 695 696 697 698 699 700

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

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

Don Gagne's avatar
Don Gagne committed
706
            const QJsonObject itemObject = itemValue.toObject();
707
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
Don Gagne's avatar
Don Gagne committed
708
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
709
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
710
                nextSequenceNumber = item->lastSequenceNumber() + 1;
711
                visualItems->append(item);
712 713 714 715
            } else {
                return false;
            }
        }
716
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
717 718

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

Don Gagne's avatar
Don Gagne committed
721
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
722
            MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
723 724 725
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
726 727 728 729
        } else {
            return false;
        }
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
730
        _addMissionSettings(visualItems, true /* addToCenter */);
731 732 733 734 735
    }

    return true;
}

736
bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
737 738 739 740 741 742
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
743
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
744 745
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
746 747 748 749 750 751 752
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

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

756 757
    if (_masterController->offline()) {
        // We only update if offline since if we are online we use the online vehicle settings
758
        appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType(static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt())));
759
        if (json.contains(_jsonVehicleTypeKey)) {
760
            appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType(static_cast<MAV_TYPE>(json[_jsonVehicleTypeKey].toInt())));
761
        }
762
    }
763
    if (json.contains(_jsonCruiseSpeedKey)) {
764
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
765 766
    }
    if (json.contains(_jsonHoverSpeedKey)) {
767
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
768 769
    }

770 771 772 773
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
774
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
775 776
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802
    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) {
803
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
804
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
805
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
806
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
807 808 809 810 811 812 813 814 815 816 817 818 819
                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();

820
            if (complexItemType == SurveyComplexItem::jsonComplexItemTypeValue) {
Don Gagne's avatar
Don Gagne committed
821
                qCDebug(MissionControllerLog) << "Loading Survey: nextSequenceNumber" << nextSequenceNumber;
822
                SurveyComplexItem* surveyItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
Don Gagne's avatar
Don Gagne committed
823 824 825 826 827 828
                if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(surveyItem);
829
            } else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
830
                qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
831
                FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
832 833 834 835 836 837
                if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(landingItem);
838 839
            } else if (complexItemType == StructureScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Structure Scan: nextSequenceNumber" << nextSequenceNumber;
840
                StructureScanComplexItem* structureItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
841 842 843 844 845 846
                if (!structureItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = structureItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Structure Scan load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(structureItem);
847 848
            } else if (complexItemType == CorridorScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Corridor Scan: nextSequenceNumber" << nextSequenceNumber;
849
                CorridorScanComplexItem* corridorItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
850 851 852 853 854 855
                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
856 857 858 859 860 861 862 863 864
            } 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);
865
            } else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
866
                qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
867
                MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
868 869 870 871 872 873
                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
874 875 876 877 878 879 880 881 882 883 884 885 886
            } 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);
887
            if (doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
888
                bool found = false;
889
                int findDoJumpId = static_cast<int>(doJumpItem->missionItem().param1());
Don Gagne's avatar
Don Gagne committed
890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910
                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;
}

911 912 913 914 915 916 917 918
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;
919 920 921 922 923 924
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
925 926

    if (fileVersion == 1) {
927
        return _loadJsonMissionFileV1(json, visualItems, errorString);
928
    } else {
929
        return _loadJsonMissionFileV2(json, visualItems, errorString);
930 931 932
    }
}

933
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
934
{
935 936
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
937 938 939 940 941 942 943 944 945

    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;
946
            plannedHomePositionInFile = true;
947 948 949
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
950
            plannedHomePositionInFile = false;
951 952 953 954
        }
    }

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

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

            if (item->load(stream)) {
963 964 965 966 967 968
                if (firstItem && plannedHomePositionInFile) {
                    settingsItem->setCoordinate(item->coordinate());
                } else {
                    visualItems->append(item);
                }
                firstItem = false;
969
            } else {
970
                errorString = tr("The mission file is corrupted.");
971 972 973 974
                return false;
            }
        }
    } else {
975
        errorString = tr("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
976 977 978
        return false;
    }

979
    if (!plannedHomePositionInFile) {
980 981 982
        // 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));
983
            if (item && item->command() == MAV_CMD_DO_JUMP) {
984
                item->missionItem().setParam1(static_cast<int>(item->missionItem().param1()) + 1);
Don Gagne's avatar
Don Gagne committed
985 986
            }
        }
987 988 989
    }

    return true;
990 991
}

992
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
993
{
Don Gagne's avatar
Don Gagne committed
994 995 996
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
997
        _settingsItem = nullptr;
Don Gagne's avatar
Don Gagne committed
998 999
    }

1000
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
1001 1002

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

1006
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
1007

Don Gagne's avatar
Don Gagne committed
1008
    _initAllVisualItems();
1009
}
1010

1011 1012 1013 1014 1015 1016
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

1017
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042
        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;
1043
    }
1044

1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057
    _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);
1058
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
1059 1060 1061 1062 1063 1064
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
1065
    return true;
1066 1067
}

1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079
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;
}

1080
bool MissionController::setTakeoffCommand(SimpleMissionItem &missionItem)
1081
{
1082
    if (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() || _controllerVehicle->multiRotor()) {
1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093
        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;
}

1094
bool MissionController::setLandCommand(SimpleMissionItem &missionItem)
1095
{
1096 1097
    MAV_CMD landCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_LAND;
    if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(landCmd)) {
1098 1099 1100 1101 1102 1103 1104
        missionItem.setCommand(landCmd);
    } else
        return false;

    return true;
}

1105
void MissionController::save(QJsonObject& json)
1106
{
1107
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
1108

1109
    // Mission settings
1110

1111 1112 1113 1114 1115 1116 1117
    MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsItem";
        return;
    }
    QJsonValue coordinateValue;
    JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
1118 1119 1120 1121 1122
    json[_jsonPlannedHomePositionKey]   = coordinateValue;
    json[_jsonFirmwareTypeKey]          = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey]           = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey]           = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey]            = _controllerVehicle->defaultHoverSpeed();
1123

1124
    // Save the visual items
1125

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

1130 1131
        visualItem->save(rgJsonMissionItems);
    }
1132

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

1137
        if (convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
1138 1139 1140 1141
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
1142
        }
1143 1144
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
1145 1146 1147
        }
    }

1148
    json[_jsonItemsKey] = rgJsonMissionItems;
1149 1150
}

1151
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
1152
{
Don Gagne's avatar
Don Gagne committed
1153
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
1154
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
1155 1156 1157 1158
    bool            distanceOk =    false;

    // Convert to fixed altitudes

1159
    distanceOk = true;
1160
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
1161 1162
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
1163
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
1164
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
1165 1166 1167
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
1168 1169 1170
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
1171
    } else {
Don Gagne's avatar
Don Gagne committed
1172
        *altDifference = 0.0;
1173
        *azimuth = 0.0;
1174
        *distance = 0.0;
1175 1176 1177
    }
}

1178
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
1179 1180 1181 1182 1183 1184 1185
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

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

1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210
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;
    }
}

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

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

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

Nate Weibley's avatar
Nate Weibley committed
1220 1221
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
1222
    _waypointLines.clear();
1223
    _waypointPath.clear();
1224

1225 1226 1227 1228 1229 1230 1231 1232 1233
    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;
1234 1235 1236
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));

1237 1238 1239 1240 1241 1242
        // 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;
1243
            }
1244 1245
        }

1246 1247 1248
        if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
            firstCoordinateItem = false;
            if (lastCoordinateItem != _settingsItem || (homePositionValid && linkStartToHome)) {
1249
                if (!_flyView) {
1250 1251
                    VisualItemPair pair(lastCoordinateItem, item);
                    _addWaypointLineSegment(old_table, pair);
1252 1253
                }
            }
1254 1255
            _waypointPath.append(QVariant::fromValue(item->coordinate()));
            lastCoordinateItem = item;
1256 1257
        }
    }
1258 1259 1260 1261 1262 1263

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

    if (linkEndToHome && lastCoordinateItem != _settingsItem && homePositionValid) {
1264
        if (!_flyView) {
1265 1266 1267 1268 1269
            VisualItemPair pair(lastCoordinateItem, _settingsItem);
            _addWaypointLineSegment(old_table, pair);
        } else {
            _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
        }
1270
    }
1271 1272 1273 1274

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1275
        objs.reserve(_linesTable.count());
1276
        for(CoordinateVector *vect: _linesTable.values()) {
1277 1278 1279 1280 1281 1282 1283 1284 1285 1286
            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
1287
    _recalcMissionFlightStatus();
1288

1289 1290 1291 1292 1293 1294 1295 1296
    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)));
    }

1297
    emit waypointLinesChanged();
1298
    emit waypointPathChanged();
1299 1300
}

1301 1302 1303 1304 1305 1306
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);
1307 1308 1309
        // 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.
1310
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333
            _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);
}

1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360
/// 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
1361
void MissionController::_recalcMissionFlightStatus()
1362
{
1363
    if (!_visualItems->count()) {
1364
        return;
1365
    }
1366 1367 1368 1369

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

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1372
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1373

1374 1375 1376
    // 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.
1377

1378
    // No values for first item
1379
    lastCoordinateItem->setAltDifference(0.0);
1380
    lastCoordinateItem->setAzimuth(0.0);
1381
    lastCoordinateItem->setDistance(0.0);
1382

1383 1384
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1385 1386
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1387

1388
    _resetMissionFlightStatus();
1389

DonLakeFlyer's avatar
DonLakeFlyer committed
1390
    bool vtolInHover = true;
1391
    bool linkStartToHome = false;
1392 1393 1394 1395 1396 1397 1398 1399 1400 1401
    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();
        }
    }
1402

DonLakeFlyer's avatar
DonLakeFlyer committed
1403
    for (int i=0; i<_visualItems->count(); i++) {
1404
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1405 1406 1407
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1408 1409
        // Assume the worst
        item->setAzimuth(0.0);
1410
        item->setDistance(0.0);
1411

DonLakeFlyer's avatar
DonLakeFlyer committed
1412 1413 1414
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1415
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1416
                _missionFlightStatus.hoverSpeed = newSpeed;
1417
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1418 1419
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1420
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1421
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1422
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1423 1424
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1425
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1426 1427 1428 1429
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1430 1431 1432 1433 1434 1435 1436
        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
1437 1438 1439 1440 1441
        }

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

1444
        // Link back to home if first item is takeoff and we have home position
1445
        if (firstCoordinateItem && simpleItem && (simpleItem->command() == MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
1446
            if (showHomePosition) {
1447
                linkStartToHome = true;
1448 1449 1450 1451 1452 1453 1454
                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);
                }
1455 1456 1457 1458
            }
        }

        // Update VTOL state
1459
        if (simpleItem && _controllerVehicle->vtol()) {
1460
            switch (simpleItem->command()) {
1461
            case MAV_CMD_NAV_TAKEOFF:
1462 1463
                vtolInHover = false;
                break;
1464
            case MAV_CMD_NAV_VTOL_TAKEOFF:
DonLakeFlyer's avatar
DonLakeFlyer committed
1465 1466
                vtolInHover = true;
                break;
1467
            case MAV_CMD_NAV_LAND:
1468 1469
                vtolInHover = false;
                break;
1470
            case MAV_CMD_NAV_VTOL_LAND:
DonLakeFlyer's avatar
DonLakeFlyer committed
1471 1472
                vtolInHover = true;
                break;
1473
            case MAV_CMD_DO_VTOL_TRANSITION:
1474 1475 1476 1477 1478 1479
            {
                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;
1480 1481
                }
            }
1482 1483 1484
                break;
            default:
                break;
1485
            }
Don Gagne's avatar
Don Gagne committed
1486 1487
        }

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

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

1493
            double absoluteAltitude = item->coordinate().altitude();
1494
            if (item->coordinateHasRelativeAltitude()) {
1495 1496 1497 1498 1499
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1500 1501 1502 1503
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1504 1505 1506
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1507
                firstCoordinateItem = false;
1508 1509 1510 1511 1512 1513 1514

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

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

1519
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1520 1521 1522
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1523

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1526 1527 1528
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1529
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1530
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1531

1532
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1533 1534
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1535
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1536

1537 1538
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1539
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1540
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1541 1542

                item->setMissionFlightStatus(_missionFlightStatus);
1543

1544 1545
                lastCoordinateItem = item;
            }
1546 1547
        }
    }
1548
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1549

1550 1551 1552 1553 1554 1555 1556 1557
    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();
1558
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1559 1560
    }

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1565 1566 1567 1568 1569 1570 1571
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1572 1573
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1574

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

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1582
            if (item->coordinateHasRelativeAltitude()) {
1583 1584 1585 1586
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1587
                item->setTerrainPercent(qQNaN());
1588
                item->setTerrainCollision(false);
1589 1590
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1591 1592 1593 1594 1595 1596 1597
                double terrainAltitude = item->terrainAltitude();
                if (qIsNaN(terrainAltitude)) {
                    item->setTerrainPercent(qQNaN());
                    item->setTerrainCollision(false);
                } else {
                    item->setTerrainPercent((terrainAltitude - minAltSeen) / altRange);
                    item->setTerrainCollision(absoluteAltitude < terrainAltitude);
1598
                }
1599
            }
1600 1601
        }
    }
1602 1603

    _updateTimer.start(UPDATE_TIMEOUT);
1604 1605
}

1606 1607 1608
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1609 1610 1611 1612 1613
    if (_inRecalcSequence) {
        // Don't let this call recurse due to signalling
        return;
    }

1614 1615
    // Setup ascending sequence numbers for all visual items

1616
    _inRecalcSequence = true;
1617 1618 1619
    int sequenceNumber = 0;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1620 1621
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1622 1623
    }    
    _inRecalcSequence = false;
1624 1625
}

1626 1627 1628
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1629
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1630 1631 1632

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

1633 1634
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1635 1636 1637 1638 1639

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

1646
void MissionController::_setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate)
1647
{
1648 1649
    QGeoCoordinate firstCoordinate;

1650 1651 1652 1653
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1654
    // Set the planned home position to be a delta from first coordinate
1655 1656 1657 1658
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

        if (item->specifiesCoordinate()) {
1659 1660
            firstCoordinate = item->coordinate();
            break;
1661 1662 1663
        }
    }

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

1669 1670 1671 1672 1673 1674 1675 1676 1677
    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)
1678
{
1679
    if (!_flyView) {
1680
        _setPlannedHomePositionFromFirstCoordinate(clickCoordinate);
1681
    }
1682
    _recalcSequence();
1683 1684
    _recalcChildItems();
    _recalcWaypointLines();
1685
    _updateTimer.start(UPDATE_TIMEOUT);
1686 1687
}

1688 1689 1690 1691 1692 1693
void MissionController::_recalcAll(void)
{
    QGeoCoordinate emptyCoord;
    _recalcAllWithClickCoordinate(emptyCoord);
}

1694 1695 1696 1697 1698 1699
void MissionController::_enableDisableRemainingDistTimeCalculation(bool flying)
{
    if (flying) {
        _remainingDistanceTimeTimer.start();
    } else {
        _remainingDistanceTimeTimer.stop();
1700 1701
        _setRemainingTime(-1);
        _setRemainingDistance(-1);
1702 1703 1704 1705 1706 1707 1708
    }
}

void MissionController::_updateRemainingDistanceTime()
{
    double dist = 0;
    double time = 0;
1709
    bool success = distanceTimeToMissionEnd(dist, time, _missionManager->currentIndex() /*missionIndex >= 1*/, true /* useVehiclePostion */);
1710
    if (success) {
1711 1712 1713 1714 1715
        _setRemainingTime(time);
        _setRemainingDistance(dist);
    } else {
        _setRemainingTime(-1);
        _setRemainingDistance(-1);
1716 1717 1718
    }
}

1719
/// Initializes a new set of mission items
1720
void MissionController::_initAllVisualItems(void)
1721
{
1722 1723
    // Setup home position at index 0

1724 1725 1726
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1727 1728
        return;
    }
1729
    if (!_flyView) {
1730 1731
        _settingsItem->setIsCurrentItem(true);
    }
1732

1733
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1734
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1735
    }
1736

1737 1738 1739
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1740

1741 1742 1743 1744
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1745

1746
    _recalcAll();
1747

1748
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1749 1750 1751
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1752
    emit containsItemsChanged(containsItems());
1753
    emit plannedHomePositionChanged(plannedHomePosition());
1754

1755
    setDirty(false);
1756 1757
}

1758
void MissionController::_deinitAllVisualItems(void)
1759
{
1760 1761 1762
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

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

1767
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1768
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1769 1770
}

1771
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1772
{
1773
    setDirty(false);
1774

1775
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1776 1777
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1778 1779
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1780
    connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged,                this, &MissionController::_recalcMissionFlightStatus);
1781
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1782
    connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged,                 this, &MissionController::_recalcMissionFlightStatus);
1783
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1784

1785 1786 1787 1788 1789 1790 1791 1792
    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";
        }
1793 1794
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1795
        if (complexItem) {
1796
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
1797
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
1798 1799 1800
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1801
    }
1802 1803
}

1804
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1805
{
1806 1807
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1808 1809
}

1810
void MissionController::_itemCommandChanged(void)
1811
{
1812 1813
    _recalcChildItems();
    _recalcWaypointLines();
1814 1815
}

1816
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1817
{
1818 1819 1820 1821 1822 1823
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1824

1825 1826
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1827
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1828 1829
        return;
    }
1830

1831 1832
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1833 1834
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1835 1836 1837 1838 1839
    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);
1840
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1841 1842 1843 1844
    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);
1845
    connect(_managerVehicle, &Vehicle::flyingChanged,                   this, &MissionController::_enableDisableRemainingDistTimeCalculation);
1846

1847 1848
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1849
    }
1850

1851
    emit complexMissionItemNamesChanged();
1852
    emit resumeMissionIndexChanged();
1853 1854
}

1855
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1856
{
1857
    if (_visualItems) {
1858 1859
        bool currentDirtyBit = dirty();

1860
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1861
        if (settingsItem) {
1862
            settingsItem->setHomePositionFromVehicle(homePosition);
1863
        } else {
1864
            qWarning() << "First item is not MissionSettingsItem";
1865
        }
1866 1867 1868 1869 1870 1871

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

void MissionController::_inProgressChanged(bool inProgress)
1876
{
1877
    emit syncInProgressChanged(inProgress);
1878
}
1879

1880
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1881
{
1882 1883
    bool        found = false;
    double      foundAltitude;
1884
    int         foundAltitudeMode;
1885

1886 1887 1888 1889 1890 1891
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1894 1895 1896
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1897 1898 1899
                if (simpleItem->specifiesAltitude()) {
                    foundAltitude = simpleItem->altitude()->rawValue().toDouble();
                    foundAltitudeMode = simpleItem->altitudeMode();
1900
                    found = true;
1901
                    break;
1902 1903
                }
            }
1904 1905 1906
        }
    }

1907
    if (found) {
1908
        *prevAltitude = foundAltitude;
1909
        *prevAltitudeMode = foundAltitudeMode;
1910 1911 1912
    }

    return found;
1913
}
1914 1915 1916 1917 1918 1919 1920 1921 1922 1923 1924 1925 1926

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

1927
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1928
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1929
{
1930
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
1931

Don Gagne's avatar
Don Gagne committed
1932 1933
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1934
    visualItems->insert(0, settingsItem);
1935

1936 1937 1938 1939 1940 1941 1942 1943 1944 1945 1946 1947 1948 1949 1950 1951 1952 1953 1954 1955 1956 1957 1958 1959 1960
    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;
                    }
1961 1962
                }
            }
1963

1964 1965 1966
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1967
        }
Don Gagne's avatar
Don Gagne committed
1968 1969
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1970 1971
    }
}
1972

1973
int MissionController::resumeMissionIndex(void) const
1974
{
1975

1976
    int resumeIndex = 0;
1977

1978
    if (_flyView) {
1979
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1980
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1981 1982
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1983 1984
        } else {
            resumeIndex = 0;
1985 1986 1987 1988 1989
        }
    }

    return resumeIndex;
}
1990

1991 1992
int MissionController::currentMissionIndex(void) const
{
1993
    if (!_flyView) {
1994 1995 1996 1997 1998 1999 2000 2001 2002 2003
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

2004
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
2005
{
2006
    if (_flyView) {
2007
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
2008 2009 2010
            sequenceNumber++;
        }

2011 2012
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
2013 2014
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
2015
        emit currentMissionIndexChanged(currentMissionIndex());
2016 2017
    }
}
2018

2019
bool MissionController::syncInProgress(void) const
2020
{
2021
    return _missionManager->inProgress();
2022 2023 2024 2025 2026 2027 2028 2029 2030 2031 2032 2033
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
2034
    }
2035
}
2036

2037 2038
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
2039 2040
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, vehicle);
2041

2042 2043 2044 2045 2046 2047
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

2048
        if (!_flyView) {
2049 2050 2051 2052 2053 2054
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
2055 2056 2057
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
2058
        if (simpleItem) {
2059 2060 2061 2062 2063
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
2064 2065 2066
        }
    }
}
2067 2068 2069 2070 2071 2072 2073 2074 2075 2076 2077 2078 2079

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
2080 2081 2082 2083 2084 2085 2086 2087
    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();
    }
2088
}
2089 2090 2091 2092 2093

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

2094
    complexItems.append(_circularSurveyMissionItemName);
2095
    complexItems.append(_surveyMissionItemName);
2096
    complexItems.append(patternCorridorScanName);
2097
    if (_controllerVehicle->fixedWing()) {
2098
        complexItems.append(patternFWLandingName);
2099
    }
2100
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
2101
        complexItems.append(patternStructureScanName);
2102
    }
2103

2104
    return qgcApp()->toolbox()->corePlugin()->complexMissionItemNames(_controllerVehicle, complexItems);
2105
}
2106

2107 2108
void MissionController::resumeMission(int resumeIndex)
{
2109
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
2110 2111
        resumeIndex--;
    }
2112
    _missionManager->generateResumeMission(resumeIndex);
2113
}
2114 2115 2116 2117 2118 2119 2120 2121 2122

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
2123 2124 2125 2126 2127 2128 2129 2130 2131 2132

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

2134 2135 2136 2137 2138 2139 2140
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
2141 2142 2143 2144 2145 2146

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
2147 2148 2149

bool MissionController::showPlanFromManagerVehicle (void)
{
2150
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
DonLakeFlyer's avatar
DonLakeFlyer committed
2151 2152
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
2153
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
2154 2155 2156 2157 2158 2159 2160 2161 2162 2163 2164 2165 2166 2167 2168 2169 2170 2171 2172
    } 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;
        }
    }
}

2173
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2174
{
2175
    // Fly view always reloads on send complete
2176
    if (!error && _flyView) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2177 2178 2179 2180
        showPlanFromManagerVehicle();
    }
}

2181
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2182
{
2183 2184 2185 2186
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2187
}
2188 2189 2190 2191 2192 2193

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

2194
bool MissionController::distanceTimeToMissionEnd(double &remainingDistance, double &remainingTime, int missionIndex, bool useVehiclePosition) const
2195
{
2196
    // input check
2197 2198 2199 2200
    if (   _visualItems == nullptr
        || _visualItems->count() < 1
        || !_flyView
        || missionIndex < 1
2201
        || missionIndex > _visualItems->count()) {
2202 2203
        return false;
    }
2204 2205 2206 2207 2208 2209 2210 2211 2212 2213 2214
    // 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.");
        }
    }

2215 2216 2217 2218 2219 2220 2221 2222 2223 2224 2225 2226 2227 2228 2229 2230 2231 2232 2233 2234 2235 2236 2237 2238 2239 2240 2241 2242 2243 2244 2245 2246
    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();
        }
    }

2247
    // determine speed at waypoint with index missionIndex
2248 2249
    double currentSpeed = _settingsItem->specifiedFlightSpeed();
    currentSpeed = !qIsNaN(currentSpeed) ? currentSpeed : 5;
2250
    for (int i = 1; i < missionIndex; ++i) {
2251 2252 2253 2254 2255 2256 2257 2258 2259
        SimpleMissionItem* simpleItem = _visualItems->value<SimpleMissionItem*>(i);

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

2260
    // calculate dist and time from current vehicle pos. to mission item with index missionIndex
2261
    if (useVehiclePosition) {
2262 2263 2264 2265 2266 2267 2268 2269 2270 2271 2272
        // 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;
            }
2273 2274 2275
        }
    }

2276
    // iterate over mission items starting at currentMissionIdx-1 and determine time and distance
2277
    for (int i=missionIndex; i<_visualItems->count(); i++) {
2278 2279 2280 2281 2282 2283 2284 2285 2286 2287 2288 2289 2290 2291 2292 2293 2294 2295 2296 2297 2298 2299 2300 2301 2302 2303 2304 2305 2306 2307 2308 2309 2310 2311 2312 2313 2314 2315 2316 2317 2318 2319 2320 2321 2322 2323 2324 2325 2326 2327 2328 2329 2330 2331 2332 2333 2334 2335 2336 2337 2338
        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;
        }
2339

2340 2341 2342 2343
        if (    simpleItem != nullptr
            && (   simpleItem->command() == MAV_CMD_NAV_LAND
                || simpleItem->command() == MAV_CMD_NAV_LAND_LOCAL
                || simpleItem->command() == MAV_CMD_NAV_VTOL_LAND)) {
2344

2345 2346 2347 2348 2349 2350 2351 2352 2353 2354 2355 2356 2357 2358 2359 2360
            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;
        }
2361 2362 2363 2364 2365 2366 2367 2368 2369 2370 2371 2372 2373 2374 2375 2376 2377 2378 2379 2380 2381 2382 2383
    }

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

2384 2385 2386 2387 2388 2389 2390 2391
VisualMissionItem* MissionController::currentPlanViewItem(void) const
{
    return _currentPlanViewItem;
}

void MissionController::setCurrentPlanViewIndex(int sequenceNumber, bool force)
{
    if(_visualItems && (force || sequenceNumber != _currentPlanViewIndex)) {
2392
        _currentPlanViewItem  = nullptr;
2393 2394 2395 2396 2397 2398 2399 2400 2401 2402 2403 2404 2405 2406 2407
        _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();
    }
}
2408 2409 2410

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

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