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


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

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

36 37
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

DonLakeFlyer's avatar
DonLakeFlyer committed
54 55 56 57
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"));
58

59
MissionController::MissionController(PlanMasterController* masterController, QObject *parent)
60 61 62 63 64 65 66 67 68 69 70 71
    : 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)
    , _currentPlanViewIndex     (-1)
    , _currentPlanViewItem      (nullptr)
72
    , _splitSegment             (nullptr)
73
{
74
    _resetMissionFlightStatus();
75
    managerVehicleChanged(_managerVehicle);
76 77
    _updateTimer.setSingleShot(true);
    connect(&_updateTimer, &QTimer::timeout, this, &MissionController::_updateTimeout);
78 79 80 81
}

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

83 84
}

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

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

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

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

128 129
}

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

134
    PlanElementController::start(flyView);
135 136 137 138 139
    _init();
}

void MissionController::_init(void)
{
140
    // We start with an empty mission
141
    _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
142
    _addMissionSettings(_visualItems, false /* addToCenter */);
143
    _initAllVisualItems();
144 145
}

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

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

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

167 168 169
        _missionItemCount = newMissionItems.count();
        emit missionItemCountChanged(_missionItemCount);

170
        int i = 0;
171
        if (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() && newMissionItems.count() != 0) {
172
            // First item is fake home position
DonLakeFlyer's avatar
DonLakeFlyer committed
173
            _addMissionSettings(newControllerMissionItems, false /* addToCenter */);
174
            MissionSettingsItem* settingsItem = newControllerMissionItems->value<MissionSettingsItem*>(0);
175 176 177 178
            if (!settingsItem) {
                qWarning() << "First item is not settings item";
                return;
            }
179 180 181 182
            MissionItem* fakeHomeItem = newMissionItems[0];
            if (fakeHomeItem->coordinate().latitude() != 0 || fakeHomeItem->coordinate().longitude() != 0) {
                settingsItem->setCoordinate(fakeHomeItem->coordinate());
            }
183 184
            i = 1;
        }
185

186
        for (; i < newMissionItems.count(); i++) {
187
            const MissionItem* missionItem = newMissionItems[i];
188
            newControllerMissionItems->append(new SimpleMissionItem(_controllerVehicle, _flyView, *missionItem, this));
189 190 191
        }

        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
192
        _visualItems->deleteLater();
193 194
        _settingsItem = nullptr;
        _visualItems  = nullptr;
195
        _updateContainsItems(); // This will clear containsItems which will be set again below. This will re-pop Start Mission confirmation.
196 197
        _visualItems = newControllerMissionItems;

198
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
199
            _addMissionSettings(_visualItems, !_flyView && _visualItems->count() > 0 /* addToCenter */);
200 201
        }

202
        MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
203

204
        _initAllVisualItems();
205
        _updateContainsItems();
206
        emit newItemsFromVehicle();
207
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
208
    _itemsRequested = false;
209 210
}

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

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

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

254 255 256 257 258
/// 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
259 260 261 262
    if (visualMissionItems->count() == 0) {
        return false;
    }

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

    return endActionSet;
}

287 288
void MissionController::convertToKMLDocument(QDomDocument& document)
{
289 290
    QObject*            deleteParent = new QObject();
    QList<MissionItem*> rgMissionItems;
291

292 293
    _convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
    if (rgMissionItems.count() == 0) {
294 295
        return;
    }
296

297
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
298 299 300 301 302

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

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

    deleteParent->deleteLater();

324 325 326 327 328
    Kml kml;
    kml.points(coords);
    kml.save(document);
}

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

334
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
335

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

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

352
VisualMissionItem* MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem)
353
{
354
    int sequenceNumber = _nextSequenceNumber();
355
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
356
    newItem->setSequenceNumber(sequenceNumber);
357
    newItem->setCoordinate(coordinate);
358
    newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
359
    _initVisualItem(newItem);
360
    if (_visualItems->count() == 1 && (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() || _controllerVehicle->multiRotor())) {
361
        MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
362
        if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) {
363 364
            newItem->setCommand(takeoffCmd);
        }
365
    }
366 367 368
    if (newItem->specifiesAltitude()) {
        double  prevAltitude;
        int     prevAltitudeMode;
369

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

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

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

    return newItem;
390 391
}

392
VisualMissionItem* MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem)
393 394
{
    int sequenceNumber = _nextSequenceNumber();
395
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
396
    newItem->setSequenceNumber(sequenceNumber);
397
    newItem->setCommand((_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_DO_SET_ROI_LOCATION) ?
398 399
        MAV_CMD_DO_SET_ROI_LOCATION :
        MAV_CMD_DO_SET_ROI));
400
    _initVisualItem(newItem);
401
    newItem->setCoordinate(coordinate);
402

403 404
    double  prevAltitude;
    int     prevAltitudeMode;
405

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

    _recalcAll();

418 419 420 421 422
    if (makeCurrentItem) {
        setCurrentPlanViewIndex(newItem->sequenceNumber(), true);
    }

    return newItem;
423 424
}

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

429 430
    // If the ComplexMissionItem is inserted first, add a TakeOff SimpleMissionItem
    if (_visualItems->count() == 1 && (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() || _controllerVehicle->multiRotor())) {
431 432
        insertSimpleMissionItem(mapCenterCoordinate, visualItemIndex);
        visualItemIndex++;
433 434
    }

DonLakeFlyer's avatar
DonLakeFlyer committed
435
    if (itemName == patternSurveyName) {
436
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
437
        newItem->setCoordinate(mapCenterCoordinate);
438
    } else if (itemName == patternFWLandingName) {
439
        newItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, _visualItems /* parent */);
