MissionController.cc 83.7 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

33
#ifndef __mobile__
34
#include "MainWindow.h"
35
#include "QGCQFileDialog.h"
36 37
#endif

38 39
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

56
MissionController::MissionController(PlanMasterController* masterController, QObject *parent)
57 58
    : PlanElementController         (masterController, parent)
    , _missionManager               (_managerVehicle->missionManager())
59 60
    , _visualItems                  (nullptr)
    , _settingsItem                 (nullptr)
61 62 63 64 65 66 67 68 69 70
    , _firstItemsFromVehicle        (false)
    , _itemsRequested               (false)
    , _inRecalcSequence             (false)
    , _surveyMissionItemName        (tr("Survey"))
    , _fwLandingMissionItemName     (tr("Fixed Wing Landing"))
    , _structureScanMissionItemName (tr("Structure Scan"))
    , _corridorScanMissionItemName  (tr("Corridor Scan"))
    , _appSettings                  (qgcApp()->toolbox()->settingsManager()->appSettings())
    , _progressPct                  (0)
    , _currentPlanViewIndex         (-1)
71
    , _currentPlanViewItem          (nullptr)
72
{
73
    _resetMissionFlightStatus();
74
    managerVehicleChanged(_managerVehicle);
75 76 77 78
}

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

80 81
}

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

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

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

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

125 126
}

127
void MissionController::start(bool flyView)
128
{
129
    qCDebug(MissionControllerLog) << "start flyView" << flyView;
130

131
    PlanElementController::start(flyView);
132 133 134 135 136
    _init();
}

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

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

DonLakeFlyer's avatar
DonLakeFlyer committed
148 149
    // Fly view always reloads on _loadComplete
    // Plan view only reloads on _loadComplete if specifically requested
150
    if (_flyView || removeAllRequested || _itemsRequested || _visualItems->count() <= 1) {
151
        // Fly Mode (accept if):
Don Gagne's avatar
Don Gagne committed
152
        //      - Always accepts new items from the vehicle so Fly view is kept up to date
153
        // Edit Mode (accept if):
154 155
        //      - 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
156
        //      - The initial automatic load from a vehicle completed and the current editor is empty
157

158
        QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
159
        const QList<MissionItem*>& newMissionItems = _missionManager->missionItems();
160 161 162
        qCDebug(MissionControllerLog) << "loading from vehicle: count"<< newMissionItems.count();

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

178 179
        for (; i<newMissionItems.count(); i++) {
            const MissionItem* missionItem = newMissionItems[i];
180
            newControllerMissionItems->append(new SimpleMissionItem(_controllerVehicle, _flyView, *missionItem, this));
181 182 183
        }

        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
184
        _visualItems->deleteLater();
185 186
        _settingsItem = nullptr;
        _visualItems  = nullptr;
187
        _updateContainsItems(); // This will clear containsItems which will be set again below. This will re-pop Start Mission confirmation.
188 189
        _visualItems = newControllerMissionItems;

190
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
191
            _addMissionSettings(_visualItems, !_flyView && _visualItems->count() > 0 /* addToCenter */);
192 193
        }

194
        MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
195

196
        _initAllVisualItems();
197
        _updateContainsItems();
198
        emit newItemsFromVehicle();
199
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
200
    _itemsRequested = false;
201 202
}

203
void MissionController::loadFromVehicle(void)
204
{
DonLakeFlyer's avatar
DonLakeFlyer committed
205 206 207 208 209 210 211 212
    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();
    }
213 214
}

215 216 217 218 219 220 221 222 223 224 225
void MissionController::_warnIfTerrainFrameUsed(void)
{
    for (int i=1; i<_visualItems->count(); i++) {
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(i));
        if (simpleItem && simpleItem->altitudeMode() == SimpleMissionItem::AltitudeTerrainFrame) {
            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;
        }
    }
}

226
void MissionController::sendToVehicle(void)
227
{
DonLakeFlyer's avatar
DonLakeFlyer committed
228 229 230 231 232
    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
233
        qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
234
        _warnIfTerrainFrameUsed();
DonLakeFlyer's avatar
DonLakeFlyer committed
235 236 237 238 239 240 241 242 243
        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
244 245
}

246 247 248 249 250
/// 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
251 252 253 254
    if (visualMissionItems->count() == 0) {
        return false;
    }

255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270
    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
271
    MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
272 273 274 275 276 277 278
    if (settingsItem) {
        endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
    }

    return endActionSet;
}

