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


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
#include "TakeoffMissionItem.h"
34

35 36
#define UPDATE_TIMEOUT 5000 ///< How often we check for bounding box changes

37 38
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

39
const char* MissionController::_settingsGroup =                 "MissionController";
Don Gagne's avatar
Don Gagne committed
40 41
const char* MissionController::_jsonFileTypeValue =             "Mission";
const char* MissionController::_jsonItemsKey =                  "items";
42
const char* MissionController::_jsonPlannedHomePositionKey =    "plannedHomePosition";
Don Gagne's avatar
Don Gagne committed
43
const char* MissionController::_jsonFirmwareTypeKey =           "firmwareType";
44 45 46
const char* MissionController::_jsonVehicleTypeKey =            "vehicleType";
const char* MissionController::_jsonCruiseSpeedKey =            "cruiseSpeed";
const char* MissionController::_jsonHoverSpeedKey =             "hoverSpeed";
Don Gagne's avatar
Don Gagne committed
47 48 49 50 51 52 53
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;
54

DonLakeFlyer's avatar
DonLakeFlyer committed
55 56 57 58
const QString MissionController::patternSurveyName          (QT_TRANSLATE_NOOP("MissionController", "Survey"));
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"));
59

60
MissionController::MissionController(PlanMasterController* masterController, QObject *parent)
61 62 63 64 65 66 67 68 69 70
    : PlanElementController     (masterController, parent)
    , _missionManager           (_managerVehicle->missionManager())
    , _missionItemCount         (0)
    , _visualItems              (nullptr)
    , _settingsItem             (nullptr)
    , _firstItemsFromVehicle    (false)
    , _itemsRequested           (false)
    , _inRecalcSequence         (false)
    , _appSettings              (qgcApp()->toolbox()->settingsManager()->appSettings())
    , _progressPct              (0)
71 72
    , _currentPlanViewSeqNum    (-1)
    , _currentPlanViewVIIndex   (-1)
73
    , _currentPlanViewItem      (nullptr)
74
    , _splitSegment             (nullptr)
75
{
76
    _resetMissionFlightStatus();
77
    managerVehicleChanged(_managerVehicle);
78 79
    _updateTimer.setSingleShot(true);
    connect(&_updateTimer, &QTimer::timeout, this, &MissionController::_updateTimeout);
80 81 82 83
}

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

85 86
}

87 88 89 90 91 92 93 94 95
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;
96 97 98
    _missionFlightStatus.cruiseSpeed =          _controllerVehicle->defaultCruiseSpeed();
    _missionFlightStatus.hoverSpeed =           _controllerVehicle->defaultHoverSpeed();
    _missionFlightStatus.vehicleSpeed =         _controllerVehicle->multiRotor() || _managerVehicle->vtol() ? _missionFlightStatus.hoverSpeed : _missionFlightStatus.cruiseSpeed;
99
    _missionFlightStatus.vehicleYaw =           0.0;
100
    _missionFlightStatus.gimbalYaw =            std::numeric_limits<double>::quiet_NaN();
101
    _missionFlightStatus.gimbalPitch =          std::numeric_limits<double>::quiet_NaN();
102 103 104 105 106 107 108 109 110 111 112 113

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

114 115 116
    _controllerVehicle->firmwarePlugin()->batteryConsumptionData(_controllerVehicle, _missionFlightStatus.mAhBattery, _missionFlightStatus.hoverAmps, _missionFlightStatus.cruiseAmps);
    if (_missionFlightStatus.mAhBattery != 0) {
        double batteryPercentRemainingAnnounce = qgcApp()->toolbox()->settingsManager()->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toDouble();
117
        _missionFlightStatus.ampMinutesAvailable = static_cast<double>(_missionFlightStatus.mAhBattery) / 1000.0 * 60.0 * ((100.0 - batteryPercentRemainingAnnounce) / 100.0);
118
    }
119 120 121 122 123 124 125 126 127 128 129

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

130 131
}

132
void MissionController::start(bool flyView)
133
{
134
    qCDebug(MissionControllerLog) << "start flyView" << flyView;
135

136
    PlanElementController::start(flyView);
137 138 139 140 141
    _init();
}

void MissionController::_init(void)
{
142
    // We start with an empty mission
143
    _visualItems = new QmlObjectListModel(this);
144
    _addMissionSettings(_visualItems);
145
    _initAllVisualItems();
146 147
}

148
// Called when new mission items have completed downloading from Vehicle
149
void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllRequested)
150
{
151
    qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle flyView:count" << _flyView << _missionManager->missionItems().count();
152

DonLakeFlyer's avatar
DonLakeFlyer committed
153
    // Fly view always reloads on _loadComplete
154 155 156 157
    // Plan view only reloads if:
    //  - Load was specifically requested
    //  - There is no current Plan
    if (_flyView || removeAllRequested || _itemsRequested || isEmpty()) {
158
        // Fly Mode (accept if):
Don Gagne's avatar
Don Gagne committed
159
        //      - Always accepts new items from the vehicle so Fly view is kept up to date
160
        // Edit Mode (accept if):
161 162
        //      - 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
163
        //      - The initial automatic load from a vehicle completed and the current editor is empty
164

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

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

175 176 177
        _missionItemCount = newMissionItems.count();
        emit missionItemCountChanged(_missionItemCount);

178
        MissionSettingsItem* settingsItem = _addMissionSettings(newControllerMissionItems);
179 180

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

190
        for (; i < newMissionItems.count(); i++) {
191
            const MissionItem* missionItem = newMissionItems[i];
192 193 194
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, *missionItem, this);
            if (TakeoffMissionItem::isTakeoffCommand(static_cast<MAV_CMD>(simpleItem->command()))) {
                // This needs to be a TakeoffMissionItem
195
                TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(*missionItem, _controllerVehicle, _flyView, settingsItem, this);
196 197 198 199
                simpleItem->deleteLater();
                simpleItem = takeoffItem;
            }
            newControllerMissionItems->append(simpleItem);
200 201 202
        }

        _visualItems = newControllerMissionItems;
203
        _settingsItem = settingsItem;
204

205
        MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
206

207
        _initAllVisualItems();
208
        _updateContainsItems();
209
        emit newItemsFromVehicle();
210
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
211
    _itemsRequested = false;
212 213
}

214
void MissionController::loadFromVehicle(void)
215
{
DonLakeFlyer's avatar
DonLakeFlyer committed
216 217 218 219 220 221 222 223
    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();
    }
224 225
}

226 227 228 229
void MissionController::_warnIfTerrainFrameUsed(void)
{
    for (int i=1; i<_visualItems->count(); i++) {
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(i));
230
        if (simpleItem && simpleItem->altitudeMode() == QGroundControlQmlGlobal::AltitudeModeTerrainFrame) {
231 232 233 234 235 236
            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;
        }
    }
}

237
void MissionController::sendToVehicle(void)
238
{
DonLakeFlyer's avatar
DonLakeFlyer committed
239 240 241 242 243
    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
244
        qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
245
        _warnIfTerrainFrameUsed();
DonLakeFlyer's avatar
DonLakeFlyer committed
246 247 248 249 250 251 252 253 254
        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
255 256
}