440
    } else if (itemName == patternStructureScanName) {
441
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
442
    } else if (itemName == patternCorridorScanName) {
443
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
444 445
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
446
        return nullptr;
447 448
    }

449 450 451
    _insertComplexMissionItemWorker(newItem, visualItemIndex, makeCurrentItem);

    return newItem;
452 453
}

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

DonLakeFlyer's avatar
DonLakeFlyer committed
458
    if (itemName == patternSurveyName) {
459
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
460
    } else if (itemName == patternStructureScanName) {
461
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
462
    } else if (itemName == patternCorridorScanName) {
463
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
464 465
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
466
        return nullptr;
467 468
    }

469 470 471
    _insertComplexMissionItemWorker(newItem, visualItemIndex, makeCurrentItem);

    return newItem;
472 473
}

474
void MissionController::_insertComplexMissionItemWorker(ComplexMissionItem* complexItem, int visualItemIndex, bool makeCurrentItem)
475 476
{
    int sequenceNumber = _nextSequenceNumber();
477 478 479
    bool surveyStyleItem = qobject_cast<SurveyComplexItem*>(complexItem) ||
                            qobject_cast<CorridorScanComplexItem*>(complexItem) ||
                            qobject_cast<StructureScanComplexItem*>(complexItem);
480

481
    if (surveyStyleItem) {
482
        bool rollSupported  = false;
483
        bool pitchSupported = false;
484
        bool yawSupported   = false;
485 486 487

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

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

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

497
        // Point gimbal straight down
498
        if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
499 500 501
            // If the user already specified a gimbal angle leave it alone
            if (!cameraSection->specifyGimbal()) {
                cameraSection->setSpecifyGimbal(true);
502
                cameraSection->gimbalPitch()->setRawValue(-90.0);
503 504
            }
        }
505
    }
506

507 508
    complexItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(complexItem);
509

Don Gagne's avatar
Don Gagne committed
510
    if (visualItemIndex == -1) {
511 512
        _visualItems->append(complexItem);
    } else {
Don Gagne's avatar
Don Gagne committed
513
        _visualItems->insert(visualItemIndex, complexItem);
514
    }
515

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

522 523 524
    if (makeCurrentItem) {
        setCurrentPlanViewIndex(complexItem->sequenceNumber(), true);
    }
525 526
}

527 528
void MissionController::removeMissionItem(int index)
{
529 530 531 532 533
    if (index <= 0 || index >= _visualItems->count()) {
        qWarning() << "MissionController::removeMissionItem called with bad index - count:index" << _visualItems->count() << index;
        return;
    }

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

537
    _deinitVisualItem(item);
538
    item->deleteLater();
539

540 541
    if (removeSurveyStyle) {
        // Determine if the mission still has another survey style item in it
542 543
        bool foundSurvey = false;
        for (int i=1; i<_visualItems->count(); i++) {
544
            if (_visualItems->value<SurveyComplexItem*>(i) || _visualItems->value<CorridorScanComplexItem*>(i)) {
545 546 547 548 549
                foundSurvey = true;
                break;
            }
        }

550
        // If there is no longer a survey item in the mission remove added commands
551 552 553 554
        if (!foundSurvey) {
            bool rollSupported = false;
            bool pitchSupported = false;
            bool yawSupported = false;
555 556
            MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
            CameraSection* cameraSection = settingsItem->cameraSection();
557
            if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
558
                if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
559 560 561
                    cameraSection->setSpecifyGimbal(false);
                }
            }
562
            if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
563 564
                cameraSection->setSpecifyCameraMode(false);
            }
565 566 567
        }
    }

568
    _recalcAll();
569
    setDirty(true);
570 571
}

572
void MissionController::removeAll(void)
573
{
574 575
    if (_visualItems) {
        _deinitAllVisualItems();
DonLakeFlyer's avatar
DonLakeFlyer committed
576
        _visualItems->clearAndDeleteContents();
Don Gagne's avatar
Don Gagne committed
577
        _visualItems->deleteLater();
578
        _settingsItem = nullptr;
579
        _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
580
        _addMissionSettings(_visualItems, false /* addToCenter */);
581
        _initAllVisualItems();
582
        setDirty(true);
583
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
584 585 586
    }
}

587
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
588 589 590 591 592 593 594 595 596
{
    // 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)) {
597 598 599
        return false;
    }

600
    // Read complex items
601
    QList<SurveyComplexItem*> surveyItems;
602 603 604 605
    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];
606

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

612
        SurveyComplexItem* item = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems /* parent */);
Don Gagne's avatar
Don Gagne committed
613 614
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
615
            surveyItems.append(item);
616 617
        } else {
            return false;
618
        }
619
    }
620

621 622 623 624 625
    // 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
626
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
627

628
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
629 630 631 632
    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
633
        if (nextComplexItemIndex < surveyItems.count()) {
634
            SurveyComplexItem* complexItem = surveyItems[nextComplexItemIndex];
635 636 637 638 639 640 641 642 643 644 645 646 647 648

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

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

Don Gagne's avatar
Don Gagne committed
654
            const QJsonObject itemObject = itemValue.toObject();
655
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
Don Gagne's avatar
Don Gagne committed
656
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
657
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
658
                nextSequenceNumber = item->lastSequenceNumber() + 1;
659
                visualItems->append(item);
660 661 662 663
            } else {
                return false;
            }
        }
664
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
665 666

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

Don Gagne's avatar
Don Gagne committed
669
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
670
            MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
