MissionController.cc 81.3 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 "SurveyMissionItem.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 57 58
MissionController::MissionController(PlanMasterController* masterController, QObject *parent)
    : PlanElementController(masterController, parent)
    , _missionManager(_managerVehicle->missionManager())
59
    , _visualItems(NULL)
60
    , _settingsItem(NULL)
61
    , _firstItemsFromVehicle(false)
DonLakeFlyer's avatar
DonLakeFlyer committed
62
    , _itemsRequested(false)
63 64
    , _surveyMissionItemName(tr("Survey"))
    , _fwLandingMissionItemName(tr("Fixed Wing Landing"))
65
    , _structureScanMissionItemName(tr("Structure Scan"))
66
    , _corridorScanMissionItemName(tr("Corridor Scan"))
67
    , _appSettings(qgcApp()->toolbox()->settingsManager()->appSettings())
68
    , _progressPct(0)
69 70
    , _currentPlanViewIndex(-1)
    , _currentPlanViewItem(NULL)
71
{
72
    _resetMissionFlightStatus();
73
    managerVehicleChanged(_managerVehicle);
74 75 76 77
}

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

79 80
}

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

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

108 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();
        _missionFlightStatus.ampMinutesAvailable = (double)_missionFlightStatus.mAhBattery / 1000.0 * 60.0 * ((100.0 - batteryPercentRemainingAnnounce) / 100.0);
112
    }
113 114 115 116 117 118 119 120 121 122 123

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

124 125
}

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

130
    PlanElementController::start(editMode);
131 132 133 134 135
    _init();
}

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

142
// Called when new mission items have completed downloading from Vehicle
143
void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllRequested)
144
{
145 146
    qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle";

DonLakeFlyer's avatar
DonLakeFlyer committed
147 148 149
    // Fly view always reloads on _loadComplete
    // Plan view only reloads on _loadComplete if specifically requested
    if (!_editMode || removeAllRequested || _itemsRequested) {
150
        // Fly Mode (accept if):
Don Gagne's avatar
Don Gagne committed
151
        //      - Always accepts new items from the vehicle so Fly view is kept up to date
152
        // Edit Mode (accept if):
153
        //      - Either a load from vehicle was manually requested or
Don Gagne's avatar
Don Gagne committed
154
        //      - The initial automatic load from a vehicle completed and the current editor is empty
155
        //      - Remove all way requested from Fly view (clear mission on flight end)
156

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

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

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

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

189
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
DonLakeFlyer's avatar
DonLakeFlyer committed
190
            _addMissionSettings(_visualItems, _editMode && _visualItems->count() > 0 /* addToCenter */);
191 192
        }

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

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

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

214
void MissionController::sendToVehicle(void)
215
{
DonLakeFlyer's avatar
DonLakeFlyer committed
216 217 218 219 220
    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
221
        qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
DonLakeFlyer's avatar
DonLakeFlyer committed
222 223 224 225 226 227 228 229 230
        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
231 232
}

233 234 235 236 237
/// 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
238 239 240 241
    if (visualMissionItems->count() == 0) {
        return false;
    }

242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257
    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
258
    MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
259 260 261 262 263 264 265
    if (settingsItem) {
        endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
    }

    return endActionSet;
}

266 267 268 269
void MissionController::convertToKMLDocument(QDomDocument& document)
{
    QJsonObject missionJson;
    QmlObjectListModel* visualItems = new QmlObjectListModel();
270
    QList<MissionItem*> missionItems;
271 272 273
    QString error;
    save(missionJson);
    _loadItemsFromJson(missionJson, visualItems, error);
274 275 276 277 278
    _convertToMissionItems(visualItems, missionItems, this);

    if (missionItems.count() == 0) {
        return;
    }
279

280
    float homeAltitude = missionJson[_jsonPlannedHomePositionKey].toArray()[2].toDouble();
281 282 283 284 285

    QString coord;
    QStringList coords;
    // Drop home position
    bool dropPoint = true;
286
    for(const auto& item : missionItems) {
287 288 289 290 291
        if(dropPoint) {
            dropPoint = false;
            continue;
        }
        const MissionCommandUIInfo* uiInfo = \
292
                qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, item->command());
293 294

        if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
295
            double amslAltitude = item->param7() + (item->frame() == MAV_FRAME_GLOBAL ? 0 : homeAltitude);
yaoling's avatar
yaoling committed
296
            coord = QString::number(item->param6(),'f',7) \
297 298 299
                    + "," \
                    + QString::number(item->param5(),'f',7) \
                    + "," \
300
                    + QString::number(amslAltitude,'f',2);
301 302 303 304 305 306 307 308
            coords.append(coord);
        }
    }
    Kml kml;
    kml.points(coords);
    kml.save(document);
}