257 258 259 260 261
/// Converts from visual items to MissionItems
///     @param missionItemParent QObject parent for newly allocated MissionItems
/// @return true: Mission end action was added to end of list
bool MissionController::_convertToMissionItems(QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
262 263 264 265
    if (visualMissionItems->count() == 0) {
        return false;
    }

266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281
    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
282
    MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
283 284 285 286 287 288 289
    if (settingsItem) {
        endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
    }

    return endActionSet;
}

290 291
void MissionController::convertToKMLDocument(QDomDocument& document)
{
292 293
    QObject*            deleteParent = new QObject();
    QList<MissionItem*> rgMissionItems;
294

295 296
    _convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
    if (rgMissionItems.count() == 0) {
297 298
        return;
    }
299

300
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
301 302 303 304 305

    QString coord;
    QStringList coords;
    // Drop home position
    bool dropPoint = true;
306
    for(const auto& item : rgMissionItems) {
307 308 309 310 311
        if(dropPoint) {
            dropPoint = false;
            continue;
        }
        const MissionCommandUIInfo* uiInfo = \
312
                qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, item->command());
313 314

        if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
315
            double amslAltitude = item->param7() + (item->frame() == MAV_FRAME_GLOBAL ? 0 : homePositionAltitude);
yaoling's avatar
yaoling committed
316
            coord = QString::number(item->param6(),'f',7) \
317 318 319
                    + "," \
                    + QString::number(item->param5(),'f',7) \
                    + "," \
320
                    + QString::number(amslAltitude,'f',2);
321 322 323
            coords.append(coord);
        }
    }
324 325 326

    deleteParent->deleteLater();

327 328 329 330 331
    Kml kml;
    kml.points(coords);
    kml.save(document);
}

Don Gagne's avatar
Don Gagne committed
332 333 334
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
335
        QList<MissionItem*> rgMissionItems;
336

337
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
338

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

344 345 346 347 348 349
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
350 351
        VisualMissionItem* lastItem = _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1);
        return lastItem->lastSequenceNumber() + 1;
352 353 354
    }
}

355
VisualMissionItem* MissionController::_insertSimpleMissionItemWorker(QGeoCoordinate coordinate, MAV_CMD command, int visualItemIndex, bool makeCurrentItem)
356
{
357
    int sequenceNumber = _nextSequenceNumber();
358
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
359
    newItem->setSequenceNumber(sequenceNumber);
360
    newItem->setCoordinate(coordinate);
361
    newItem->setCommand(command);
362
    _initVisualItem(newItem);
363 364 365 366 367 368 369 370

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

        if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltitudeMode)) {
            newItem->altitude()->setRawValue(prevAltitude);
            newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
371
        }
372
    }
373 374 375 376 377 378 379 380
    newItem->setMissionFlightStatus(_missionFlightStatus);
    if (visualItemIndex == -1) {
        _visualItems->append(newItem);
    } else {
        _visualItems->insert(visualItemIndex, newItem);
    }

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

    if (makeCurrentItem) {
384
        setCurrentPlanViewSeqNum(newItem->sequenceNumber(), true);
385 386 387 388 389
    }

    return newItem;
}

390 391 392 393 394 395

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

396
VisualMissionItem* MissionController::insertTakeoffItem(QGeoCoordinate /*coordinate*/, int visualItemIndex, bool makeCurrentItem)
397 398
{
    int sequenceNumber = _nextSequenceNumber();
DonLakeFlyer's avatar
DonLakeFlyer committed
399
    TakeoffMissionItem * newItem = new TakeoffMissionItem(_controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF, _controllerVehicle, _flyView, _settingsItem, this);
400 401 402
    newItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(newItem);

403 404 405
    if (newItem->specifiesAltitude()) {
        double  prevAltitude;
        int     prevAltitudeMode;
406

Don Gagne's avatar
Don Gagne committed
407
        if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltitudeMode)) {
408
            newItem->altitude()->setRawValue(prevAltitude);
409
            newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
410
        }
411
    }
412
    newItem->setMissionFlightStatus(_missionFlightStatus);
413 414 415 416 417
    if (visualItemIndex == -1) {
        _visualItems->append(newItem);
    } else {
        _visualItems->insert(visualItemIndex, newItem);
    }
418

419
    _recalcAll();
420

421
    if (makeCurrentItem) {
422
        setCurrentPlanViewSeqNum(newItem->sequenceNumber(), true);
423 424 425
    }

    return newItem;
426 427
}

428
VisualMissionItem* MissionController::insertLandItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem)
429
{
430 431 432 433
    if (_managerVehicle->fixedWing()) {
        FixedWingLandingComplexItem* fwLanding = qobject_cast<FixedWingLandingComplexItem*>(insertComplexMissionItem(MissionController::patternFWLandingName, coordinate, visualItemIndex, makeCurrentItem));
        fwLanding->setLoiterDragAngleOnly(true);
        return fwLanding;
434
    } else {
435
        return _insertSimpleMissionItemWorker(coordinate, MAV_CMD_NAV_RETURN_TO_LAUNCH, visualItemIndex, makeCurrentItem);
436
    }
437
}
438

439 440
VisualMissionItem* MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem)
{
441 442 443 444 445 446
    SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_insertSimpleMissionItemWorker(coordinate, MAV_CMD_DO_SET_ROI_LOCATION, visualItemIndex, makeCurrentItem));

    if (!_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_DO_SET_ROI_LOCATION)) {
        simpleItem->setCommand(MAV_CMD_DO_SET_ROI)  ;
        simpleItem->missionItem().setParam1(MAV_ROI_LOCATION);
    }
447
    _recalcROISpecialVisuals();
448 449 450 451 452 453 454 455 456 457 458
    return simpleItem;
}

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

    if (!_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_DO_SET_ROI_NONE)) {
        simpleItem->setCommand(MAV_CMD_DO_SET_ROI)  ;
        simpleItem->missionItem().setParam1(MAV_ROI_NONE);
    }
459
    _recalcROISpecialVisuals();
460
    return simpleItem;
461 462
}

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

DonLakeFlyer's avatar
DonLakeFlyer committed
467
    if (itemName == patternSurveyName) {
468
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
469
        newItem->setCoordinate(mapCenterCoordinate);
470
    } else if (itemName == patternFWLandingName) {
471
        newItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, _visualItems /* parent */);
472
    } else if (itemName == patternStructureScanName) {
473
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
474
    } else if (itemName == patternCorridorScanName) {
475
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
476 477
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
478
        return nullptr;
479 480
    }

481
    _insertComplexMissionItemWorker(mapCenterCoordinate, newItem, visualItemIndex, makeCurrentItem);
482 483

    return newItem;
484 485
}

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

DonLakeFlyer's avatar
DonLakeFlyer committed
490
    if (itemName == patternSurveyName) {
491
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
492
    } else if (itemName == patternStructureScanName) {
493
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
494
    } else if (itemName == patternCorridorScanName) {
495
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
496 497
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
498
        return nullptr;
499 500
    }

501
    _insertComplexMissionItemWorker(QGeoCoordinate(), newItem, visualItemIndex, makeCurrentItem);
502 503

    return newItem;
504 505
}