671 672 673
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
674 675 676 677
        } else {
            return false;
        }
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
678
        _addMissionSettings(visualItems, true /* addToCenter */);
679 680 681 682 683
    }

    return true;
}

684
bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
685 686 687 688 689 690
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
691
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
692 693
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
694 695 696 697 698 699 700
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

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

704 705
    if (_masterController->offline()) {
        // We only update if offline since if we are online we use the online vehicle settings
706
        appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType(static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt())));
707
        if (json.contains(_jsonVehicleTypeKey)) {
708
            appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType(static_cast<MAV_TYPE>(json[_jsonVehicleTypeKey].toInt())));
709
        }
710
    }
711
    if (json.contains(_jsonCruiseSpeedKey)) {
712
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
713 714
    }
    if (json.contains(_jsonHoverSpeedKey)) {
715
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
716 717
    }

718 719 720 721
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
722
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
723 724
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750
    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) {
751
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
752
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
753
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
754
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
755 756 757 758 759 760 761 762 763 764 765 766 767
                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();

768
            if (complexItemType == SurveyComplexItem::jsonComplexItemTypeValue) {
Don Gagne's avatar
Don Gagne committed
769
                qCDebug(MissionControllerLog) << "Loading Survey: nextSequenceNumber" << nextSequenceNumber;
770
                SurveyComplexItem* surveyItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
Don Gagne's avatar
Don Gagne committed
771 772 773 774 775 776
                if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(surveyItem);
777
            } else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
778
                qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
779
                FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
780 781 782 783 784 785
                if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(landingItem);
786 787
            } else if (complexItemType == StructureScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Structure Scan: nextSequenceNumber" << nextSequenceNumber;
788
                StructureScanComplexItem* structureItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
789 790 791 792 793 794
                if (!structureItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = structureItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Structure Scan load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(structureItem);
795 796
            } else if (complexItemType == CorridorScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Corridor Scan: nextSequenceNumber" << nextSequenceNumber;
797
                CorridorScanComplexItem* corridorItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
798 799 800 801 802 803
                if (!corridorItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = corridorItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Corridor Scan load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(corridorItem);
804
            } else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
805
                qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
806
                MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
807 808 809 810 811 812
                if (!settingsItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = settingsItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Mission Settings load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(settingsItem);
Don Gagne's avatar
Don Gagne committed
813 814 815 816 817 818 819 820 821 822 823 824 825
            } 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);
826
            if (doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
827
                bool found = false;
828
                int findDoJumpId = static_cast<int>(doJumpItem->missionItem().param1());
Don Gagne's avatar
Don Gagne committed
829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849
                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;
}

850 851 852 853 854 855 856 857
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;
858 859 860 861 862 863
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
864 865

    if (fileVersion == 1) {
866
        return _loadJsonMissionFileV1(json, visualItems, errorString);
867
    } else {
868
        return _loadJsonMissionFileV2(json, visualItems, errorString);
869 870 871
    }
}

872
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
873
{
874 875
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
876 877 878 879 880 881 882 883 884

    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;
885
            plannedHomePositionInFile = true;
886 887 888
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
889
            plannedHomePositionInFile = false;
890 891 892 893
        }
    }

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

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

            if (item->load(stream)) {
902 903 904 905 906 907
                if (firstItem && plannedHomePositionInFile) {
                    settingsItem->setCoordinate(item->coordinate());
                } else {
                    visualItems->append(item);
                }
                firstItem = false;
908
            } else {
909
                errorString = tr("The mission file is corrupted.");
910 911 912 913
                return false;
            }
        }
    } else {
914
        errorString = tr("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
915 916 917
        return false;
    }

918
    if (!plannedHomePositionInFile) {
919 920 921
        // 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));
922
            if (item && item->command() == MAV_CMD_DO_JUMP) {
923
                item->missionItem().setParam1(static_cast<int>(item->missionItem().param1()) + 1);
Don Gagne's avatar
Don Gagne committed
924 925
            }
        }
926 927 928
    }

    return true;
929 930
}

931
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
932
{
Don Gagne's avatar
Don Gagne committed
933 934 935
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
936
        _settingsItem = nullptr;
Don Gagne's avatar
Don Gagne committed
937 938
    }

939
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
940 941

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

945
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
946

Don Gagne's avatar
Don Gagne committed
947
    _initAllVisualItems();
948
}
949

950 951 952 953 954 955
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

956
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981
        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;
982
    }
983

984 985 986 987 988 989 990 991 992 993 994 995 996
    _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);
997
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
998 999 1000 1001 1002 1003
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
1004
    return true;
1005 1006
}

1007
int MissionController::readyForSaveState(void) const
1008 1009 1010
{
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
DonLakeFlyer's avatar
DonLakeFlyer committed
1011
        if (visualItem->readyForSaveState() != VisualMissionItem::ReadyForSave) {
1012
            return visualItem->readyForSaveState();
1013 1014 1015
        }
    }

1016
    return VisualMissionItem::ReadyForSave;
1017 1018
}

1019
void MissionController::save(QJsonObject& json)
1020
{
1021
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
1022

1023
    // Mission settings
1024

1025 1026 1027 1028 1029 1030 1031
    MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsItem";
        return;
    }
    QJsonValue coordinateValue;
    JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
1032 1033 1034 1035 1036
    json[_jsonPlannedHomePositionKey]   = coordinateValue;
    json[_jsonFirmwareTypeKey]          = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey]           = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey]           = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey]            = _controllerVehicle->defaultHoverSpeed();
1037

1038
    // Save the visual items
1039

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

1044 1045
        visualItem->save(rgJsonMissionItems);
    }