Don Gagne's avatar
Don Gagne committed
309 310 311
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
312
        QList<MissionItem*> rgMissionItems;
313

314
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
315

316
        // PlanManager takes control of MissionItems so no need to delete
317
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
318 319
    }
}
320

321 322 323 324 325 326
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
327 328
        VisualMissionItem* lastItem = _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1);
        return lastItem->lastSequenceNumber() + 1;
329 330 331
    }
}

332
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
333
{
334
    int sequenceNumber = _nextSequenceNumber();
335
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, this);
336
    newItem->setSequenceNumber(sequenceNumber);
337
    newItem->setCoordinate(coordinate);
338
    newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
339 340
    _initVisualItem(newItem);
    if (_visualItems->count() == 1) {
341
        MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
342 343 344
        if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains((MAV_CMD)takeoffCmd)) {
            newItem->setCommand(takeoffCmd);
        }
345
    }
346
    newItem->setDefaultsForCommand();
347 348 349
    if (newItem->specifiesAltitude()) {
        double  prevAltitude;
        int     prevAltitudeMode;
350

351 352 353
        if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
            newItem->altitude()->setRawValue(prevAltitude);
            newItem->setAltitudeMode((SimpleMissionItem::AltitudeMode)prevAltitudeMode);
354
        }
355
    }
356
    newItem->setMissionFlightStatus(_missionFlightStatus);
357
    _visualItems->insert(i, newItem);
358 359 360

    _recalcAll();

361
    return newItem->sequenceNumber();
362 363
}

364 365 366 367 368
int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
{
    int sequenceNumber = _nextSequenceNumber();
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, this);
    newItem->setSequenceNumber(sequenceNumber);
369
    newItem->setCommand((MAV_CMD)(_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains((MAV_CMD)MAV_CMD_DO_SET_ROI_LOCATION) ?
370 371
        MAV_CMD_DO_SET_ROI_LOCATION :
        MAV_CMD_DO_SET_ROI));
372 373
    _initVisualItem(newItem);
    newItem->setDefaultsForCommand();
374
    newItem->setCoordinate(coordinate);
375

376 377
    double  prevAltitude;
    int     prevAltitudeMode;
378

379 380 381
    if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
        newItem->altitude()->setRawValue(prevAltitude);
        newItem->setAltitudeMode((SimpleMissionItem::AltitudeMode)prevAltitudeMode);
382 383 384 385 386 387 388 389
    }
    _visualItems->insert(i, newItem);

    _recalcAll();

    return newItem->sequenceNumber();
}

390
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
391
{
392
    ComplexMissionItem* newItem;
393
    bool surveyStyleItem = false;
394

395
    int sequenceNumber = _nextSequenceNumber();
396
    if (itemName == _surveyMissionItemName) {
397
        newItem = new SurveyMissionItem(_controllerVehicle, _visualItems);
398
        newItem->setCoordinate(mapCenterCoordinate);
399 400 401 402 403 404 405 406 407 408 409 410 411 412
        surveyStyleItem = true;
    } else if (itemName == _fwLandingMissionItemName) {
        newItem = new FixedWingLandingComplexItem(_controllerVehicle, _visualItems);
    } else if (itemName == _structureScanMissionItemName) {
        newItem = new StructureScanComplexItem(_controllerVehicle, _visualItems);
    } else if (itemName == _corridorScanMissionItemName) {
        newItem = new CorridorScanComplexItem(_controllerVehicle, _visualItems);
        surveyStyleItem = true;
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }

    if (surveyStyleItem) {
413 414 415
        bool rollSupported = false;
        bool pitchSupported = false;
        bool yawSupported = false;
416 417 418

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

419 420
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
        CameraSection* cameraSection = settingsItem->cameraSection();
421

422
        // Set camera to photo mode (leave alone if user already specified)
423
        if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
424
            cameraSection->setSpecifyCameraMode(true);
425
            cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
426
        }
427

428
        // Point gimbal straight down
429
        if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
430 431 432
            // If the user already specified a gimbal angle leave it alone
            if (!cameraSection->specifyGimbal()) {
                cameraSection->setSpecifyGimbal(true);
433
                cameraSection->gimbalPitch()->setRawValue(-90.0);
434 435
            }
        }