279 280
void MissionController::convertToKMLDocument(QDomDocument& document)
{
281 282 283 284 285
    QObject*            deleteParent = new QObject();
    QList<MissionItem*> rgMissionItems;

    _convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
    if (rgMissionItems.count() == 0) {
286 287
        return;
    }
288

289
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
290 291 292 293 294

    QString coord;
    QStringList coords;
    // Drop home position
    bool dropPoint = true;
295
    for(const auto& item : rgMissionItems) {
296 297 298 299 300
        if(dropPoint) {
            dropPoint = false;
            continue;
        }
        const MissionCommandUIInfo* uiInfo = \
301
                qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, item->command());
302 303

        if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
304
            double amslAltitude = item->param7() + (item->frame() == MAV_FRAME_GLOBAL ? 0 : homePositionAltitude);
yaoling's avatar
yaoling committed
305
            coord = QString::number(item->param6(),'f',7) \
306 307 308
                    + "," \
                    + QString::number(item->param5(),'f',7) \
                    + "," \
309
                    + QString::number(amslAltitude,'f',2);
310 311 312
            coords.append(coord);
        }
    }
313 314 315

    deleteParent->deleteLater();

316 317 318 319 320
    Kml kml;
    kml.points(coords);
    kml.save(document);
}

Don Gagne's avatar
Don Gagne committed
321 322 323
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
324
        QList<MissionItem*> rgMissionItems;
325

326
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
327

328
        // PlanManager takes control of MissionItems so no need to delete
329
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
330 331
    }
}
332

333 334 335 336 337 338
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
339 340
        VisualMissionItem* lastItem = _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1);
        return lastItem->lastSequenceNumber() + 1;
341 342 343
    }
}

344
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
345
{
346
    int sequenceNumber = _nextSequenceNumber();
347
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
348
    newItem->setSequenceNumber(sequenceNumber);
349
    newItem->setCoordinate(coordinate);
350
    newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
351
    _initVisualItem(newItem);
352
    if (_visualItems->count() == 1 && (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() || _controllerVehicle->multiRotor())) {
353
        MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
354
        if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) {
355 356
            newItem->setCommand(takeoffCmd);
        }
357
    }
358 359 360
    if (newItem->specifiesAltitude()) {
        double  prevAltitude;
        int     prevAltitudeMode;
361

362 363
        if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
            newItem->altitude()->setRawValue(prevAltitude);
364
            newItem->setAltitudeMode(static_cast<SimpleMissionItem::AltitudeMode>(prevAltitudeMode));
365
        }
366
    }
367
    newItem->setMissionFlightStatus(_missionFlightStatus);
368
    _visualItems->insert(i, newItem);
369 370 371

    _recalcAll();

372
    return newItem->sequenceNumber();
373 374
}

375 376 377
int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
{
    int sequenceNumber = _nextSequenceNumber();
378
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
379
    newItem->setSequenceNumber(sequenceNumber);
380
    newItem->setCommand((_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_DO_SET_ROI_LOCATION) ?
381 382
        MAV_CMD_DO_SET_ROI_LOCATION :
        MAV_CMD_DO_SET_ROI));
383
    _initVisualItem(newItem);
384
    newItem->setCoordinate(coordinate);
385

386 387
    double  prevAltitude;
    int     prevAltitudeMode;
388

389 390
    if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
        newItem->altitude()->setRawValue(prevAltitude);
391
        newItem->setAltitudeMode(static_cast<SimpleMissionItem::AltitudeMode>(prevAltitudeMode));
392 393 394 395 396 397 398 399
    }
    _visualItems->insert(i, newItem);

    _recalcAll();

    return newItem->sequenceNumber();
}

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

404
    int sequenceNumber = _nextSequenceNumber();
405
    if (itemName == _surveyMissionItemName) {
406
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
407
        newItem->setCoordinate(mapCenterCoordinate);
408
    } else if (itemName == _fwLandingMissionItemName) {
409
        newItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, _visualItems /* parent */);
410
    } else if (itemName == _structureScanMissionItemName) {
411
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
412
    } else if (itemName == _corridorScanMissionItemName) {
413
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
414 415 416 417 418
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }

419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444
    return _insertComplexMissionItemWorker(newItem, i);
}

int MissionController::insertComplexMissionItemFromKML(QString itemName, QString kmlFile, int i)
{
    ComplexMissionItem* newItem;

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

    return _insertComplexMissionItemWorker(newItem, i);
}

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

445
    if (surveyStyleItem) {
446 447 448
        bool rollSupported = false;
        bool pitchSupported = false;
        bool yawSupported = false;
449 450 451

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

452 453
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
        CameraSection* cameraSection = settingsItem->cameraSection();
454

455
        // Set camera to photo mode (leave alone if user already specified)
456
        if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
457
            cameraSection->setSpecifyCameraMode(true);
458
            cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
459
        }