1046

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

1051 1052 1053 1054 1055
        if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
1056
        }
1057 1058
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
1059 1060 1061
        }
    }

1062
    json[_jsonItemsKey] = rgJsonMissionItems;
1063 1064
}

1065
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
1066
{
Don Gagne's avatar
Don Gagne committed
1067
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
1068
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
1069 1070 1071 1072
    bool            distanceOk =    false;

    // Convert to fixed altitudes

1073
    distanceOk = true;
1074
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
1075 1076
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
1077
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
1078
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
1079 1080 1081
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
1082 1083 1084
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
1085
    } else {
Don Gagne's avatar
Don Gagne committed
1086
        *altDifference = 0.0;
1087
        *azimuth = 0.0;
1088
        *distance = 0.0;
1089 1090 1091
    }
}

1092
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
1093 1094 1095 1096 1097 1098 1099
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

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

1103
CoordinateVector* MissionController::_addWaypointLineSegment(CoordVectHashTable& prevItemPairHashTable, VisualItemPair& pair)
1104
{
1105 1106
    CoordinateVector* coordVector = nullptr;

1107 1108
    if (prevItemPairHashTable.contains(pair)) {
        // Pair already exists and connected, just re-use
1109
        _linesTable[pair] = coordVector = prevItemPairHashTable.take(pair);
1110 1111
    } else {
        // Create a new segment and wire update notifiers
1112
        coordVector         = new CoordinateVector(pair.first->isSimpleItem() ? pair.first->coordinate() : pair.first->exitCoordinate(), pair.second->coordinate(), this);
1113 1114 1115 1116
        auto originNotifier = pair.first->isSimpleItem() ? &VisualMissionItem::coordinateChanged : &VisualMissionItem::exitCoordinateChanged;
        auto endNotifier    = &VisualMissionItem::coordinateChanged;

        // Use signals/slots to update the coordinate endpoints
1117 1118
        connect(pair.first,     originNotifier, coordVector, &CoordinateVector::setCoordinate1);
        connect(pair.second,    endNotifier,    coordVector, &CoordinateVector::setCoordinate2);
1119 1120 1121 1122

        // 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);
1123
        _linesTable[pair] = coordVector;
1124
    }
1125 1126

    return coordVector;
1127 1128
}

1129 1130
void MissionController::_recalcWaypointLines(void)
{
1131
    int                 segmentCount = 0;
1132
    VisualItemPair      lastSegmentVisualItemPair;
1133 1134 1135
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

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

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

Nate Weibley's avatar
Nate Weibley committed
1140
    CoordVectHashTable old_table = _linesTable;
1141

Nate Weibley's avatar
Nate Weibley committed
1142
    _linesTable.clear();
1143
    _waypointPath.clear();
1144 1145 1146 1147 1148

    _waypointLines.beginReset();
    _directionArrows.beginReset();

    _waypointLines.clear();
1149
    _directionArrows.clear();
1150

1151 1152 1153 1154 1155 1156 1157 1158 1159
    bool linkEndToHome;
    SimpleMissionItem* lastItem = _visualItems->value<SimpleMissionItem*>(_visualItems->count() - 1);
    if (lastItem && (int)lastItem->command() == MAV_CMD_NAV_RETURN_TO_LAUNCH) {
        linkEndToHome = true;
    } else {
        linkEndToHome = _settingsItem->missionEndRTL();
    }

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

1163 1164 1165 1166 1167 1168
        // If we still haven't found the first coordinate item and we hit a takeoff command this means the mission starts from the ground.
        // Link the first item back to home to show that.
        if (firstCoordinateItem && item->isSimpleItem()) {
            MAV_CMD command = (MAV_CMD)qobject_cast<SimpleMissionItem*>(item)->command();
            if (command == MAV_CMD_NAV_TAKEOFF || command == MAV_CMD_NAV_VTOL_TAKEOFF) {
                linkStartToHome = true;
1169
            }
1170 1171
        }

1172 1173
        if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
            if (lastCoordinateItem != _settingsItem || (homePositionValid && linkStartToHome)) {
1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185
                // Direction arrows are added to the first segment and every 5 segments in the middle.
                bool addDirectionArrow = false;
                if (firstCoordinateItem || !lastCoordinateItem->isSimpleItem() || !item->isSimpleItem()) {
                    addDirectionArrow = true;
                } else if (segmentCount > 5) {
                    segmentCount = 0;
                    addDirectionArrow = true;
                }
                segmentCount++;

                lastSegmentVisualItemPair =  VisualItemPair(lastCoordinateItem, item);
                if (!_flyView || addDirectionArrow) {
1186 1187 1188 1189
                    CoordinateVector* coordVector = _addWaypointLineSegment(old_table, lastSegmentVisualItemPair);
                    if (addDirectionArrow) {
                        _directionArrows.append(coordVector);
                    }
1190
                }
1191
            }
1192
            firstCoordinateItem = false;
1193 1194
            _waypointPath.append(QVariant::fromValue(item->coordinate()));
            lastCoordinateItem = item;
1195 1196
        }
    }
1197 1198 1199 1200 1201 1202

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

    if (linkEndToHome && lastCoordinateItem != _settingsItem && homePositionValid) {
1203 1204
        lastSegmentVisualItemPair =  VisualItemPair(lastCoordinateItem, _settingsItem);
        if (_flyView) {
1205 1206
            _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
        }
1207
        _addWaypointLineSegment(old_table, lastSegmentVisualItemPair);
1208
    }
1209