506
void MissionController::_insertComplexMissionItemWorker(const QGeoCoordinate& mapCenterCoordinate, ComplexMissionItem* complexItem, int visualItemIndex, bool makeCurrentItem)
507 508
{
    int sequenceNumber = _nextSequenceNumber();
509
    bool surveyStyleItem = qobject_cast<SurveyComplexItem*>(complexItem) ||
510 511
            qobject_cast<CorridorScanComplexItem*>(complexItem) ||
            qobject_cast<StructureScanComplexItem*>(complexItem);
512

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

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

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

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

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

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

Don Gagne's avatar
Don Gagne committed
543
    if (visualItemIndex == -1) {
544 545
        _visualItems->append(complexItem);
    } else {
Don Gagne's avatar
Don Gagne committed
546
        _visualItems->insert(visualItemIndex, complexItem);
547
    }
548

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

555
    if (makeCurrentItem) {
556
        setCurrentPlanViewSeqNum(complexItem->sequenceNumber(), true);
557
    }
558 559
}

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

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

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

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

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

600
    _recalcAll();
601 602 603 604 605 606 607 608 609 610

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

611
    setDirty(true);
612 613
}

614
void MissionController::removeAll(void)
615
{
616 617
    if (_visualItems) {
        _deinitAllVisualItems();
DonLakeFlyer's avatar
DonLakeFlyer committed
618
        _visualItems->clearAndDeleteContents();
Don Gagne's avatar
Don Gagne committed
619
        _visualItems->deleteLater();
620
        _settingsItem = nullptr;
621
        _visualItems = new QmlObjectListModel(this);
622
        _addMissionSettings(_visualItems);
623
        _initAllVisualItems();
624
        setDirty(true);
625
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
626 627 628
    }
}

629
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
630 631 632 633 634 635 636 637 638
{
    // 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)) {
639 640 641
        return false;
    }

642
    // Read complex items
643
    QList<SurveyComplexItem*> surveyItems;
644 645 646 647
    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];
648

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

654
        SurveyComplexItem* item = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems /* parent */);
Don Gagne's avatar
Don Gagne committed
655 656
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
657
            surveyItems.append(item);
658 659
        } else {
            return false;
660
        }
661
    }
662

663 664 665 666 667
    // 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
668
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
669

670
    MissionSettingsItem* settingsItem = _addMissionSettings(visualItems);
671 672 673
    if (json.contains(_jsonPlannedHomePositionKey)) {
        SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
674
            settingsItem->setInitialHomePositionFromUser(item->coordinate());
675 676 677 678 679 680
            item->deleteLater();
        } else {
            return false;
        }
    }

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

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

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

Don Gagne's avatar
Don Gagne committed
707
            const QJsonObject itemObject = itemValue.toObject();
708
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
Don Gagne's avatar
Don Gagne committed
709
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
710 711
                if (TakeoffMissionItem::isTakeoffCommand(item->mavCommand())) {
                    // This needs to be a TakeoffMissionItem
712
                    TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, visualItems);
713 714 715 716
                    takeoffItem->load(itemObject, itemObject["id"].toInt(), errorString);
                    item->deleteLater();
                    item = takeoffItem;
                }
717
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
718
                nextSequenceNumber = item->lastSequenceNumber() + 1;
719
                visualItems->append(item);
720 721 722 723
            } else {
                return false;
            }
        }
724
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
725 726 727 728

    return true;
}

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

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

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

749 750
    if (_masterController->offline()) {
        // We only update if offline since if we are online we use the online vehicle settings
751
        appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType(static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt())));
752
        if (json.contains(_jsonVehicleTypeKey)) {
753
            appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType(static_cast<MAV_TYPE>(json[_jsonVehicleTypeKey].toInt())));
754
        }
755
    }
756
    if (json.contains(_jsonCruiseSpeedKey)) {
757
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
758 759
    }
    if (json.contains(_jsonHoverSpeedKey)) {
760
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
761 762
    }

763 764 765 766
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
767 768 769
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795
    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) {
796
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
797
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
798 799
                if (TakeoffMissionItem::isTakeoffCommand(static_cast<MAV_CMD>(simpleItem->command()))) {
                    // This needs to be a TakeoffMissionItem
800
                    TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, this);
801 802 803 804
                    takeoffItem->load(itemObject, nextSequenceNumber, errorString);
                    simpleItem->deleteLater();
                    simpleItem = takeoffItem;
                }
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);
Don Gagne's avatar
Don Gagne committed
856 857 858 859 860 861 862 863 864 865 866 867 868
            } 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);
869
            if (doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
870
                bool found = false;
871
                int findDoJumpId = static_cast<int>(doJumpItem->missionItem().param1());
Don Gagne's avatar
Don Gagne committed
872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892
                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;
}

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

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

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

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

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

939
        while (!stream.atEnd()) {
940
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
941
            if (item->load(stream)) {
942
                if (firstItem && plannedHomePositionInFile) {
943
                    settingsItem->setInitialHomePositionFromUser(item->coordinate());
944
                } else {
945 946
                    if (TakeoffMissionItem::isTakeoffCommand(static_cast<MAV_CMD>(item->command()))) {
                        // This needs to be a TakeoffMissionItem
947
                        TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, visualItems);
948 949 950 951
                        takeoffItem->load(stream);
                        item->deleteLater();
                        item = takeoffItem;
                    }
952 953 954
                    visualItems->append(item);
                }
                firstItem = false;
955
            } else {
956
                errorString = tr("The mission file is corrupted.");
957 958 959 960
                return false;
            }
        }
    } else {
961
        errorString = tr("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
962 963 964
        return false;
    }

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

    return true;
976 977
}

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

986
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
987 988

    if (_visualItems->count() == 0) {
989
        _addMissionSettings(_visualItems);
990 991
    } else {
        _settingsItem = _visualItems->value<MissionSettingsItem*>(0);
Don Gagne's avatar
Don Gagne committed
992 993
    }

994
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
995

Don Gagne's avatar
Don Gagne committed
996
    _initAllVisualItems();
997
}
998

999 1000 1001 1002 1003 1004
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

1005
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030
        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;
1031
    }
1032

1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045
    _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);
1046
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
1047 1048 1049 1050 1051 1052
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
1053
    return true;
1054 1055
}

1056
int MissionController::readyForSaveState(void) const
1057 1058 1059
{
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
DonLakeFlyer's avatar
DonLakeFlyer committed
1060
        if (visualItem->readyForSaveState() != VisualMissionItem::ReadyForSave) {
1061
            return visualItem->readyForSaveState();
1062 1063 1064
        }
    }

1065
    return VisualMissionItem::ReadyForSave;
1066 1067
}

1068
void MissionController::save(QJsonObject& json)
1069
{
1070
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
1071

1072
    // Mission settings
1073

1074 1075 1076 1077 1078 1079 1080
    MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsItem";
        return;
    }
    QJsonValue coordinateValue;
    JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
1081 1082 1083 1084 1085
    json[_jsonPlannedHomePositionKey]   = coordinateValue;
    json[_jsonFirmwareTypeKey]          = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey]           = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey]           = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey]            = _controllerVehicle->defaultHoverSpeed();
1086

1087
    // Save the visual items
1088

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

1093 1094
        visualItem->save(rgJsonMissionItems);
    }
1095

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

1100 1101 1102 1103 1104
        if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
1105
        }
1106 1107
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
1108 1109 1110
        }
    }

1111
    json[_jsonItemsKey] = rgJsonMissionItems;
1112 1113
}

