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 "SurveyComplexItem.h"
20
#include "FixedWingLandingComplexItem.h"
21
#include "StructureScanComplexItem.h"
22
#include "CorridorScanComplexItem.h"
23
#include "JsonHelper.h"
24
#include "ParameterManager.h"
25
#include "QGroundControlQmlGlobal.h"
26
#include "SettingsManager.h"
27
#include "AppSettings.h"
28
#include "MissionSettingsItem.h"
29
#include "QGCQGeoCoordinate.h"
30
#include "PlanMasterController.h"
31
#include "KML.h"
32

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

38 39
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

// Deprecated V1 format keys
const char* MissionController::_jsonComplexItemsKey =           "complexItems";
const char* MissionController::_jsonMavAutopilotKey =           "MAV_AUTOPILOT";

const int   MissionController::_missionFileVersion =            2;
55

56 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
void MissionController::convertToKMLDocument(QDomDocument& document)
{
268 269 270 271 272
    QObject*            deleteParent = new QObject();
    QList<MissionItem*> rgMissionItems;

    _convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
    if (rgMissionItems.count() == 0) {
273 274
        return;
    }
275

276
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
277 278 279 280 281

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

        if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
291
            double amslAltitude = item->param7() + (item->frame() == MAV_FRAME_GLOBAL ? 0 : homePositionAltitude);
yaoling's avatar
yaoling committed
292
            coord = QString::number(item->param6(),'f',7) \
293 294 295
                    + "," \
                    + QString::number(item->param5(),'f',7) \
                    + "," \
296
                    + QString::number(amslAltitude,'f',2);
297 298 299
            coords.append(coord);
        }
    }
300 301 302

    deleteParent->deleteLater();

303 304 305 306 307
    Kml kml;
    kml.points(coords);
    kml.save(document);
}

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

313
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
314

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

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

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

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

    _recalcAll();

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

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

375 376
    double  prevAltitude;
    int     prevAltitudeMode;
377

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

    _recalcAll();

    return newItem->sequenceNumber();
}

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

394
    int sequenceNumber = _nextSequenceNumber();
395
    if (itemName == _surveyMissionItemName) {
396
        newItem = new SurveyComplexItem(_controllerVehicle, _visualItems);
397
        newItem->setCoordinate(mapCenterCoordinate);
398 399 400 401 402 403 404 405 406 407 408 409 410 411
        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) {
412 413 414
        bool rollSupported = false;
        bool pitchSupported = false;
        bool yawSupported = false;
415 416 417

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

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

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

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

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

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

    _recalcAll();

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

    return true;
}

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

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

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

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

638 639 640 641
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
642
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _editMode, visualItems);
643 644
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
645 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
    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) {
671
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, visualItems);
672
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
673
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
674
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
675 676 677 678 679 680 681 682 683 684 685 686 687
                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();

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

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

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

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

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

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

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

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

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

    return true;
849 850
}

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

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

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

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

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

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

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

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

    _initLoadedVisualItems(loadedVisualItems);

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

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

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

943
    // Mission settings
944

945 946 947 948 949 950 951 952
    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;
953 954 955 956
    json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
957

958
    // Save the visual items
959

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

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

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

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

982
    json[_jsonItemsKey] = rgJsonMissionItems;
983 984
}

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

    // Convert to fixed altitudes

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

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

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

    distanceOk = true;

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1242
    _resetMissionFlightStatus();
1243

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1453 1454 1455
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1456 1457 1458 1459 1460 1461
    // 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));

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

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

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

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

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

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

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

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


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

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

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

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

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

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

1541
    _recalcAll();
1542

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

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

1550
    setDirty(false);
1551 1552
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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
    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;
                    }
1750 1751
                }
            }
1752

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

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

1765
    int resumeIndex = 0;
1766

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

    return resumeIndex;
}
1779

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

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

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

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

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


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

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

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

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

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

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

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

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

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

    return complexItems;
}
1896

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

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

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

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

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

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

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

1971
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1972
{
1973 1974 1975 1976
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1977
}
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

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