1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232
    // 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
             coordVector = _linesTable[lastSegmentVisualItemPair];
        } 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) {
1233 1234
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1235
        objs.reserve(_linesTable.count());
1236
        for(CoordinateVector *vect: _linesTable.values()) {
1237 1238 1239 1240 1241 1242 1243
            objs.append(vect);
        }

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

1244 1245 1246
    _waypointLines.endReset();
    _directionArrows.endReset();

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1250
    _recalcMissionFlightStatus();
1251

1252
    if (_waypointPath.count() == 0) {
1253
        // MapPolyLine has a bug where if you change from a path which has elements to an empty path the line drawn
1254 1255 1256 1257 1258 1259 1260
        // 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();
1261 1262
}

1263 1264 1265 1266 1267 1268
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);
1269 1270 1271
        // 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.
1272
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295
            _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);
}

1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322
/// 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
1323
void MissionController::_recalcMissionFlightStatus()
1324
{
1325
    if (!_visualItems->count()) {
1326
        return;
1327
    }
1328 1329 1330 1331

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

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1334
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1335

1336 1337 1338
    // 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.
1339

1340
    // No values for first item
1341
    lastCoordinateItem->setAltDifference(0.0);
1342
    lastCoordinateItem->setAzimuth(0.0);
1343
    lastCoordinateItem->setDistance(0.0);
1344

1345 1346
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1347 1348
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1349

1350
    _resetMissionFlightStatus();
1351

DonLakeFlyer's avatar
DonLakeFlyer committed
1352
    bool vtolInHover = true;
1353
    bool linkStartToHome = false;
1354 1355 1356 1357 1358 1359 1360 1361 1362 1363
    bool linkEndToHome = false;

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1365
    for (int i=0; i<_visualItems->count(); i++) {
1366
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1367 1368 1369
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1370 1371
        // Assume the worst
        item->setAzimuth(0.0);
1372
        item->setDistance(0.0);
1373

DonLakeFlyer's avatar
DonLakeFlyer committed
1374 1375 1376
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1377
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1378
                _missionFlightStatus.hoverSpeed = newSpeed;
1379
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1380 1381
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1382
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1383
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1384
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1385 1386
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1387
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1388 1389 1390 1391
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1392 1393 1394 1395 1396 1397 1398
        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
1399 1400 1401 1402 1403
        }

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

1406
        // Link back to home if first item is takeoff and we have home position
1407
        if (firstCoordinateItem && simpleItem && (simpleItem->command() == MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
1408
            if (showHomePosition) {
1409
                linkStartToHome = true;
1410 1411 1412 1413 1414 1415 1416
                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);
                }
1417 1418 1419 1420
            }
        }

        // Update VTOL state
1421
        if (simpleItem && _controllerVehicle->vtol()) {
1422
            switch (simpleItem->command()) {
1423
            case MAV_CMD_NAV_TAKEOFF:
1424 1425
                vtolInHover = false;
                break;
1426
            case MAV_CMD_NAV_VTOL_TAKEOFF:
DonLakeFlyer's avatar
DonLakeFlyer committed
1427 1428
                vtolInHover = true;
                break;
1429
            case MAV_CMD_NAV_LAND:
1430 1431
                vtolInHover = false;
                break;
1432
            case MAV_CMD_NAV_VTOL_LAND:
DonLakeFlyer's avatar
DonLakeFlyer committed
1433 1434
                vtolInHover = true;
                break;
1435
            case MAV_CMD_DO_VTOL_TRANSITION:
1436 1437 1438 1439 1440 1441
            {
                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;
1442 1443
                }
            }
1444 1445 1446
                break;
            default:
                break;
1447
            }
Don Gagne's avatar
Don Gagne committed
1448 1449
        }

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

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

1455
            double absoluteAltitude = item->coordinate().altitude();
1456
            if (item->coordinateHasRelativeAltitude()) {
1457 1458 1459 1460 1461
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1462 1463 1464 1465
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1466 1467 1468
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1469
                firstCoordinateItem = false;
1470 1471 1472 1473 1474 1475 1476

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

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

1481
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1482 1483 1484
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1485

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1488 1489 1490
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1491
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1492
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1493

1494
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1495 1496
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1497
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1498

1499 1500
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1501
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1502
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1503 1504

                item->setMissionFlightStatus(_missionFlightStatus);
1505

1506 1507
                lastCoordinateItem = item;
            }
1508 1509
        }
    }
1510
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1511

1512 1513 1514 1515 1516 1517 1518 1519
    if (linkEndToHome && lastCoordinateItem != _settingsItem) {
        double azimuth, distance, altDifference;
        _calcPrevWaypointValues(homePositionAltitude, lastCoordinateItem, _settingsItem, &azimuth, &distance, &altDifference);

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

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1527 1528 1529 1530 1531 1532 1533
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1534 1535
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1536

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

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1544
            if (item->coordinateHasRelativeAltitude()) {
1545 1546 1547 1548
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1549
                item->setTerrainPercent(qQNaN());
1550
                item->setTerrainCollision(false);
1551 1552
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1553 1554 1555 1556 1557 1558 1559
                double terrainAltitude = item->terrainAltitude();
                if (qIsNaN(terrainAltitude)) {
                    item->setTerrainPercent(qQNaN());
                    item->setTerrainCollision(false);
                } else {
                    item->setTerrainPercent((terrainAltitude - minAltSeen) / altRange);
                    item->setTerrainCollision(absoluteAltitude < terrainAltitude);
1560
                }
1561
            }
1562 1563
        }
    }
1564 1565

    _updateTimer.start(UPDATE_TIMEOUT);
1566 1567
}