1114
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
1115
{
Don Gagne's avatar
Don Gagne committed
1116
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
1117
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
1118 1119 1120 1121
    bool            distanceOk =    false;

    // Convert to fixed altitudes

1122
    distanceOk = true;
1123
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
1124 1125
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
1126
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
1127
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
1128 1129 1130
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
1131 1132 1133
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
1134
    } else {
Don Gagne's avatar
Don Gagne committed
1135
        *altDifference = 0.0;
1136
        *azimuth = 0.0;
1137
        *distance = 0.0;
1138 1139 1140
    }
}

1141
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
1142 1143 1144 1145 1146 1147 1148
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

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

1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171
CoordinateVector* MissionController::_createCoordinateVectorWorker(VisualItemPair& pair)
{
    CoordinateVector* coordVector = nullptr;

    // Create a new segment and wire update notifiers
    coordVector         = 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, coordVector, &CoordinateVector::setCoordinate1);
    connect(pair.second,    endNotifier,    coordVector, &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);

    return coordVector;
}

1172
CoordinateVector* MissionController::_addWaypointLineSegment(CoordVectHashTable& prevItemPairHashTable, VisualItemPair& pair)
1173
{
1174 1175
    CoordinateVector* coordVector = nullptr;

1176 1177
    if (prevItemPairHashTable.contains(pair)) {
        // Pair already exists and connected, just re-use
1178
        _linesTable[pair] = coordVector = prevItemPairHashTable.take(pair);
1179
    } else {
1180
        coordVector = _createCoordinateVectorWorker(pair);
1181
        _linesTable[pair] = coordVector;
1182
    }
1183 1184

    return coordVector;
1185 1186
}

1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219
void MissionController::_recalcROISpecialVisuals(void)
{
    return;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));
    bool                roiActive =             false;

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

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

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

1220 1221
void MissionController::_recalcWaypointLines(void)
{
1222
    VisualItemPair      lastSegmentVisualItemPair;
1223 1224 1225 1226 1227 1228
    int                 segmentCount =                  0;
    bool                firstCoordinateNotFound =       true;
    VisualMissionItem*  lastCoordinateItemBeforeRTL =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));
    bool                linkEndToHome =                 false;
    bool                linkStartToHome =               _managerVehicle->rover() ? true : false;
    bool                foundRTL =                      false;
1229 1230
    bool                homePositionValid =             _settingsItem->coordinate().isValid();
    bool                roiActive =                     false;
1231 1232
    bool                setupIncompleteItem =           false;
    VisualMissionItem*  startVIForIncompleteItem =      nullptr;
1233

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

Nate Weibley's avatar
Nate Weibley committed
1236
    CoordVectHashTable old_table = _linesTable;
1237

Nate Weibley's avatar
Nate Weibley committed
1238
    _linesTable.clear();
1239
    _waypointPath.clear();
1240 1241 1242

    _waypointLines.beginReset();
    _directionArrows.beginReset();
1243
    _incompleteComplexItemLines.beginReset();
1244 1245

    _waypointLines.clear();
1246
    _directionArrows.clear();
1247
    _incompleteComplexItemLines.clearAndDeleteContents();
1248

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

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

1256
        if (simpleItem) {
1257 1258 1259 1260 1261 1262 1263 1264 1265 1266
            if (roiActive) {
                if (_isROICancelItem(simpleItem)) {
                    roiActive = false;
                }
            } else {
                if (_isROIBeginItem(simpleItem)) {
                    roiActive = true;
                }
            }

1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284
            MAV_CMD command = simpleItem->mavCommand();
            switch (command) {
            case MAV_CMD_NAV_TAKEOFF:
            case MAV_CMD_NAV_VTOL_TAKEOFF:
                if (!linkEndToHome) {
                    // If we still haven't found the first coordinate item and we hit a takeoff command this means the mission starts from the ground.
                    // Link the first item back to home to show that.
                    if (firstCoordinateNotFound) {
                        linkStartToHome = true;
                    }
                }
                break;
            case MAV_CMD_NAV_RETURN_TO_LAUNCH:
                linkEndToHome = true;
                foundRTL = true;
                break;
            default:
                break;
1285
            }
1286 1287
        }

1288 1289 1290 1291 1292 1293
        // No need to add waypoint segments after an RTL.
        if (foundRTL) {
            break;
        }

        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308
            // Incomplete items are complex items which are waiting for the user to complete setup before there visuals can become valid.
            // For example a Survey which has no polygon set for it yet. For these cases we draw incomplete segment lines so that there
            // isn't a hole in the flight path lines.
            if (complexItem && complexItem->isIncomplete()) {
                setupIncompleteItem = true;
            } else {
                if (setupIncompleteItem) {
                    VisualItemPair viPair(startVIForIncompleteItem, visualItem);
                    CoordinateVector* coordVector = _createCoordinateVectorWorker(viPair);

                    _incompleteComplexItemLines.append(coordVector);
                    startVIForIncompleteItem = nullptr;
                    setupIncompleteItem = false;
                } else {
                    startVIForIncompleteItem = visualItem;
1309
                }
1310

1311
                if (lastCoordinateItemBeforeRTL != _settingsItem || (homePositionValid && linkStartToHome)) {
1312
                    bool addDirectionArrow = false;
1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323
                    if (i != 1) {
                        // Direction arrows are added to the second segment and every 5 segments thereafter.
                        // The reason for start with second segment is to prevent an arrow being added in between the home position
                        // and a takeoff item which may be right over each other. In that case the arrow points in a random direction.
                        if (firstCoordinateNotFound || !lastCoordinateItemBeforeRTL->isSimpleItem() || !visualItem->isSimpleItem()) {
                            addDirectionArrow = true;
                        } else if (segmentCount > 5) {
                            segmentCount = 0;
                            addDirectionArrow = true;
                        }
                        segmentCount++;
1324 1325 1326 1327 1328 1329 1330 1331 1332
                    }

                    lastSegmentVisualItemPair =  VisualItemPair(lastCoordinateItemBeforeRTL, visualItem);
                    if (!_flyView || addDirectionArrow) {
                        CoordinateVector* coordVector = _addWaypointLineSegment(old_table, lastSegmentVisualItemPair);
                        coordVector->setSpecialVisual(roiActive);
                        if (addDirectionArrow) {
                            _directionArrows.append(coordVector);
                        }
1333
                    }
1334
                }
1335 1336 1337
                firstCoordinateNotFound = false;
                _waypointPath.append(QVariant::fromValue(visualItem->coordinate()));
                lastCoordinateItemBeforeRTL = visualItem;
1338 1339 1340
            }
        }
    }
1341 1342 1343 1344 1345

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

1346 1347
    if (linkEndToHome && lastCoordinateItemBeforeRTL != _settingsItem && homePositionValid) {
        lastSegmentVisualItemPair =  VisualItemPair(lastCoordinateItemBeforeRTL, _settingsItem);
1348
        if (_flyView) {
1349 1350
            _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
        }
1351 1352
        CoordinateVector* coordVector = _addWaypointLineSegment(old_table, lastSegmentVisualItemPair);
        coordVector->setSpecialVisual(roiActive);
1353
    }
1354