460

461
        // Point gimbal straight down
462
        if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
463 464 465
            // If the user already specified a gimbal angle leave it alone
            if (!cameraSection->specifyGimbal()) {
                cameraSection->setSpecifyGimbal(true);
466
                cameraSection->gimbalPitch()->setRawValue(-90.0);
467 468
            }
        }
469
    }
470

471 472
    complexItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(complexItem);
473

474 475 476 477 478
    if (i == -1) {
        _visualItems->append(complexItem);
    } else {
        _visualItems->insert(i, complexItem);
    }
479 480 481

    _recalcAll();

482
    return complexItem->sequenceNumber();
483 484
}

485 486
void MissionController::removeMissionItem(int index)
{
487 488 489 490 491
    if (index <= 0 || index >= _visualItems->count()) {
        qWarning() << "MissionController::removeMissionItem called with bad index - count:index" << _visualItems->count() << index;
        return;
    }

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

495
    _deinitVisualItem(item);
496
    item->deleteLater();
497

498 499
    if (removeSurveyStyle) {
        // Determine if the mission still has another survey style item in it
500 501
        bool foundSurvey = false;
        for (int i=1; i<_visualItems->count(); i++) {
502
            if (_visualItems->value<SurveyComplexItem*>(i) || _visualItems->value<CorridorScanComplexItem*>(i)) {
503 504 505 506 507
                foundSurvey = true;
                break;
            }
        }

508
        // If there is no longer a survey item in the mission remove added commands
509 510 511 512
        if (!foundSurvey) {
            bool rollSupported = false;
            bool pitchSupported = false;
            bool yawSupported = false;
513 514
            MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
            CameraSection* cameraSection = settingsItem->cameraSection();
515
            if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
516
                if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
517 518 519
                    cameraSection->setSpecifyGimbal(false);
                }
            }
520
            if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
521 522
                cameraSection->setSpecifyCameraMode(false);
            }
523 524 525
        }
    }

526
    _recalcAll();
527
    setDirty(true);
528 529
}

530
void MissionController::removeAll(void)
531
{
532 533
    if (_visualItems) {
        _deinitAllVisualItems();
DonLakeFlyer's avatar
DonLakeFlyer committed
534
        _visualItems->clearAndDeleteContents();
Don Gagne's avatar
Don Gagne committed
535
        _visualItems->deleteLater();
536
        _settingsItem = nullptr;
537
        _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
538
        _addMissionSettings(_visualItems, false /* addToCenter */);
539
        _initAllVisualItems();
540
        setDirty(true);
541
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
542 543 544
    }
}

545
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
546 547 548 549 550 551 552 553 554
{
    // 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)) {
555 556 557
        return false;
    }

558
    // Read complex items
559
    QList<SurveyComplexItem*> surveyItems;
560 561 562 563
    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];
564

565 566 567 568 569
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

570
        SurveyComplexItem* item = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems /* parent */);
Don Gagne's avatar
Don Gagne committed
571 572
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
573
            surveyItems.append(item);
574 575
        } else {
            return false;
576
        }
577
    }
578

579 580 581 582 583
    // 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
584
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
585

586
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
587 588 589 590
    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
591
        if (nextComplexItemIndex < surveyItems.count()) {
592
            SurveyComplexItem* complexItem = surveyItems[nextComplexItemIndex];
593 594 595 596 597 598 599 600 601 602 603 604 605 606

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

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

Don Gagne's avatar
Don Gagne committed
612
            const QJsonObject itemObject = itemValue.toObject();
613
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
Don Gagne's avatar
Don Gagne committed
614
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
615
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
616
                nextSequenceNumber = item->lastSequenceNumber() + 1;
617
                visualItems->append(item);
618 619 620 621
            } else {
                return false;
            }
        }
622
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
623 624

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

Don Gagne's avatar
Don Gagne committed
627
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
628
            MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
629 630 631
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
632 633 634 635
        } else {
            return false;
        }
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
636
        _addMissionSettings(visualItems, true /* addToCenter */);
637 638 639 640 641
    }

    return true;
}

642
bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
643 644 645 646 647 648
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
649
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
650 651
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
652 653 654 655 656 657 658
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

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

662 663
    if (_masterController->offline()) {
        // We only update if offline since if we are online we use the online vehicle settings
664
        appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType(static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt())));
665
        if (json.contains(_jsonVehicleTypeKey)) {
666
            appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType(static_cast<MAV_TYPE>(json[_jsonVehicleTypeKey].toInt())));