436
    }
437

438
    newItem->setSequenceNumber(sequenceNumber);
439
    _initVisualItem(newItem);
440

441
    _visualItems->insert(i, newItem);
442 443 444

    _recalcAll();

445
    return newItem->sequenceNumber();
446 447
}

448 449
void MissionController::removeMissionItem(int index)
{
450 451 452 453 454
    if (index <= 0 || index >= _visualItems->count()) {
        qWarning() << "MissionController::removeMissionItem called with bad index - count:index" << _visualItems->count() << index;
        return;
    }

455
    bool removeSurveyStyle = _visualItems->value<SurveyMissionItem*>(index) || _visualItems->value<CorridorScanComplexItem*>(index);
456
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
457

458
    _deinitVisualItem(item);
459
    item->deleteLater();
460

461 462
    if (removeSurveyStyle) {
        // Determine if the mission still has another survey style item in it
463 464
        bool foundSurvey = false;
        for (int i=1; i<_visualItems->count(); i++) {
465
            if (_visualItems->value<SurveyMissionItem*>(i) || _visualItems->value<CorridorScanComplexItem*>(i)) {
466 467 468 469 470
                foundSurvey = true;
                break;
            }
        }

471
        // If there is no longer a survey item in the mission remove added commands
472 473 474 475
        if (!foundSurvey) {
            bool rollSupported = false;
            bool pitchSupported = false;
            bool yawSupported = false;
476 477
            MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
            CameraSection* cameraSection = settingsItem->cameraSection();
478
            if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
479
                if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
480 481 482
                    cameraSection->setSpecifyGimbal(false);
                }
            }
483
            if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
484 485
                cameraSection->setSpecifyCameraMode(false);
            }
486 487 488
        }
    }

489
    _recalcAll();
490
    setDirty(true);
491 492
}

493
void MissionController::removeAll(void)
494
{
495 496
    if (_visualItems) {
        _deinitAllVisualItems();
DonLakeFlyer's avatar
DonLakeFlyer committed
497
        _visualItems->clearAndDeleteContents();
Don Gagne's avatar
Don Gagne committed
498
        _visualItems->deleteLater();
499
        _settingsItem = NULL;
500
        _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
501
        _addMissionSettings(_visualItems, false /* addToCenter */);
502
        _initAllVisualItems();
503
        setDirty(true);
504
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
505 506 507
    }
}

508
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
509 510 511 512 513 514 515 516 517
{
    // 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)) {
518 519 520
        return false;
    }

521
    // Read complex items
522
    QList<SurveyMissionItem*> surveyItems;
523 524 525 526
    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];
527

528 529 530 531 532
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

533
        SurveyMissionItem* item = new SurveyMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
534 535
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
536
            surveyItems.append(item);
537 538
        } else {
            return false;
539
        }
540
    }
541

542 543 544 545 546
    // 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
547
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
548

549
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
550 551 552 553
    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
554 555
        if (nextComplexItemIndex < surveyItems.count()) {
            SurveyMissionItem* complexItem = surveyItems[nextComplexItemIndex];
556 557 558 559 560 561 562 563 564 565 566 567 568 569

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

570 571 572 573 574
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
575
            const QJsonObject itemObject = itemValue.toObject();
576
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
577
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
578
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
579
                nextSequenceNumber = item->lastSequenceNumber() + 1;
580
                visualItems->append(item);
581 582 583 584
            } else {
                return false;
            }
        }
585
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
586 587

    if (json.contains(_jsonPlannedHomePositionKey)) {
588
        SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
589

Don Gagne's avatar
Don Gagne committed
590
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
591
            MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
592 593 594
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
595 596 597 598
        } else {
            return false;
        }
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
599
        _addMissionSettings(visualItems, true /* addToCenter */);
600 601 602 603 604
    }

    return true;
}

605
bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
606 607 608 609 610 611
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
612
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
613 614
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
615 616 617 618 619 620 621
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

622
    // Mission Settings
623
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
624

625 626
    if (_masterController->offline()) {
        // We only update if offline since if we are online we use the online vehicle settings
627 628 629 630
        appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType((MAV_AUTOPILOT)json[_jsonFirmwareTypeKey].toInt()));
        if (json.contains(_jsonVehicleTypeKey)) {
            appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType((MAV_TYPE)json[_jsonVehicleTypeKey].toInt()));
        }
631
    }