1355 1356 1357 1358 1359 1360 1361 1362 1363
    // Add direction arrow to last segment
    if (lastSegmentVisualItemPair.first) {
        CoordinateVector* coordVector = nullptr;

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

        if (_linesTable.contains(lastSegmentVisualItemPair)) {
            // Pair exists in the new table already just reuse it
1364
            coordVector = _linesTable[lastSegmentVisualItemPair];
1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377
        } else if (old_table.contains(lastSegmentVisualItemPair)) {
            // Pair already exists in old table, pull from old to new and reuse
            _linesTable[lastSegmentVisualItemPair] = coordVector = old_table.take(lastSegmentVisualItemPair);
        } else {
            // Create a new segment. Since this is the fly view there is no need to wire change signals.
            coordVector = new CoordinateVector(lastSegmentVisualItemPair.first->isSimpleItem() ? lastSegmentVisualItemPair.first->coordinate() : lastSegmentVisualItemPair.first->exitCoordinate(), lastSegmentVisualItemPair.second->coordinate(), this);
            _linesTable[lastSegmentVisualItemPair] = coordVector;
        }

        _directionArrows.append(coordVector);
    }

    if (!_flyView) {
1378 1379
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1380
        objs.reserve(_linesTable.count());
1381
        for(CoordinateVector *vect: _linesTable.values()) {
1382 1383 1384 1385 1386 1387 1388
            objs.append(vect);
        }

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

1389 1390
    _waypointLines.endReset();
    _directionArrows.endReset();
1391
    _incompleteComplexItemLines.endReset();
1392

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1396
    _recalcMissionFlightStatus();
1397

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

    emit waypointPathChanged();
1407 1408
}

1409 1410 1411 1412 1413 1414
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);
1415 1416 1417
        // 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.
1418
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441
            _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);
}

1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468
/// 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
1469
void MissionController::_recalcMissionFlightStatus()
1470
{
1471
    if (!_visualItems->count()) {
1472
        return;
1473
    }
1474

1475 1476
    bool                firstCoordinateItem =           true;
    VisualMissionItem*  lastCoordinateItemBeforeRTL =   qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1477

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1480
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1481

1482 1483 1484
    // 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.
1485

1486
    // No values for first item
1487 1488 1489
    lastCoordinateItemBeforeRTL->setAltDifference(0.0);
    lastCoordinateItemBeforeRTL->setAzimuth(0.0);
    lastCoordinateItemBeforeRTL->setDistance(0.0);
1490

1491 1492
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1493 1494
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1495

1496
    _resetMissionFlightStatus();
1497

DonLakeFlyer's avatar
DonLakeFlyer committed
1498
    bool vtolInHover = true;
1499
    bool linkStartToHome = false;
1500
    bool foundRTL = false;
1501
    bool vehicleYawSpecificallySet = false;
1502

DonLakeFlyer's avatar
DonLakeFlyer committed
1503
    for (int i=0; i<_visualItems->count(); i++) {
1504 1505 1506 1507 1508 1509 1510
        VisualMissionItem*  item =          qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        SimpleMissionItem*  simpleItem =    qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem =   qobject_cast<ComplexMissionItem*>(item);

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

1512 1513
        // Assume the worst
        item->setAzimuth(0.0);
1514
        item->setDistance(0.0);
1515

DonLakeFlyer's avatar
DonLakeFlyer committed
1516 1517 1518
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1519
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1520
                _missionFlightStatus.hoverSpeed = newSpeed;
1521
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1522 1523
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1524
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1525
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1526
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1527 1528
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1529
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1530 1531 1532
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

1533 1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547
        // ROI commands cancel out previous gimbal yaw/pitch
        if (simpleItem) {
            switch (simpleItem->command()) {
            case MAV_CMD_NAV_ROI:
            case MAV_CMD_DO_SET_ROI_LOCATION:
            case MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET:
                _missionFlightStatus.gimbalYaw = std::numeric_limits<double>::quiet_NaN();
                _missionFlightStatus.gimbalPitch = std::numeric_limits<double>::quiet_NaN();
                break;
            default:
                break;
            }
        }

        // Look for specific gimbal changes
1548 1549 1550 1551 1552 1553 1554
        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
1555 1556 1557 1558 1559
        }

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

1562 1563 1564 1565 1566
        if (foundRTL) {
            // No more vehicle distances after RTL
            continue;
        }

1567
        // Link back to home if first item is takeoff and we have home position
1568 1569
        if (firstCoordinateItem && simpleItem && (simpleItem->mavCommand() == MAV_CMD_NAV_TAKEOFF || simpleItem->mavCommand() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
            if (homePositionValid) {
1570
                linkStartToHome = true;
1571 1572 1573 1574 1575 1576 1577
                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);
                }
1578 1579 1580 1581
            }
        }

        // Update VTOL state
1582
        if (simpleItem && _controllerVehicle->vtol()) {
1583
            switch (simpleItem->command()) {
1584
            case MAV_CMD_NAV_TAKEOFF:
1585 1586
                vtolInHover = false;
                break;
1587
            case MAV_CMD_NAV_VTOL_TAKEOFF:
DonLakeFlyer's avatar
DonLakeFlyer committed
1588 1589
                vtolInHover = true;
                break;
1590
            case MAV_CMD_NAV_LAND:
1591 1592
                vtolInHover = false;
                break;
1593
            case MAV_CMD_NAV_VTOL_LAND:
DonLakeFlyer's avatar
DonLakeFlyer committed
1594 1595
                vtolInHover = true;
                break;
1596
            case MAV_CMD_DO_VTOL_TRANSITION:
1597 1598 1599 1600 1601 1602
            {
                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;
1603 1604
                }
            }
1605 1606 1607
                break;
            default:
                break;
1608
            }
Don Gagne's avatar
Don Gagne committed
1609 1610
        }

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

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

1616
            double absoluteAltitude = item->coordinate().altitude();
1617
            if (item->coordinateHasRelativeAltitude()) {
1618 1619 1620 1621 1622
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1623 1624 1625 1626
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1627 1628 1629
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1630
                firstCoordinateItem = false;
1631

1632
                // Update vehicle yaw assuming direction to next waypoint and/or mission item change
1633
                if (item != lastCoordinateItemBeforeRTL) {
1634 1635 1636 1637 1638 1639
                    if (simpleItem && !qIsNaN(simpleItem->specifiedVehicleYaw())) {
                        vehicleYawSpecificallySet = true;
                        _missionFlightStatus.vehicleYaw = simpleItem->specifiedVehicleYaw();
                    } else if (!vehicleYawSpecificallySet) {
                        _missionFlightStatus.vehicleYaw = lastCoordinateItemBeforeRTL->exitCoordinate().azimuthTo(item->coordinate());
                    }
1640
                    lastCoordinateItemBeforeRTL->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1641 1642
                }

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

1647
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItemBeforeRTL, &azimuth, &distance, &altDifference);
1648 1649 1650
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1651

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1654 1655 1656
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1657
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1658
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1659

1660
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1661 1662
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1663
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1664

1665 1666
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1667
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1668
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1669 1670

                item->setMissionFlightStatus(_missionFlightStatus);
1671

1672
                lastCoordinateItemBeforeRTL = item;
1673
            }
1674 1675
        }
    }
1676
    lastCoordinateItemBeforeRTL->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1677