667
        }
668
    }
669
    if (json.contains(_jsonCruiseSpeedKey)) {
670
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
671 672
    }
    if (json.contains(_jsonHoverSpeedKey)) {
673
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
674 675
    }

676 677 678 679
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
680
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
681 682
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708
    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) {
709
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
710
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
711
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
712
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
713 714 715 716 717 718 719 720 721 722 723 724 725
                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();

726
            if (complexItemType == SurveyComplexItem::jsonComplexItemTypeValue) {
Don Gagne's avatar
Don Gagne committed
727
                qCDebug(MissionControllerLog) << "Loading Survey: nextSequenceNumber" << nextSequenceNumber;
728
                SurveyComplexItem* surveyItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
Don Gagne's avatar
Don Gagne committed
729 730 731 732 733 734
                if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(surveyItem);
735
            } else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
736
                qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
737
                FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
738 739 740 741 742 743
                if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(landingItem);
744 745
            } else if (complexItemType == StructureScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Structure Scan: nextSequenceNumber" << nextSequenceNumber;
746
                StructureScanComplexItem* structureItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
747 748 749 750 751 752
                if (!structureItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = structureItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Structure Scan load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(structureItem);
753 754
            } else if (complexItemType == CorridorScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Corridor Scan: nextSequenceNumber" << nextSequenceNumber;
755
                CorridorScanComplexItem* corridorItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
756 757 758 759 760 761
                if (!corridorItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = corridorItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Corridor Scan load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(corridorItem);
762
            } else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
763
                qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
764
                MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
765 766 767 768 769 770
                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
771 772 773 774 775 776 777 778 779 780 781 782 783
            } 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);
784
            if (doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
785
                bool found = false;
786
                int findDoJumpId = static_cast<int>(doJumpItem->missionItem().param1());
Don Gagne's avatar
Don Gagne committed
787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807
                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;
}

808 809 810 811 812 813 814 815
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;
816 817 818 819 820 821
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
822 823

    if (fileVersion == 1) {
824
        return _loadJsonMissionFileV1(json, visualItems, errorString);
825
    } else {
826
        return _loadJsonMissionFileV2(json, visualItems, errorString);
827 828 829
    }
}

830
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
831
{
832 833
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
834 835 836 837 838 839 840 841 842

    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;
843
            plannedHomePositionInFile = true;
844 845 846
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
847
            plannedHomePositionInFile = false;
848 849 850 851
        }
    }

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

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

            if (item->load(stream)) {
860 861 862 863 864 865
                if (firstItem && plannedHomePositionInFile) {
                    settingsItem->setCoordinate(item->coordinate());
                } else {
                    visualItems->append(item);
                }
                firstItem = false;
866
            } else {
867
                errorString = tr("The mission file is corrupted.");
868 869 870 871
                return false;
            }
        }
    } else {
872
        errorString = tr("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
873 874 875
        return false;
    }

876
    if (!plannedHomePositionInFile) {
877 878 879
        // 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));
880
            if (item && item->command() == MAV_CMD_DO_JUMP) {
881
                item->missionItem().setParam1(static_cast<int>(item->missionItem().param1()) + 1);
Don Gagne's avatar
Don Gagne committed
882 883
            }
        }
884 885 886
    }

    return true;
887 888
}

889
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
890
{
Don Gagne's avatar
Don Gagne committed
891 892 893
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
894
        _settingsItem = nullptr;
Don Gagne's avatar
Don Gagne committed
895 896
    }

897
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
898 899

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

903
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
904

Don Gagne's avatar
Don Gagne committed
905
    _initAllVisualItems();
906
}
907

908 909 910 911 912 913
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

914
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939
        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;
940
    }
941

942 943 944 945 946 947 948 949 950 951 952 953 954
    _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);
955
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
956 957 958 959 960 961
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
962
    return true;
963 964
}

965 966 967 968 969 970 971 972 973 974 975 976
bool MissionController::readyForSaveSend(void) const
{
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        if (!visualItem->readyForSave()) {
            return false;
        }
    }

    return true;
}

977
void MissionController::save(QJsonObject& json)
978
{
979
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
980

981
    // Mission settings
982

983 984 985 986 987 988 989
    MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsItem";
        return;
    }
    QJsonValue coordinateValue;
    JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
990 991 992 993 994
    json[_jsonPlannedHomePositionKey]   = coordinateValue;
    json[_jsonFirmwareTypeKey]          = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey]           = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey]           = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey]            = _controllerVehicle->defaultHoverSpeed();
995