632
    if (json.contains(_jsonCruiseSpeedKey)) {
633
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
634 635
    }
    if (json.contains(_jsonHoverSpeedKey)) {
636
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
637 638
    }

639 640 641 642
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
643
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _editMode, visualItems);
644 645
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671
    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) {
672
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, visualItems);
673
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
674
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
675
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
676 677 678 679 680 681 682 683 684 685 686 687 688 689 690
                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();

            if (complexItemType == SurveyMissionItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Survey: nextSequenceNumber" << nextSequenceNumber;
691
                SurveyMissionItem* surveyItem = new SurveyMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
692 693 694 695 696 697
                if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(surveyItem);
698
            } else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
699
                qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
700
                FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(_controllerVehicle, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
701 702 703 704 705 706
                if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(landingItem);
707 708 709 710 711 712 713 714 715
            } else if (complexItemType == StructureScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Structure Scan: nextSequenceNumber" << nextSequenceNumber;
                StructureScanComplexItem* structureItem = new StructureScanComplexItem(_controllerVehicle, visualItems);
                if (!structureItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = structureItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Structure Scan load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(structureItem);
716 717 718 719 720 721 722 723 724
            } else if (complexItemType == CorridorScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Corridor Scan: nextSequenceNumber" << nextSequenceNumber;
                CorridorScanComplexItem* corridorItem = new CorridorScanComplexItem(_controllerVehicle, visualItems);
                if (!corridorItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = corridorItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Corridor Scan load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(corridorItem);
725
            } else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
726
                qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
727
                MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _editMode, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
728 729 730 731 732 733
                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
734 735 736 737 738 739 740 741 742 743 744 745 746
            } 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);
Don Gagne's avatar
Don Gagne committed
747
            if ((MAV_CMD)doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770
                bool found = false;
                int findDoJumpId = doJumpItem->missionItem().param1();
                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;
}

771 772 773 774 775 776 777 778
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;
779 780 781 782 783 784
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
785 786

    if (fileVersion == 1) {
787
        return _loadJsonMissionFileV1(json, visualItems, errorString);
788
    } else {
789
        return _loadJsonMissionFileV2(json, visualItems, errorString);
790 791 792
    }
}

793
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
794
{
795 796
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
797 798 799 800 801 802 803 804 805

    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;
806
            plannedHomePositionInFile = true;
807 808 809
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
810
            plannedHomePositionInFile = false;
811 812 813 814
        }
    }

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

819
        while (!stream.atEnd()) {
820
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
821 822

            if (item->load(stream)) {
823 824 825 826 827 828
                if (firstItem && plannedHomePositionInFile) {
                    settingsItem->setCoordinate(item->coordinate());
                } else {
                    visualItems->append(item);
                }
                firstItem = false;
829
            } else {
830
                errorString = tr("The mission file is corrupted.");
831 832 833 834
                return false;
            }
        }
    } else {
835
        errorString = tr("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
836 837 838
        return false;
    }

839
    if (!plannedHomePositionInFile) {
840 841 842
        // 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));
843
            if (item && item->command() == MAV_CMD_DO_JUMP) {
844
                item->missionItem().setParam1((int)item->missionItem().param1() + 1);
Don Gagne's avatar
Don Gagne committed
845 846
            }
        }
847 848 849
    }

    return true;
850 851
}

852
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
853
{
Don Gagne's avatar
Don Gagne committed
854 855 856
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
857
        _settingsItem = NULL;
Don Gagne's avatar
Don Gagne committed
858 859
    }

860
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
861 862

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

866
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
867

Don Gagne's avatar
Don Gagne committed
868
    _initAllVisualItems();
869
}
870

871 872 873 874 875 876
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

877
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902
        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;
903
    }
904

905 906 907 908 909 910 911 912 913 914 915 916 917
    _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);
918
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
919 920 921 922 923 924
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
925
    return true;
926 927
}

928 929 930 931 932 933 934 935 936 937 938 939
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;
}

940
void MissionController::save(QJsonObject& json)
941
{
942
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
943

944
    // Mission settings
945

946 947 948 949 950 951 952 953
    MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsItem";
        return;
    }
    QJsonValue coordinateValue;
    JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
    json[_jsonPlannedHomePositionKey] = coordinateValue;
954 955 956 957
    json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
958

959
    // Save the visual items
960

961 962 963
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
964

965 966
        visualItem->save(rgJsonMissionItems);
    }
967