1568 1569 1570
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1571 1572 1573 1574 1575
    if (_inRecalcSequence) {
        // Don't let this call recurse due to signalling
        return;
    }

1576 1577
    // Setup ascending sequence numbers for all visual items

1578
    _inRecalcSequence = true;
1579 1580 1581
    int sequenceNumber = 0;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1582 1583
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1584 1585
    }    
    _inRecalcSequence = false;
1586 1587
}

1588 1589 1590
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1591
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1592 1593 1594

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

1595 1596
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1597 1598 1599 1600 1601

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

1608
void MissionController::_setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate)
1609
{
1610 1611
    QGeoCoordinate firstCoordinate;

1612 1613 1614 1615
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1616
    // Set the planned home position to be a delta from first coordinate
1617 1618 1619 1620
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

        if (item->specifiesCoordinate()) {
1621 1622
            firstCoordinate = item->coordinate();
            break;
1623 1624 1625
        }
    }

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

1631 1632 1633 1634 1635 1636 1637 1638 1639
    if (firstCoordinate.isValid()) {
        QGeoCoordinate plannedHomeCoord = firstCoordinate.atDistanceAndAzimuth(30, 0);
        plannedHomeCoord.setAltitude(0);
        _settingsItem->setCoordinate(plannedHomeCoord);
    }
}

/// @param clickCoordinate The location of the user click when inserting a new item
void MissionController::_recalcAllWithClickCoordinate(QGeoCoordinate& clickCoordinate)
1640
{
1641
    if (!_flyView) {
1642
        _setPlannedHomePositionFromFirstCoordinate(clickCoordinate);
1643
    }
1644
    _recalcSequence();
1645 1646
    _recalcChildItems();
    _recalcWaypointLines();
1647
    _updateTimer.start(UPDATE_TIMEOUT);
1648 1649
}

1650 1651 1652 1653 1654 1655
void MissionController::_recalcAll(void)
{
    QGeoCoordinate emptyCoord;
    _recalcAllWithClickCoordinate(emptyCoord);
}

1656
/// Initializes a new set of mission items
1657
void MissionController::_initAllVisualItems(void)
1658
{
1659 1660
    // Setup home position at index 0

1661 1662 1663
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1664 1665
        return;
    }
1666
    if (!_flyView) {
1667 1668
        _settingsItem->setIsCurrentItem(true);
    }
1669

1670
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1671
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1672
    }
1673

1674 1675 1676
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1677

1678 1679 1680 1681
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1682

1683
    _recalcAll();
1684

1685
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1686 1687 1688
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1689
    emit containsItemsChanged(containsItems());
1690
    emit plannedHomePositionChanged(plannedHomePosition());
1691

1692
    setDirty(false);
1693 1694
}

1695
void MissionController::_deinitAllVisualItems(void)
1696
{
1697 1698 1699
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

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

1704
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1705
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1706 1707
}

1708
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1709
{
1710
    setDirty(false);
1711

1712
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1713 1714
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1715 1716
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1717
    connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged,                this, &MissionController::_recalcMissionFlightStatus);
1718
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1719
    connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged,                 this, &MissionController::_recalcMissionFlightStatus);
1720
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1721

1722 1723 1724 1725 1726 1727 1728 1729
    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";
        }
1730 1731
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1732
        if (complexItem) {
1733
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
1734
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
1735 1736 1737
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1738
    }
1739 1740
}

1741
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1742
{
1743
    // Disconnect all signals
1744
    disconnect(visualItem, nullptr, nullptr, nullptr);
1745 1746
}

1747
void MissionController::_itemCommandChanged(void)
1748
{
1749 1750
    _recalcChildItems();
    _recalcWaypointLines();
1751 1752
}

1753
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1754
{
1755 1756 1757
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
1758 1759
        _managerVehicle = nullptr;
        _missionManager = nullptr;
1760
    }
1761

1762 1763
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1764
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1765 1766
        return;
    }
1767

1768 1769
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1770 1771
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1772 1773 1774 1775 1776
    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);
1777
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1778 1779 1780 1781
    connect(_managerVehicle, &Vehicle::homePositionChanged,             this, &MissionController::_managerVehicleHomePositionChanged);
    connect(_managerVehicle, &Vehicle::defaultCruiseSpeedChanged,       this, &MissionController::_recalcMissionFlightStatus);
    connect(_managerVehicle, &Vehicle::defaultHoverSpeedChanged,        this, &MissionController::_recalcMissionFlightStatus);
    connect(_managerVehicle, &Vehicle::vehicleTypeChanged,              this, &MissionController::complexMissionItemNamesChanged);
1782

1783 1784
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1785
    }
1786

1787
    emit complexMissionItemNamesChanged();
1788
    emit resumeMissionIndexChanged();
1789 1790
}

1791
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1792
{
1793
    if (_visualItems) {
1794 1795
        bool currentDirtyBit = dirty();

1796
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1797
        if (settingsItem) {
1798
            settingsItem->setHomePositionFromVehicle(homePosition);
1799
        } else {
1800
            qWarning() << "First item is not MissionSettingsItem";
1801
        }
1802 1803 1804 1805 1806 1807

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

void MissionController::_inProgressChanged(bool inProgress)
1812
{
1813
    emit syncInProgressChanged(inProgress);
1814
}
1815

1816
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1817
{
1818 1819
    bool        found = false;
    double      foundAltitude;
1820
    int         foundAltitudeMode;
1821

1822 1823 1824 1825 1826 1827
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1830 1831 1832
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1833 1834 1835
                if (simpleItem->specifiesAltitude()) {
                    foundAltitude = simpleItem->altitude()->rawValue().toDouble();
                    foundAltitudeMode = simpleItem->altitudeMode();
1836
                    found = true;
1837
                    break;
1838 1839
                }
            }
1840 1841 1842
        }
    }