996
    // Save the visual items
997

998 999 1000
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1001

1002 1003
        visualItem->save(rgJsonMissionItems);
    }
1004

1005 1006 1007
    // Mission settings has a special case for end mission action
    if (settingsItem) {
        QList<MissionItem*> rgMissionItems;
1008

1009 1010 1011 1012 1013
        if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
1014
        }
1015 1016
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
1017 1018 1019
        }
    }

1020
    json[_jsonItemsKey] = rgJsonMissionItems;
1021 1022
}

1023
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
1024
{
Don Gagne's avatar
Don Gagne committed
1025
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
1026
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
1027 1028 1029 1030
    bool            distanceOk =    false;

    // Convert to fixed altitudes

1031
    distanceOk = true;
1032
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
1033 1034
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
1035
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
1036
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
1037 1038 1039
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
1040 1041 1042
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
1043
    } else {
Don Gagne's avatar
Don Gagne committed
1044
        *altDifference = 0.0;
1045
        *azimuth = 0.0;
1046
        *distance = 0.0;
1047 1048 1049
    }
}

1050
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
1051 1052 1053 1054 1055 1056 1057
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

1058
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
1059 1060
}

1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082
void MissionController::_addWaypointLineSegment(CoordVectHashTable& prevItemPairHashTable, VisualItemPair& pair)
{
    if (prevItemPairHashTable.contains(pair)) {
        // Pair already exists and connected, just re-use
        _linesTable[pair] = prevItemPairHashTable.take(pair);
    } else {
        // Create a new segment and wire update notifiers
        auto linevect       = new CoordinateVector(pair.first->isSimpleItem() ? pair.first->coordinate() : pair.first->exitCoordinate(), pair.second->coordinate(), this);
        auto originNotifier = pair.first->isSimpleItem() ? &VisualMissionItem::coordinateChanged : &VisualMissionItem::exitCoordinateChanged;
        auto endNotifier    = &VisualMissionItem::coordinateChanged;

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

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

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

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

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

Nate Weibley's avatar
Nate Weibley committed
1092 1093
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
1094
    _waypointLines.clear();
1095
    _waypointPath.clear();
1096

1097 1098 1099 1100 1101 1102 1103 1104 1105
    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;
1106 1107 1108
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));

1109 1110 1111 1112 1113 1114
        // 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;
1115
            }
1116 1117
        }

1118 1119 1120
        if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
            firstCoordinateItem = false;
            if (lastCoordinateItem != _settingsItem || (homePositionValid && linkStartToHome)) {
1121
                if (!_flyView) {
1122 1123
                    VisualItemPair pair(lastCoordinateItem, item);
                    _addWaypointLineSegment(old_table, pair);
1124 1125
                }
            }
1126 1127
            _waypointPath.append(QVariant::fromValue(item->coordinate()));
            lastCoordinateItem = item;
1128 1129
        }
    }
1130 1131 1132 1133 1134 1135

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

    if (linkEndToHome && lastCoordinateItem != _settingsItem && homePositionValid) {
1136
        if (!_flyView) {
1137 1138 1139 1140 1141
            VisualItemPair pair(lastCoordinateItem, _settingsItem);
            _addWaypointLineSegment(old_table, pair);
        } else {
            _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
        }
1142
    }
1143 1144 1145 1146

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1147 1148
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
1149 1150 1151 1152 1153 1154 1155 1156 1157 1158
            objs.append(vect);
        }

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

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1159
    _recalcMissionFlightStatus();
1160

1161 1162 1163 1164 1165 1166 1167 1168
    if (_waypointPath.count() == 0) {
        // MapPolyLine has a bug where if you can from a path which has elements to an empty path the line drawn
        // is not cleared from the map. This hack works around that since it causes the previous lines to be remove
        // as then doesn't draw anything on the map.
        _waypointPath.append(QVariant::fromValue(QGeoCoordinate(0, 0)));
        _waypointPath.append(QVariant::fromValue(QGeoCoordinate(0, 0)));
    }

1169
    emit waypointLinesChanged();
1170
    emit waypointPathChanged();
1171 1172
}

1173 1174 1175 1176 1177 1178
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);
1179 1180 1181
        // 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.
1182
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205
            _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);
}