968 969 970
    // Mission settings has a special case for end mission action
    if (settingsItem) {
        QList<MissionItem*> rgMissionItems;
971

972 973 974 975 976
        if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
977
        }
978 979
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
980 981 982
        }
    }

983
    json[_jsonItemsKey] = rgJsonMissionItems;
984 985
}

986
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
987
{
Don Gagne's avatar
Don Gagne committed
988
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
989
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
990 991 992 993
    bool            distanceOk =    false;

    // Convert to fixed altitudes

994
    distanceOk = true;
995
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
996 997
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
998
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
999
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
1000 1001 1002
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
1003 1004 1005
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
1006
    } else {
Don Gagne's avatar
Don Gagne committed
1007
        *altDifference = 0.0;
1008
        *azimuth = 0.0;
1009
        *distance = 0.0;
1010 1011 1012
    }
}

1013
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
1014 1015 1016 1017 1018 1019 1020
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

1021
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
1022 1023
}

1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045
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;
    }
}

1046 1047
void MissionController::_recalcWaypointLines(void)
{
1048 1049 1050
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

1051
    bool homePositionValid = _settingsItem->coordinate().isValid();
1052

1053
    qCDebug(MissionControllerLog) << "_recalcWaypointLines homePositionValid" << homePositionValid;
1054

Nate Weibley's avatar
Nate Weibley committed
1055 1056
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
1057
    _waypointLines.clear();
1058
    _waypointPath.clear();
1059

1060 1061 1062 1063 1064 1065 1066 1067 1068
    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;
1069 1070 1071
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));

1072 1073 1074 1075 1076 1077
        // 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;
1078
            }
1079 1080
        }

1081 1082 1083 1084 1085 1086
        if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
            firstCoordinateItem = false;
            if (lastCoordinateItem != _settingsItem || (homePositionValid && linkStartToHome)) {
                if (_editMode) {
                    VisualItemPair pair(lastCoordinateItem, item);
                    _addWaypointLineSegment(old_table, pair);
1087 1088
                }
            }
1089 1090
            _waypointPath.append(QVariant::fromValue(item->coordinate()));
            lastCoordinateItem = item;
1091 1092
        }
    }
1093 1094 1095 1096 1097 1098

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

    if (linkEndToHome && lastCoordinateItem != _settingsItem && homePositionValid) {
1099 1100 1101 1102 1103 1104
        if (_editMode) {
            VisualItemPair pair(lastCoordinateItem, _settingsItem);
            _addWaypointLineSegment(old_table, pair);
        } else {
            _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
        }
1105
    }
1106 1107 1108 1109

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1110 1111
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
1112 1113 1114 1115 1116 1117 1118 1119 1120 1121
            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
1122
    _recalcMissionFlightStatus();
1123

1124 1125 1126 1127 1128 1129 1130 1131
    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)));
    }

1132
    emit waypointLinesChanged();
1133
    emit waypointPathChanged();
1134 1135
}

1136 1137 1138 1139 1140 1141
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);
1142 1143 1144
        // 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.
1145
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168
            _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);
}

1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215
/// Adds additional time to a mission as specified by the command
void MissionController::_addCommandTimeDelay(SimpleMissionItem* simpleItem, bool vtolInHover)
{
    double seconds = 0;

    if (!simpleItem) {
        return;
    }

    // This routine is currently quite minimal and only handles the simple cases.
    switch ((int)simpleItem->command()) {
    case MAV_CMD_NAV_WAYPOINT:
    case MAV_CMD_CONDITION_DELAY:
        seconds = simpleItem->missionItem().param1();
        break;
    }

    _addTimeDistance(vtolInHover, 0, 0, seconds, 0, -1);
}

/// 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
1216
void MissionController::_recalcMissionFlightStatus()
1217
{
1218
    if (!_visualItems->count()) {
1219
        return;
1220
    }
1221 1222 1223 1224

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

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1227
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1228

1229 1230 1231
    // 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.
1232

1233
    // No values for first item
1234
    lastCoordinateItem->setAltDifference(0.0);
1235
    lastCoordinateItem->setAzimuth(0.0);
1236
    lastCoordinateItem->setDistance(0.0);
1237

1238 1239
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1240 1241
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1242

1243
    _resetMissionFlightStatus();
1244

DonLakeFlyer's avatar
DonLakeFlyer committed
1245
    bool vtolInHover = true;
1246
    bool linkStartToHome = false;
1247 1248 1249 1250 1251 1252 1253 1254 1255 1256
    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();
        }
    }
1257