1843
    if (found) {
1844
        *prevAltitude = foundAltitude;
1845
        *prevAltitudeMode = foundAltitudeMode;
1846 1847 1848
    }

    return found;
1849
}
1850 1851 1852 1853 1854 1855 1856 1857 1858 1859 1860 1861 1862

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

1863
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1864
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1865
{
1866
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
1867

Don Gagne's avatar
Don Gagne committed
1868 1869
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1870
    visualItems->insert(0, settingsItem);
1871

1872 1873 1874 1875 1876 1877 1878 1879 1880 1881 1882 1883 1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895 1896
    if (addToCenter) {
        if (visualItems->count() > 1) {
            double north = 0.0;
            double south = 0.0;
            double east  = 0.0;
            double west  = 0.0;
            bool firstCoordSet = false;

            for (int i=1; i<visualItems->count(); i++) {
                VisualMissionItem* item = qobject_cast<VisualMissionItem*>(visualItems->get(i));
                if (item->specifiesCoordinate()) {
                    if (firstCoordSet) {
                        double lat = _normalizeLat(item->coordinate().latitude());
                        double lon = _normalizeLon(item->coordinate().longitude());
                        north = fmax(north, lat);
                        south = fmin(south, lat);
                        east  = fmax(east, lon);
                        west  = fmin(west, lon);
                    } else {
                        firstCoordSet = true;
                        north = _normalizeLat(item->coordinate().latitude());
                        south = north;
                        east  = _normalizeLon(item->coordinate().longitude());
                        west  = east;
                    }
1897 1898
                }
            }
1899

1900 1901 1902
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1903
        }
Don Gagne's avatar
Don Gagne committed
1904 1905
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1906 1907
    }
}
1908

1909
int MissionController::resumeMissionIndex(void) const
1910
{
1911

1912
    int resumeIndex = 0;
1913

1914
    if (_flyView) {
1915
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1916
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1917 1918
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1919 1920
        } else {
            resumeIndex = 0;
1921 1922 1923 1924 1925
        }
    }

    return resumeIndex;
}
1926

1927 1928
int MissionController::currentMissionIndex(void) const
{
1929
    if (!_flyView) {
1930 1931 1932 1933 1934 1935 1936 1937 1938 1939
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

1940
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1941
{
1942
    if (_flyView) {
1943
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1944 1945 1946
            sequenceNumber++;
        }

1947 1948
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1949 1950
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1951
        emit currentMissionIndexChanged(currentMissionIndex());
1952 1953
    }
}
1954

1955
bool MissionController::syncInProgress(void) const
1956
{
1957
    return _missionManager->inProgress();
1958 1959 1960 1961 1962 1963 1964 1965 1966 1967 1968 1969
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1970
    }
1971
}
1972

1973 1974
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1975 1976
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, vehicle);
1977

1978 1979 1980 1981 1982 1983
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1984
        if (!_flyView) {
1985 1986 1987 1988 1989 1990
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
1991 1992 1993
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1994
        if (simpleItem) {
1995 1996 1997 1998 1999
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
2000 2001 2002
        }
    }
}
2003 2004 2005 2006 2007 2008 2009 2010 2011 2012 2013 2014 2015

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
2016 2017 2018 2019 2020 2021 2022 2023
    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();
    }
2024
}
2025 2026 2027 2028 2029

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

DonLakeFlyer's avatar
DonLakeFlyer committed
2030
    complexItems.append(patternSurveyName);
2031
    complexItems.append(patternCorridorScanName);
2032
    if (_controllerVehicle->fixedWing()) {
2033
        complexItems.append(patternFWLandingName);
2034
    }
2035
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
2036
        complexItems.append(patternStructureScanName);
2037
    }
2038

2039
    return qgcApp()->toolbox()->corePlugin()->complexMissionItemNames(_controllerVehicle, complexItems);
2040
}
2041

2042 2043
void MissionController::resumeMission(int resumeIndex)
{
2044
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
2045 2046
        resumeIndex--;
    }
2047
    _missionManager->generateResumeMission(resumeIndex);
2048
}
2049 2050 2051 2052 2053 2054 2055 2056 2057

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
2058 2059 2060 2061 2062 2063 2064 2065 2066 2067

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

2069 2070 2071 2072 2073 2074 2075
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
2076 2077 2078 2079 2080 2081

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
2082 2083 2084

bool MissionController::showPlanFromManagerVehicle (void)
{
2085
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
DonLakeFlyer's avatar
DonLakeFlyer committed
2086 2087
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
2088
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
2089 2090 2091 2092 2093 2094 2095 2096 2097 2098 2099 2100 2101 2102 2103 2104 2105 2106 2107
    } 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;
        }
    }
}

2108
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2109
{
2110
    // Fly view always reloads on send complete
2111
    if (!error && _flyView) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2112 2113 2114 2115
        showPlanFromManagerVehicle();
    }
}

2116
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2117
{
2118 2119 2120 2121
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2122
}
2123 2124 2125 2126 2127 2128 2129 2130 2131 2132 2133 2134 2135 2136

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

VisualMissionItem* MissionController::currentPlanViewItem(void) const
{
    return _currentPlanViewItem;
}