1206 1207 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
/// 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
1233
void MissionController::_recalcMissionFlightStatus()
1234
{
1235
    if (!_visualItems->count()) {
1236
        return;
1237
    }
1238 1239 1240 1241

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

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1244
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1245

1246 1247 1248
    // 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.
1249

1250
    // No values for first item
1251
    lastCoordinateItem->setAltDifference(0.0);
1252
    lastCoordinateItem->setAzimuth(0.0);
1253
    lastCoordinateItem->setDistance(0.0);
1254

1255 1256
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1257 1258
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1259

1260
    _resetMissionFlightStatus();
1261

DonLakeFlyer's avatar
DonLakeFlyer committed
1262
    bool vtolInHover = true;
1263
    bool linkStartToHome = false;
1264 1265 1266 1267 1268 1269 1270 1271 1272 1273
    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();
        }
    }
1274

DonLakeFlyer's avatar
DonLakeFlyer committed
1275
    for (int i=0; i<_visualItems->count(); i++) {
1276
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1277 1278 1279
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1280 1281
        // Assume the worst
        item->setAzimuth(0.0);
1282
        item->setDistance(0.0);
1283

DonLakeFlyer's avatar
DonLakeFlyer committed
1284 1285 1286
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1287
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1288
                _missionFlightStatus.hoverSpeed = newSpeed;
1289
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1290 1291
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1292
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1293
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1294
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1295 1296
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1297
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1298 1299 1300 1301
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1302 1303 1304 1305 1306 1307 1308
        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
1309 1310 1311 1312 1313
        }

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

1316
        // Link back to home if first item is takeoff and we have home position
1317
        if (firstCoordinateItem && simpleItem && (simpleItem->command() == MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
1318
            if (showHomePosition) {
1319
                linkStartToHome = true;
1320 1321 1322 1323 1324 1325 1326
                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);
                }
1327 1328 1329 1330
            }
        }

        // Update VTOL state
1331
        if (simpleItem && _controllerVehicle->vtol()) {
1332
            switch (simpleItem->command()) {
1333
            case MAV_CMD_NAV_TAKEOFF:
1334 1335
                vtolInHover = false;
                break;
1336
            case MAV_CMD_NAV_VTOL_TAKEOFF:
DonLakeFlyer's avatar
DonLakeFlyer committed
1337 1338
                vtolInHover = true;
                break;
1339
            case MAV_CMD_NAV_LAND:
1340 1341
                vtolInHover = false;
                break;
1342
            case MAV_CMD_NAV_VTOL_LAND:
DonLakeFlyer's avatar
DonLakeFlyer committed
1343 1344
                vtolInHover = true;
                break;
1345
            case MAV_CMD_DO_VTOL_TRANSITION:
1346 1347 1348 1349 1350 1351
            {
                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;
1352 1353
                }
            }
1354 1355 1356
                break;
            default:
                break;
1357
            }
Don Gagne's avatar
Don Gagne committed
1358 1359
        }

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

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

1365
            double absoluteAltitude = item->coordinate().altitude();
1366
            if (item->coordinateHasRelativeAltitude()) {
1367 1368 1369 1370 1371
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1372 1373 1374 1375
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1376 1377 1378
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1379
                firstCoordinateItem = false;
1380 1381 1382 1383 1384 1385 1386

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

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

1391
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1392 1393 1394
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1395

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1398 1399 1400
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1401
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1402
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1403

1404
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1405 1406
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1407
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1408

1409 1410
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1411
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1412
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1413 1414

                item->setMissionFlightStatus(_missionFlightStatus);
1415

1416 1417
                lastCoordinateItem = item;
            }
1418 1419
        }
    }
1420
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1421

1422 1423 1424 1425 1426 1427 1428 1429
    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();
1430
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1431 1432
    }

1433 1434 1435
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1436

DonLakeFlyer's avatar
DonLakeFlyer committed
1437 1438 1439 1440 1441 1442 1443
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1444 1445
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1446

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

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1454
            if (item->coordinateHasRelativeAltitude()) {
1455 1456 1457 1458
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1459
                item->setTerrainPercent(qQNaN());
1460
                item->setTerrainCollision(false);
1461 1462
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1463 1464 1465 1466 1467 1468 1469
                double terrainAltitude = item->terrainAltitude();
                if (qIsNaN(terrainAltitude)) {
                    item->setTerrainPercent(qQNaN());
                    item->setTerrainCollision(false);
                } else {
                    item->setTerrainPercent((terrainAltitude - minAltSeen) / altRange);
                    item->setTerrainCollision(absoluteAltitude < terrainAltitude);
1470
                }
1471
            }
1472 1473 1474 1475
        }
    }
}

1476 1477 1478
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1479 1480 1481 1482 1483
    if (_inRecalcSequence) {
        // Don't let this call recurse due to signalling
        return;
    }

1484 1485
    // Setup ascending sequence numbers for all visual items

1486
    _inRecalcSequence = true;