1678 1679
    // Add the information for the final segment back to home
    if (foundRTL && lastCoordinateItemBeforeRTL != _settingsItem && homePositionValid) {
1680
        double azimuth, distance, altDifference;
1681
        _calcPrevWaypointValues(homePositionAltitude, lastCoordinateItemBeforeRTL, _settingsItem, &azimuth, &distance, &altDifference);
1682 1683 1684 1685 1686

        // Calculate time/distance
        double hoverTime = distance / _missionFlightStatus.hoverSpeed;
        double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
        double landTime = qAbs(altDifference) / _appSettings->offlineEditingDescentSpeed()->rawValue().toDouble();
1687
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1688 1689
    }

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1694 1695 1696 1697 1698 1699 1700
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1701 1702
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1703

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

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1711
            if (item->coordinateHasRelativeAltitude()) {
1712 1713 1714 1715
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1716
                item->setTerrainPercent(qQNaN());
1717
                item->setTerrainCollision(false);
1718 1719
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1720 1721 1722 1723 1724 1725 1726
                double terrainAltitude = item->terrainAltitude();
                if (qIsNaN(terrainAltitude)) {
                    item->setTerrainPercent(qQNaN());
                    item->setTerrainCollision(false);
                } else {
                    item->setTerrainPercent((terrainAltitude - minAltSeen) / altRange);
                    item->setTerrainCollision(absoluteAltitude < terrainAltitude);
1727
                }
1728
            }
1729 1730
        }
    }
1731 1732

    _updateTimer.start(UPDATE_TIMEOUT);
1733 1734
}

1735 1736 1737
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1738 1739 1740 1741 1742
    if (_inRecalcSequence) {
        // Don't let this call recurse due to signalling
        return;
    }

1743 1744
    // Setup ascending sequence numbers for all visual items

1745
    _inRecalcSequence = true;
1746 1747 1748
    int sequenceNumber = 0;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1749 1750
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1751
    }
1752
    _inRecalcSequence = false;
1753 1754
}

1755 1756 1757
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1758
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1759 1760 1761

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

1762
    for (int i=1; i<_visualItems->count(); i++) {
1763 1764 1765 1766
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

        item->setParentItem(nullptr);
        item->setHasCurrentChildItem(false);
1767 1768 1769 1770 1771

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1772
        } else if (item->isSimpleItem()) {
1773
            item->setParentItem(currentParentItem);
1774
            currentParentItem->childItems()->append(item);
1775 1776 1777
            if (item->isCurrentItem()) {
                currentParentItem->setHasCurrentChildItem(true);
            }
1778 1779 1780 1781
        }
    }
}

1782
void MissionController::_setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate)
1783
{
1784
    bool foundFirstCoordinate = false;
1785 1786
    QGeoCoordinate firstCoordinate;

1787 1788 1789 1790
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

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

1795 1796
        if (item->specifiesCoordinate() && item->coordinate().isValid()) {
            foundFirstCoordinate = true;
1797 1798
            firstCoordinate = item->coordinate();
            break;
1799 1800 1801
        }
    }

1802
    // No item specifying a coordinate was found, in this case it we have a clickCoordinate use that
1803
    if (!foundFirstCoordinate) {
1804 1805
        firstCoordinate = clickCoordinate;
    }
1806

1807 1808 1809
    if (firstCoordinate.isValid()) {
        QGeoCoordinate plannedHomeCoord = firstCoordinate.atDistanceAndAzimuth(30, 0);
        plannedHomeCoord.setAltitude(0);
1810
        _settingsItem->setInitialHomePositionFromUser(plannedHomeCoord);
1811 1812 1813
    }
}

1814
void MissionController::_recalcAllWithCoordinate(const QGeoCoordinate& coordinate)
1815
{
1816
    if (!_flyView) {
1817
        _setPlannedHomePositionFromFirstCoordinate(coordinate);
1818
    }
1819
    _recalcSequence();
1820 1821
    _recalcChildItems();
    _recalcWaypointLines();
1822
    _updateTimer.start(UPDATE_TIMEOUT);
1823 1824
}

1825 1826 1827
void MissionController::_recalcAll(void)
{
    QGeoCoordinate emptyCoord;
1828
    _recalcAllWithCoordinate(emptyCoord);
1829 1830
}

1831
/// Initializes a new set of mission items
1832
void MissionController::_initAllVisualItems(void)
1833
{
1834 1835
    // Setup home position at index 0

1836
    if (!_settingsItem) {
1837 1838 1839 1840 1841
        _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
        if (!_settingsItem) {
            qWarning() << "First item not MissionSettingsItem";
            return;
        }
1842
    }
1843

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

1847 1848 1849 1850
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1851

1852
    _recalcAll();
1853

1854
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1855 1856 1857
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1858
    emit containsItemsChanged(containsItems());
1859
    emit plannedHomePositionChanged(plannedHomePosition());
1860

1861
    if (!_flyView) {
1862
        setCurrentPlanViewSeqNum(0, true);
1863 1864
    }

1865
    setDirty(false);
1866 1867
}

1868
void MissionController::_deinitAllVisualItems(void)
1869
{
1870 1871 1872
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

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

1877
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1878
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1879 1880
}

1881
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1882
{
1883
    setDirty(false);
1884

1885
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1886 1887
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1888 1889
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1890
    connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged,                this, &MissionController::_recalcMissionFlightStatus);
1891
    connect(visualItem, &VisualMissionItem::specifiedVehicleYawChanged,                 this, &MissionController::_recalcMissionFlightStatus);
1892
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1893
    connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged,                 this, &MissionController::_recalcMissionFlightStatus);
1894
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1895

1896 1897 1898 1899 1900 1901 1902 1903
    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";
        }
1904 1905
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1906
        if (complexItem) {
1907
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
1908
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
1909
            connect(complexItem, &ComplexMissionItem::isIncompleteChanged,          this, &MissionController::_recalcWaypointLines);
1910 1911 1912
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1913
    }
1914 1915
}

1916
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1917
{
1918
    // Disconnect all signals
1919
    disconnect(visualItem, nullptr, nullptr, nullptr);
1920 1921
}

1922
void MissionController::_itemCommandChanged(void)
1923
{
1924 1925
    _recalcChildItems();
    _recalcWaypointLines();
1926 1927
}

1928
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1929
{
1930 1931 1932
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
1933 1934
        _managerVehicle = nullptr;
        _missionManager = nullptr;
1935
    }
1936

1937 1938
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1939
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1940 1941
        return;
    }
1942

1943 1944
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1945 1946
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1947 1948 1949 1950 1951
    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);
1952
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1953 1954 1955
    connect(_managerVehicle, &Vehicle::defaultCruiseSpeedChanged,       this, &MissionController::_recalcMissionFlightStatus);
    connect(_managerVehicle, &Vehicle::defaultHoverSpeedChanged,        this, &MissionController::_recalcMissionFlightStatus);
    connect(_managerVehicle, &Vehicle::vehicleTypeChanged,              this, &MissionController::complexMissionItemNamesChanged);
1956

1957
    emit complexMissionItemNamesChanged();
1958
    emit resumeMissionIndexChanged();
1959 1960 1961
}

void MissionController::_inProgressChanged(bool inProgress)
1962
{
1963
    emit syncInProgressChanged(inProgress);
1964
}
1965