void MissionController::setCurrentPlanViewIndex(int sequenceNumber, bool force)
{
    if(_visualItems && (force || sequenceNumber != _currentPlanViewIndex)) {
2137
        _splitSegment = nullptr;
2138
        _currentPlanViewItem  = nullptr;
2139 2140 2141 2142 2143 2144 2145
        _currentPlanViewIndex = -1;
        for (int i = 0; i < _visualItems->count(); i++) {
            VisualMissionItem* pVI = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
            if (pVI && pVI->sequenceNumber() == sequenceNumber) {
                pVI->setIsCurrentItem(true);
                _currentPlanViewItem  = pVI;
                _currentPlanViewIndex = sequenceNumber;
2146 2147 2148 2149 2150 2151 2152 2153 2154 2155 2156 2157 2158

                if (pVI->specifiesCoordinate() && !pVI->isStandaloneCoordinate()) {
                    // Determine split segment used to display line split editing ui.
                    for (int j=i-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];
                            }
                        }
                    }
                }
2159 2160 2161 2162 2163 2164
            } else {
                pVI->setIsCurrentItem(false);
            }
        }
        emit currentPlanViewIndexChanged();
        emit currentPlanViewItemChanged();
2165
        emit splitSegmentChanged();
2166 2167
    }
}
2168 2169 2170

void MissionController::_updateTimeout()
{
Gus Grubba's avatar
Gus Grubba committed
2171
    QGeoCoordinate firstCoordinate;
2172
    QGeoCoordinate takeoffCoordinate;
2173
    QGCGeoBoundingCube boundingCube;
2174 2175 2176 2177
    double north = 0.0;
    double south = 180.0;
    double east  = 0.0;
    double west  = 360.0;
2178 2179
    double minAlt = QGCGeoBoundingCube::MaxAlt;
    double maxAlt = QGCGeoBoundingCube::MinAlt;
2180 2181 2182 2183 2184 2185
    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()) {
2186
                case MAV_CMD_NAV_TAKEOFF:
2187 2188 2189
                case MAV_CMD_NAV_WAYPOINT:
                case MAV_CMD_NAV_LAND:
                if(pSimpleItem->coordinate().isValid()) {
2190
                    if((MAV_CMD)pSimpleItem->command() == MAV_CMD_NAV_TAKEOFF) {
Gus Grubba's avatar
Gus Grubba committed
2191 2192 2193 2194
                        takeoffCoordinate = pSimpleItem->coordinate();
                    } else if(!firstCoordinate.isValid()) {
                        firstCoordinate = pSimpleItem->coordinate();
                    }
2195 2196
                    double lat = pSimpleItem->coordinate().latitude()  + 90.0;
                    double lon = pSimpleItem->coordinate().longitude() + 180.0;
2197
                    double alt = pSimpleItem->coordinate().altitude();
2198 2199 2200 2201
                    north  = fmax(north, lat);
                    south  = fmin(south, lat);
                    east   = fmax(east,  lon);
                    west   = fmin(west,  lon);
2202 2203
                    minAlt = fmin(minAlt, alt);
                    maxAlt = fmax(maxAlt, alt);
2204 2205 2206 2207 2208 2209 2210 2211 2212
                }
                break;
                default:
                    break;
                }
            }
        } else {
            ComplexMissionItem* pComplexItem = qobject_cast<ComplexMissionItem*>(item);
            if(pComplexItem) {
2213 2214
                QGCGeoBoundingCube bc = pComplexItem->boundingCube();
                if(bc.isValid()) {
Gus Grubba's avatar
Gus Grubba committed
2215 2216 2217
                    if(!firstCoordinate.isValid() && pComplexItem->coordinate().isValid()) {
                        firstCoordinate = pComplexItem->coordinate();
                    }
2218 2219 2220 2221 2222 2223
                    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());
2224 2225 2226 2227
                }
            }
        }
    }
Gus Grubba's avatar
Gus Grubba committed
2228 2229 2230 2231 2232 2233 2234 2235 2236
    //-- Figure out where this thing is taking off from
    if(!takeoffCoordinate.isValid()) {
        if(firstCoordinate.isValid()) {
            takeoffCoordinate = firstCoordinate;
        } else {
            takeoffCoordinate = plannedHomePosition();
        }
    }
    //-- Build bounding "cube"
2237 2238 2239
    boundingCube = QGCGeoBoundingCube(
        QGeoCoordinate(north - 90.0, west - 180.0, minAlt),
        QGeoCoordinate(south - 90.0, east - 180.0, maxAlt));
2240 2241
    if(_travelBoundingCube != boundingCube || _takeoffCoordinate != takeoffCoordinate) {
        _takeoffCoordinate  = takeoffCoordinate;
2242
        _travelBoundingCube = boundingCube;
2243
        emit missionBoundingCubeChanged();
2244
        qCDebug(MissionControllerLog) << "Bounding cube:" << _travelBoundingCube.pointNW << _travelBoundingCube.pointSE;
2245 2246 2247 2248 2249 2250 2251
    }
}

void MissionController::_complexBoundingBoxChanged()
{
    _updateTimer.start(UPDATE_TIMEOUT);
}
2252 2253 2254 2255 2256

bool MissionController::isEmpty(void) const
{
    return _visualItems->count() <= 1;
}
Don Gagne's avatar
Don Gagne committed
2257 2258 2259 2260 2261 2262 2263 2264 2265 2266 2267 2268 2269

int MissionController::visualItemIndexFromSequenceNumber(int sequenceNumber) const
{
    for (int i=0; i<_visualItems->count(); i++) {
        const VisualMissionItem* vi = _visualItems->value<VisualMissionItem*>(i);
        if (vi->sequenceNumber() == sequenceNumber) {
            return i;
        }
    }

    qWarning() << "MissionController::getVisualItemIndex visual item not found";
    return 0;
}