1487 1488 1489
    int sequenceNumber = 0;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1490 1491
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1492 1493
    }    
    _inRecalcSequence = false;
1494 1495
}

1496 1497 1498
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1499
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1500 1501 1502

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

1503 1504
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1505 1506 1507 1508 1509

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

1516 1517 1518 1519 1520 1521
void MissionController::_setPlannedHomePositionFromFirstCoordinate(void)
{
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1522
    // Set the planned home position to be a delta from first coordinate
1523 1524 1525 1526
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

        if (item->specifiesCoordinate()) {
1527 1528 1529
            QGeoCoordinate plannedHomeCoord = item->coordinate().atDistanceAndAzimuth(30, 0);
            plannedHomeCoord.setAltitude(0);
            _settingsItem->setCoordinate(plannedHomeCoord);
1530 1531 1532 1533 1534
        }
    }
}


1535 1536
void MissionController::_recalcAll(void)
{
1537
    if (!_flyView) {
1538 1539
        _setPlannedHomePositionFromFirstCoordinate();
    }
1540
    _recalcSequence();
1541 1542 1543 1544
    _recalcChildItems();
    _recalcWaypointLines();
}

1545
/// Initializes a new set of mission items
1546
void MissionController::_initAllVisualItems(void)
1547
{
1548 1549
    // Setup home position at index 0

1550 1551 1552
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1553 1554
        return;
    }
1555
    if (!_flyView) {
1556 1557
        _settingsItem->setIsCurrentItem(true);
    }
1558

1559
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1560
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1561
    }
1562

1563 1564 1565
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1566

1567 1568 1569 1570
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1571

1572
    _recalcAll();
1573

1574
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1575 1576 1577
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1578
    emit containsItemsChanged(containsItems());
1579
    emit plannedHomePositionChanged(plannedHomePosition());
1580

1581
    setDirty(false);
1582 1583
}

1584
void MissionController::_deinitAllVisualItems(void)
1585
{
1586 1587 1588
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1589 1590
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1591 1592
    }

1593
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1594
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1595 1596
}

1597
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1598
{
1599
    setDirty(false);
1600

1601
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1602 1603
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1604 1605
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1606
    connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged,                this, &MissionController::_recalcMissionFlightStatus);
1607
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1608
    connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged,                 this, &MissionController::_recalcMissionFlightStatus);
1609
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1610

1611 1612 1613 1614 1615 1616 1617 1618
    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";
        }
1619 1620
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1621
        if (complexItem) {
1622
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
1623
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
1624 1625 1626
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1627
    }
1628 1629
}

1630
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1631
{
1632 1633
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1634 1635
}

1636
void MissionController::_itemCommandChanged(void)
1637
{
1638 1639
    _recalcChildItems();
    _recalcWaypointLines();
1640 1641
}

1642
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1643
{
1644 1645 1646 1647 1648 1649
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1650

1651 1652
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1653
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1654 1655
        return;
    }
1656

1657 1658
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1659 1660
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1661 1662 1663 1664 1665
    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);
1666
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1667 1668 1669 1670
    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);
1671

1672 1673
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1674
    }
1675

1676
    emit complexMissionItemNamesChanged();
1677
    emit resumeMissionIndexChanged();
1678 1679
}

1680
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1681
{
1682 1683
    if (_visualItems) {
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1684
        if (settingsItem) {
1685
            settingsItem->setHomePositionFromVehicle(homePosition);
1686
        } else {
1687
            qWarning() << "First item is not MissionSettingsItem";
1688
        }
1689 1690 1691
        // Don't let this trip the dirty bit. Otherwise plan will keep getting marked dirty if vehicle home
        // changes.
        _visualItems->setDirty(false);
1692
    }
1693 1694 1695
}

void MissionController::_inProgressChanged(bool inProgress)
1696
{
1697
    emit syncInProgressChanged(inProgress);
1698
}
1699

1700
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1701
{
1702 1703
    bool        found = false;
    double      foundAltitude;
1704
    int         foundAltitudeMode;
1705

1706 1707 1708 1709 1710 1711
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1714 1715 1716
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1717 1718 1719
                if (simpleItem->specifiesAltitude()) {
                    foundAltitude = simpleItem->altitude()->rawValue().toDouble();
                    foundAltitudeMode = simpleItem->altitudeMode();
1720
                    found = true;
1721
                    break;
1722 1723
                }
            }
1724 1725 1726
        }
    }

1727
    if (found) {
1728
        *prevAltitude = foundAltitude;
1729
        *prevAltitudeMode = foundAltitudeMode;
1730 1731 1732
    }

    return found;