1966
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1967
{
1968
    bool        found = false;
1969
    double      foundAltitude = 0;
1970
    int         foundAltitudeMode = QGroundControlQmlGlobal::AltitudeModeNone;
1971

1972 1973 1974 1975 1976 1977
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1980 1981 1982
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1983 1984 1985
                if (simpleItem->specifiesAltitude()) {
                    foundAltitude = simpleItem->altitude()->rawValue().toDouble();
                    foundAltitudeMode = simpleItem->altitudeMode();
1986
                    found = true;
1987
                    break;
1988 1989
                }
            }
1990 1991 1992
        }
    }

1993
    if (found) {
1994
        *prevAltitude = foundAltitude;
1995
        *prevAltitudeMode = foundAltitudeMode;
1996 1997 1998
    }

    return found;
1999
}
2000 2001 2002 2003 2004 2005 2006 2007 2008 2009 2010 2011 2012

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

2013
/// Add the Mission Settings complex item to the front of the items
2014
MissionSettingsItem* MissionController::_addMissionSettings(QmlObjectListModel* visualItems)
2015
{
2016 2017
    qCDebug(MissionControllerLog) << "_addMissionSettings";

2018
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_managerVehicle, _flyView, visualItems);
2019
    visualItems->insert(0, settingsItem);
2020

2021 2022 2023 2024 2025
    if (visualItems == _visualItems) {
        _settingsItem = settingsItem;
    }

    return settingsItem;
2026
}
Don Gagne's avatar
Don Gagne committed
2027

2028 2029 2030
void MissionController::_centerHomePositionOnMissionItems(QmlObjectListModel *visualItems)
{
    qCDebug(MissionControllerLog) << "_centerHomePositionOnMissionItems";
2031

2032 2033 2034 2035 2036 2037 2038 2039 2040 2041 2042 2043 2044 2045 2046 2047 2048 2049 2050 2051 2052 2053 2054
    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;
2055 2056
                }
            }
2057
        }
2058

2059 2060
        if (firstCoordSet) {
            _settingsItem->setInitialHomePositionFromUser(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
2061 2062 2063
        }
    }
}
2064

2065
int MissionController::resumeMissionIndex(void) const
2066
{
2067

2068
    int resumeIndex = 0;
2069

2070
    if (_flyView) {
2071
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
2072
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
2073 2074
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
2075 2076
        } else {
            resumeIndex = 0;
2077 2078 2079 2080 2081
        }
    }

    return resumeIndex;
}
2082

2083 2084
int MissionController::currentMissionIndex(void) const
{
2085
    if (!_flyView) {
2086 2087 2088 2089 2090 2091 2092 2093 2094 2095
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

2096
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
2097
{
2098
    if (_flyView) {
2099
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
2100 2101 2102
            sequenceNumber++;
        }

2103 2104
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
2105 2106
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
2107
        emit currentMissionIndexChanged(currentMissionIndex());
2108 2109
    }
}
2110

2111
bool MissionController::syncInProgress(void) const
2112
{
2113
    return _missionManager->inProgress();
2114 2115 2116 2117 2118 2119 2120 2121 2122 2123 2124 2125
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
2126
    }
2127
}
2128

2129 2130
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
2131 2132
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, vehicle);
2133

2134 2135 2136 2137 2138 2139
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

2140
        if (!_flyView) {
2141 2142 2143 2144 2145 2146
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
2147 2148 2149
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
2150
        if (simpleItem) {
2151 2152 2153 2154 2155
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
2156 2157 2158
        }
    }
}
2159 2160 2161 2162 2163 2164 2165 2166 2167 2168 2169 2170 2171

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
2172 2173 2174 2175 2176 2177 2178 2179
    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();
    }
2180
}
2181 2182 2183 2184 2185

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

DonLakeFlyer's avatar
DonLakeFlyer committed
2186
    complexItems.append(patternSurveyName);
2187
    complexItems.append(patternCorridorScanName);
2188
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
2189
        complexItems.append(patternStructureScanName);
2190
    }
2191

2192
    return qgcApp()->toolbox()->corePlugin()->complexMissionItemNames(_controllerVehicle, complexItems);
2193
}
2194

2195 2196
void MissionController::resumeMission(int resumeIndex)
{
2197
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
2198 2199
        resumeIndex--;
    }
2200
    _missionManager->generateResumeMission(resumeIndex);
2201
}
2202 2203 2204 2205 2206 2207 2208 2209 2210

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
2211 2212 2213 2214 2215 2216 2217 2218 2219 2220

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

2222 2223 2224 2225 2226 2227 2228
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
2229 2230 2231 2232 2233 2234

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
2235 2236 2237

bool MissionController::showPlanFromManagerVehicle (void)
{
2238
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
DonLakeFlyer's avatar
DonLakeFlyer committed
2239 2240
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
2241
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
2242 2243 2244 2245 2246 2247 2248 2249 2250 2251 2252 2253 2254 2255 2256 2257 2258 2259 2260
    } 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;
        }
    }
}

2261
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2262
{
2263
    // Fly view always reloads on send complete
2264
    if (!error && _flyView) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2265 2266 2267 2268
        showPlanFromManagerVehicle();
    }
}

2269
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2270
{
2271 2272 2273 2274
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2275
}
2276

2277 2278 2279 2280 2281 2282 2283 2284 2285 2286 2287 2288 2289 2290 2291
bool MissionController::_isROIBeginItem(SimpleMissionItem* simpleItem)
{
    return simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI_LOCATION ||
            simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET ||
            (simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI &&
             static_cast<int>(simpleItem->missionItem().param1()) == MAV_ROI_LOCATION);
}

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