DonLakeFlyer's avatar
DonLakeFlyer committed
1258
    for (int i=0; i<_visualItems->count(); i++) {
1259
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1260 1261 1262
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1263 1264
        // Assume the worst
        item->setAzimuth(0.0);
1265
        item->setDistance(0.0);
1266

DonLakeFlyer's avatar
DonLakeFlyer committed
1267 1268 1269
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1270
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1271
                _missionFlightStatus.hoverSpeed = newSpeed;
1272
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1273 1274
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1275
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1276
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1277
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1278 1279
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1280
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1281 1282 1283 1284
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1285 1286 1287 1288 1289 1290 1291
        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
1292 1293 1294 1295 1296
        }

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

1299
        // Link back to home if first item is takeoff and we have home position
1300
        if (firstCoordinateItem && simpleItem && (simpleItem->command() == MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
1301
            if (showHomePosition) {
1302
                linkStartToHome = true;
1303 1304 1305 1306 1307 1308 1309
                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);
                }
1310 1311 1312 1313
            }
        }

        // Update VTOL state
1314
        if (simpleItem && _controllerVehicle->vtol()) {
1315
            switch (simpleItem->command()) {
1316
            case MAV_CMD_NAV_TAKEOFF:
1317 1318
                vtolInHover = false;
                break;
1319
            case MAV_CMD_NAV_VTOL_TAKEOFF:
DonLakeFlyer's avatar
DonLakeFlyer committed
1320 1321
                vtolInHover = true;
                break;
1322
            case MAV_CMD_NAV_LAND:
1323 1324
                vtolInHover = false;
                break;
1325
            case MAV_CMD_NAV_VTOL_LAND:
DonLakeFlyer's avatar
DonLakeFlyer committed
1326 1327
                vtolInHover = true;
                break;
1328
            case MAV_CMD_DO_VTOL_TRANSITION:
1329 1330 1331 1332 1333 1334
            {
                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;
1335 1336
                }
            }
1337 1338 1339
                break;
            default:
                break;
1340
            }
Don Gagne's avatar
Don Gagne committed
1341 1342
        }

1343 1344 1345
        // Check for command specific time delays
        _addCommandTimeDelay(simpleItem, vtolInHover);

1346
        if (item->specifiesCoordinate()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1347 1348
            // Update vehicle yaw assuming direction to next waypoint
            if (item != lastCoordinateItem) {
1349 1350
                _missionFlightStatus.vehicleYaw = lastCoordinateItem->exitCoordinate().azimuthTo(item->coordinate());
                lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
DonLakeFlyer's avatar
DonLakeFlyer committed
1351 1352
            }

1353 1354
            // Keep track of the min/max altitude for all waypoints so we can show altitudes as a percentage

1355
            double absoluteAltitude = item->coordinate().altitude();
1356
            if (item->coordinateHasRelativeAltitude()) {
1357 1358 1359 1360 1361
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1362 1363 1364 1365
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1366 1367 1368
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1369
                firstCoordinateItem = false;
1370
                if (lastCoordinateItem != _settingsItem || linkStartToHome) {
1371 1372
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1373

1374
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1375 1376 1377
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1378

1379
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1380

DonLakeFlyer's avatar
DonLakeFlyer committed
1381 1382 1383
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1384
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1385
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1386

1387
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1388 1389
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1390
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1391

1392 1393
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1394 1395
                    double extraTime = complexItem->additionalTimeDelay();
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, extraTime, distance, item->sequenceNumber());
1396
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1397 1398

                item->setMissionFlightStatus(_missionFlightStatus);
1399
            }
1400 1401

            lastCoordinateItem = item;
1402 1403
        }
    }
1404
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1405

1406 1407 1408 1409 1410 1411 1412 1413
    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();
1414
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1415 1416
    }

1417 1418 1419
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1420

DonLakeFlyer's avatar
DonLakeFlyer committed
1421 1422 1423 1424 1425 1426 1427
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1428 1429
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1430

1431 1432
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1433 1434
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1435 1436 1437

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1438
            if (item->coordinateHasRelativeAltitude()) {
1439 1440 1441 1442
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1443
                item->setTerrainPercent(qQNaN());
1444 1445
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1446 1447 1448
                if (!qIsNaN(item->terrainAltitude())) {
                    item->setTerrainPercent((item->terrainAltitude() - minAltSeen) / altRange);
                }
1449
            }
1450 1451 1452 1453
        }
    }
}