1733
}
1734 1735 1736 1737 1738 1739 1740 1741 1742 1743 1744 1745 1746

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

1747
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1748
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1749
{
1750
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
1751

Don Gagne's avatar
Don Gagne committed
1752 1753
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1754
    visualItems->insert(0, settingsItem);
1755

1756 1757 1758 1759 1760 1761 1762 1763 1764 1765 1766 1767 1768 1769 1770 1771 1772 1773 1774 1775 1776 1777 1778 1779 1780
    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;
                    }
1781 1782
                }
            }
1783

1784 1785 1786
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1787
        }
Don Gagne's avatar
Don Gagne committed
1788 1789
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1790 1791
    }
}
1792

1793
int MissionController::resumeMissionIndex(void) const
1794
{
1795

1796
    int resumeIndex = 0;
1797

1798
    if (_flyView) {
1799
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1800
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1801 1802
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1803 1804
        } else {
            resumeIndex = 0;
1805 1806 1807 1808 1809
        }
    }

    return resumeIndex;
}
1810

1811 1812
int MissionController::currentMissionIndex(void) const
{
1813
    if (!_flyView) {
1814 1815 1816 1817 1818 1819 1820 1821 1822 1823
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

1824
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1825
{
1826
    if (_flyView) {
1827
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1828 1829 1830
            sequenceNumber++;
        }

1831 1832
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1833 1834
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1835
        emit currentMissionIndexChanged(currentMissionIndex());
1836 1837
    }
}
1838

1839
bool MissionController::syncInProgress(void) const
1840
{
1841
    return _missionManager->inProgress();
1842 1843 1844 1845 1846 1847 1848 1849 1850 1851 1852 1853
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1854
    }
1855
}
1856

1857 1858
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1859 1860
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, vehicle);
1861

1862 1863 1864 1865 1866 1867
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1868
        if (!_flyView) {
1869 1870 1871 1872 1873 1874
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
1875 1876 1877
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1878
        if (simpleItem) {
1879 1880 1881 1882 1883
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
1884 1885 1886
        }
    }
}
1887 1888 1889 1890 1891 1892 1893 1894 1895 1896 1897 1898 1899

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
1900 1901 1902 1903 1904 1905 1906 1907
    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();
    }
1908
}
1909 1910 1911 1912 1913 1914

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

    complexItems.append(_surveyMissionItemName);
1915
    complexItems.append(_corridorScanMissionItemName);
1916
    if (_controllerVehicle->fixedWing()) {
1917 1918
        complexItems.append(_fwLandingMissionItemName);
    }
1919 1920 1921
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
        complexItems.append(_structureScanMissionItemName);
    }
1922 1923 1924

    return complexItems;
}
1925

1926 1927
void MissionController::resumeMission(int resumeIndex)
{
1928
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1929 1930
        resumeIndex--;
    }
1931
    _missionManager->generateResumeMission(resumeIndex);
1932
}
1933 1934 1935 1936 1937 1938 1939 1940 1941

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1942 1943 1944 1945 1946 1947 1948 1949 1950 1951

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

1953 1954 1955 1956 1957 1958 1959
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
1960 1961 1962 1963 1964 1965

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
1966 1967 1968

bool MissionController::showPlanFromManagerVehicle (void)
{
1969
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
DonLakeFlyer's avatar
DonLakeFlyer committed
1970 1971
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
1972
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
1973 1974 1975 1976 1977 1978 1979 1980 1981 1982 1983 1984 1985 1986 1987 1988 1989 1990 1991
    } 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;
        }
    }
}

1992
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1993
{
1994
    // Fly view always reloads on send complete
1995
    if (!error && _flyView) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1996 1997 1998 1999
        showPlanFromManagerVehicle();
    }
}

2000
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2001
{
2002 2003 2004 2005
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2006
}
2007 2008 2009 2010 2011 2012 2013 2014 2015 2016 2017 2018 2019 2020 2021 2022 2023 2024 2025 2026 2027 2028 2029 2030 2031 2032 2033 2034 2035 2036

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)) {
        _currentPlanViewItem  = NULL;
        _currentPlanViewIndex = -1;
        for (int i = 0; i < _visualItems->count(); i++) {
            VisualMissionItem* pVI = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
            if (pVI && pVI->sequenceNumber() == sequenceNumber) {
                pVI->setIsCurrentItem(true);
                _currentPlanViewItem  = pVI;
                _currentPlanViewIndex = sequenceNumber;
            } else {
                pVI->setIsCurrentItem(false);
            }
        }
        emit currentPlanViewIndexChanged();
        emit currentPlanViewItemChanged();
    }
}