2292
void MissionController::setCurrentPlanViewSeqNum(int sequenceNumber, bool force)
2293
{
2294
    if (_visualItems && (force || sequenceNumber != _currentPlanViewSeqNum)) {
2295 2296 2297 2298
        bool    foundLand =             false;
        int     takeoffSeqNum =         -1;
        int     landSeqNum =            -1;
        int     lastFlyThroughSeqNum =  -1;
2299

2300 2301
        _splitSegment =                 nullptr;
        _currentPlanViewItem  =         nullptr;
2302 2303
        _currentPlanViewSeqNum =        -1;
        _currentPlanViewVIIndex =       -1;
2304 2305
        _isInsertTakeoffValid =         true;
        _isInsertLandValid =            true;
2306
        _isROIActive =                  false;
2307
        _isROIBeginCurrentItem =        false;
2308
        _flyThroughCommandsAllowed =    true;
2309
        _previousCoordinate =           QGeoCoordinate();
2310

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

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

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

2328 2329 2330 2331 2332 2333 2334 2335
            if (!foundLand) {
                if (simpleItem) {
                    switch (simpleItem->mavCommand()) {
                    case MAV_CMD_NAV_LAND:
                    case MAV_CMD_NAV_VTOL_LAND:
                    case MAV_CMD_DO_LAND_START:
                    case MAV_CMD_NAV_RETURN_TO_LAUNCH:
                        foundLand = true;
2336
                        landSeqNum = currentSeqNumber;
2337 2338 2339 2340 2341 2342 2343 2344
                        break;
                    default:
                        break;
                    }
                } else {
                    FixedWingLandingComplexItem* fwLanding = qobject_cast<FixedWingLandingComplexItem*>(pVI);
                    if (fwLanding) {
                        foundLand = true;
2345
                        landSeqNum = currentSeqNumber;
2346 2347 2348 2349 2350
                    }
                }
            }

            if (simpleItem) {
2351
                // Remember previous coordinate
2352
                if (currentSeqNumber < sequenceNumber && simpleItem->specifiesCoordinate() && !simpleItem->isStandaloneCoordinate()) {
2353 2354 2355 2356
                    _previousCoordinate = simpleItem->coordinate();
                }

                // ROI state handling
2357
                if (currentSeqNumber <= sequenceNumber) {
2358
                    if (_isROIActive) {
2359
                        if (_isROICancelItem(simpleItem)) {
2360 2361 2362
                            _isROIActive = false;
                        }
                    } else {
2363
                        if (_isROIBeginItem(simpleItem)) {
2364 2365
                            _isROIActive = true;
                        }
2366 2367
                    }
                }
2368
                if (currentSeqNumber == sequenceNumber && _isROIBeginItem(simpleItem)) {
2369 2370
                    _isROIBeginCurrentItem = true;
                }
2371 2372 2373 2374

                if (simpleItem->specifiesCoordinate() && !simpleItem->isStandaloneCoordinate()) {
                    lastFlyThroughSeqNum = currentSeqNumber;
                }
2375 2376
            }

2377 2378

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

2382
                _currentPlanViewItem  = pVI;
2383 2384
                _currentPlanViewSeqNum = sequenceNumber;
                _currentPlanViewVIIndex = viIndex;
2385

2386 2387 2388 2389 2390 2391 2392 2393 2394 2395
                if (pVI->specifiesCoordinate()) {
                    if (!pVI->isStandaloneCoordinate()) {
                        // Determine split segment used to display line split editing ui.
                        for (int j=viIndex-1; j>0; j--) {
                            VisualMissionItem* pPrev = qobject_cast<VisualMissionItem*>(_visualItems->get(j));
                            if (pPrev->specifiesCoordinate() && !pPrev->isStandaloneCoordinate()) {
                                VisualItemPair splitPair(pPrev, pVI);
                                if (_linesTable.contains(splitPair)) {
                                    _splitSegment = _linesTable[splitPair];
                                }
2396 2397 2398
                            }
                        }
                    }
2399 2400
                } else if (pVI->parentItem()) {
                    pVI->parentItem()->setHasCurrentChildItem(true);
2401
                }
2402 2403 2404 2405
            } else {
                pVI->setIsCurrentItem(false);
            }
        }
2406

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

2417 2418 2419 2420 2421 2422 2423
        if (lastFlyThroughSeqNum != -1) {
            // Land item must be after any fly through coordinates
            if (sequenceNumber < lastFlyThroughSeqNum) {
                _isInsertLandValid = false;
            }
        }

2424 2425
        if (foundLand) {
            // Can't have more than one land sequence
2426
            _isInsertLandValid = false;
2427
            if (sequenceNumber >= landSeqNum) {
2428 2429 2430
                // Can't have fly through commands after a land item
                _flyThroughCommandsAllowed = false;
            }
2431 2432
        }

2433 2434
        emit currentPlanViewSeqNumChanged();
        emit currentPlanViewVIIndexChanged();
2435
        emit currentPlanViewItemChanged();
2436
        emit splitSegmentChanged();
2437
        emit isInsertTakeoffValidChanged();
2438
        emit isInsertLandValidChanged();
2439
        emit isROIActiveChanged();
2440
        emit isROIBeginCurrentItemChanged();
2441
        emit flyThroughCommandsAllowedChanged();
2442
        emit previousCoordinateChanged();
2443 2444
    }
}
2445 2446 2447

void MissionController::_updateTimeout()
{
Gus Grubba's avatar
Gus Grubba committed
2448
    QGeoCoordinate firstCoordinate;
2449
    QGeoCoordinate takeoffCoordinate;
2450
    QGCGeoBoundingCube boundingCube;
2451 2452 2453 2454
    double north = 0.0;
    double south = 180.0;
    double east  = 0.0;
    double west  = 360.0;
2455 2456
    double minAlt = QGCGeoBoundingCube::MaxAlt;
    double maxAlt = QGCGeoBoundingCube::MinAlt;
2457 2458 2459 2460 2461 2462
    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()) {
2463
                case MAV_CMD_NAV_TAKEOFF:
2464 2465
                case MAV_CMD_NAV_WAYPOINT:
                case MAV_CMD_NAV_LAND:
2466 2467 2468 2469 2470 2471 2472 2473 2474 2475 2476 2477 2478 2479 2480
                    if(pSimpleItem->coordinate().isValid()) {
                        if((MAV_CMD)pSimpleItem->command() == MAV_CMD_NAV_TAKEOFF) {
                            takeoffCoordinate = pSimpleItem->coordinate();
                        } else if(!firstCoordinate.isValid()) {
                            firstCoordinate = pSimpleItem->coordinate();
                        }
                        double lat = pSimpleItem->coordinate().latitude()  + 90.0;
                        double lon = pSimpleItem->coordinate().longitude() + 180.0;
                        double alt = pSimpleItem->coordinate().altitude();
                        north  = fmax(north, lat);
                        south  = fmin(south, lat);
                        east   = fmax(east,  lon);
                        west   = fmin(west,  lon);
                        minAlt = fmin(minAlt, alt);
                        maxAlt = fmax(maxAlt, alt);
Gus Grubba's avatar
Gus Grubba committed
2481
                    }
2482
                    break;
2483 2484 2485 2486 2487 2488 2489
                default:
                    break;
                }
            }
        } else {
            ComplexMissionItem* pComplexItem = qobject_cast<ComplexMissionItem*>(item);
            if(pComplexItem) {
2490 2491
                QGCGeoBoundingCube bc = pComplexItem->boundingCube();
                if(bc.isValid()) {
Gus Grubba's avatar
Gus Grubba committed
2492 2493 2494
                    if(!firstCoordinate.isValid() && pComplexItem->coordinate().isValid()) {
                        firstCoordinate = pComplexItem->coordinate();
                    }
2495 2496 2497 2498 2499 2500
                    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());
2501 2502 2503 2504
                }
            }
        }
    }
Gus Grubba's avatar
Gus Grubba committed
2505 2506 2507 2508 2509 2510 2511 2512 2513
    //-- Figure out where this thing is taking off from
    if(!takeoffCoordinate.isValid()) {
        if(firstCoordinate.isValid()) {
            takeoffCoordinate = firstCoordinate;
        } else {
            takeoffCoordinate = plannedHomePosition();
        }
    }
    //-- Build bounding "cube"
2514
    boundingCube = QGCGeoBoundingCube(
2515 2516
                QGeoCoordinate(north - 90.0, west - 180.0, minAlt),
                QGeoCoordinate(south - 90.0, east - 180.0, maxAlt));
2517 2518
    if(_travelBoundingCube != boundingCube || _takeoffCoordinate != takeoffCoordinate) {
        _takeoffCoordinate  = takeoffCoordinate;
2519
        _travelBoundingCube = boundingCube;
2520
        emit missionBoundingCubeChanged();
2521
        qCDebug(MissionControllerLog) << "Bounding cube:" << _travelBoundingCube.pointNW << _travelBoundingCube.pointSE;
2522 2523 2524 2525 2526 2527 2528
    }
}

void MissionController::_complexBoundingBoxChanged()
{
    _updateTimer.start(UPDATE_TIMEOUT);
}
2529 2530 2531 2532 2533

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