1454 1455 1456
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1457 1458 1459 1460 1461 1462
    // Setup ascending sequence numbers for all visual items

    int sequenceNumber = 0;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));

1463 1464
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1465 1466 1467
    }
}

1468 1469 1470
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1471
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1472 1473 1474

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

1475 1476
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1477 1478 1479 1480 1481

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1482
        } else if (item->isSimpleItem()) {
1483 1484 1485 1486 1487
            currentParentItem->childItems()->append(item);
        }
    }
}

1488 1489 1490 1491 1492 1493
void MissionController::_setPlannedHomePositionFromFirstCoordinate(void)
{
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1494
    // Set the planned home position to be a delta from first coordinate
1495 1496 1497 1498 1499 1500 1501 1502 1503 1504
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

        if (item->specifiesCoordinate()) {
            _settingsItem->setCoordinate(item->coordinate().atDistanceAndAzimuth(30, 0));
        }
    }
}


1505 1506
void MissionController::_recalcAll(void)
{
1507 1508 1509
    if (_editMode) {
        _setPlannedHomePositionFromFirstCoordinate();
    }
1510
    _recalcSequence();
1511 1512 1513 1514
    _recalcChildItems();
    _recalcWaypointLines();
}

1515
/// Initializes a new set of mission items
1516
void MissionController::_initAllVisualItems(void)
1517
{
1518 1519
    // Setup home position at index 0

1520 1521 1522
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1523 1524
        return;
    }
1525 1526 1527
    if (_editMode) {
        _settingsItem->setIsCurrentItem(true);
    }
1528

1529
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1530
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1531
    }
1532

1533 1534 1535
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1536

1537 1538 1539 1540
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1541

1542
    _recalcAll();
1543

1544
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1545 1546 1547
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1548
    emit containsItemsChanged(containsItems());
1549
    emit plannedHomePositionChanged(plannedHomePosition());
1550

1551
    setDirty(false);
1552 1553
}

1554
void MissionController::_deinitAllVisualItems(void)
1555
{
1556 1557 1558
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1559 1560
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1561 1562
    }

1563
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1564
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1565 1566
}

1567
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1568
{
1569
    setDirty(false);
1570

1571
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1572 1573
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1574 1575
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1576
    connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged,                this, &MissionController::_recalcMissionFlightStatus);
1577
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1578
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1579

1580 1581 1582 1583 1584 1585 1586 1587
    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";
        }
1588 1589
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1590
        if (complexItem) {
1591
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
1592
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
1593
            connect(complexItem, &ComplexMissionItem::additionalTimeDelayChanged,   this, &MissionController::_recalcMissionFlightStatus);
1594 1595 1596
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1597
    }
1598 1599
}

1600
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1601
{
1602 1603
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1604 1605
}

1606
void MissionController::_itemCommandChanged(void)
1607
{
1608 1609
    _recalcChildItems();
    _recalcWaypointLines();
1610 1611
}

1612
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1613
{
1614 1615 1616 1617 1618 1619
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1620

1621 1622
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1623
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1624 1625
        return;
    }
1626

1627 1628
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1629 1630
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1631 1632 1633 1634 1635
    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);
1636
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1637 1638 1639 1640
    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);
1641

1642 1643
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1644
    }
1645

1646
    emit complexMissionItemNamesChanged();
1647
    emit resumeMissionIndexChanged();
1648 1649
}

1650
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1651
{
1652 1653
    if (_visualItems) {
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1654
        if (settingsItem) {
1655
            settingsItem->setHomePositionFromVehicle(homePosition);
1656
        } else {
1657
            qWarning() << "First item is not MissionSettingsItem";
1658
        }
1659 1660 1661
        // Don't let this trip the dirty bit. Otherwise plan will keep getting marked dirty if vehicle home
        // changes.
        _visualItems->setDirty(false);
1662
    }
1663 1664 1665
}

void MissionController::_inProgressChanged(bool inProgress)
1666
{
1667
    emit syncInProgressChanged(inProgress);
1668
}
1669

1670
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1671
{
1672 1673
    bool        found = false;
    double      foundAltitude;
1674
    int         foundAltitudeMode;
1675

1676 1677 1678 1679 1680 1681
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1684 1685 1686
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1687 1688 1689
                if (simpleItem->specifiesAltitude()) {
                    foundAltitude = simpleItem->altitude()->rawValue().toDouble();
                    foundAltitudeMode = simpleItem->altitudeMode();
1690
                    found = true;
1691
                    break;
1692 1693
                }
            }
1694 1695 1696
        }
    }

1697
    if (found) {
1698
        *prevAltitude = foundAltitude;
1699
        *prevAltitudeMode = foundAltitudeMode;
1700 1701 1702
    }

    return found;
1703
}
1704 1705 1706 1707 1708 1709 1710 1711 1712 1713 1714 1715 1716

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

1717
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1718
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1719
{
1720
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _editMode, visualItems);
1721

Don Gagne's avatar
Don Gagne committed
1722 1723
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1724
    visualItems->insert(0, settingsItem);
1725

1726 1727 1728 1729 1730 1731 1732 1733 1734 1735 1736 1737 1738 1739 1740 1741 1742 1743 1744 1745 1746 1747 1748 1749 1750
    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;
                    }
1751 1752
                }
            }
1753

1754 1755 1756
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1757
        }
Don Gagne's avatar
Don Gagne committed
1758 1759
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1760 1761
    }
}
1762

1763
int MissionController::resumeMissionIndex(void) const
1764
{
1765

1766
    int resumeIndex = 0;
1767

1768
    if (!_editMode) {
1769
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1770
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1771 1772
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1773 1774
        } else {
            resumeIndex = 0;
1775 1776 1777 1778 1779
        }
    }

    return resumeIndex;
}
1780

1781 1782 1783 1784 1785 1786 1787 1788 1789 1790 1791 1792 1793
int MissionController::currentMissionIndex(void) const
{
    if (_editMode) {
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

1794
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1795 1796
{
    if (!_editMode) {
1797
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1798 1799 1800
            sequenceNumber++;
        }

1801 1802
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1803 1804
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1805
        emit currentMissionIndexChanged(currentMissionIndex());
1806 1807
    }
}
1808

1809
bool MissionController::syncInProgress(void) const
1810
{
1811
    return _missionManager->inProgress();
1812 1813 1814 1815 1816 1817 1818 1819 1820 1821 1822 1823
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1824
    }
1825
}
1826

1827 1828
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1829 1830 1831 1832
    if (_editMode) {
        // First we look for a Fixed Wing Landing Pattern which is at the end
        FixedWingLandingComplexItem::scanForItem(visualItems, vehicle);
    }
1833

1834 1835 1836 1837 1838 1839
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1840 1841 1842 1843 1844 1845 1846
        if (_editMode) {
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
1847 1848 1849
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1850
        if (simpleItem) {
1851 1852 1853 1854 1855
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
1856 1857 1858
        }
    }
}
1859 1860 1861 1862 1863 1864 1865 1866 1867 1868 1869 1870 1871

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
1872 1873 1874 1875 1876 1877 1878 1879
    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();
    }
1880
}
1881 1882 1883 1884 1885 1886

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

    complexItems.append(_surveyMissionItemName);
1887
    complexItems.append(_corridorScanMissionItemName);
1888
    if (_controllerVehicle->fixedWing()) {
1889 1890
        complexItems.append(_fwLandingMissionItemName);
    }
1891 1892 1893
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
        complexItems.append(_structureScanMissionItemName);
    }
1894 1895 1896

    return complexItems;
}
1897

1898 1899
void MissionController::resumeMission(int resumeIndex)
{
1900
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1901 1902
        resumeIndex--;
    }
1903
    _missionManager->generateResumeMission(resumeIndex);
1904
}
1905 1906 1907 1908 1909 1910 1911 1912 1913

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1914 1915 1916 1917 1918 1919 1920 1921 1922 1923

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

1925 1926 1927 1928 1929 1930 1931
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
1932 1933 1934 1935 1936 1937

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
1938 1939 1940

bool MissionController::showPlanFromManagerVehicle (void)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1941
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle" << _editMode;
DonLakeFlyer's avatar
DonLakeFlyer committed
1942 1943
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
1944
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
1945 1946 1947 1948 1949 1950 1951 1952 1953 1954 1955 1956 1957 1958 1959 1960 1961 1962 1963
    } 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;
        }
    }
}

1964
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1965
{
1966 1967
    // Fly view always reloads on send complete
    if (!error && !_editMode) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1968 1969 1970 1971
        showPlanFromManagerVehicle();
    }
}

1972
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1973
{
1974 1975 1976 1977
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1978
}
1979 1980 1981 1982 1983 1984 1985 1986 1987 1988 1989 1990 1991 1992 1993 1994 1995 1996 1997 1998 1999 2000 2001 2002 2003 2004 2005 2006 2007 2008

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