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


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

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

38 39
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

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

const int   MissionController::_missionFileVersion =            2;
55

56 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
void MissionController::start(bool flyView)
127
{
128
    qCDebug(MissionControllerLog) << "start flyView" << flyView;
129

130
    PlanElementController::start(flyView);
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
    // Fly view always reloads on _loadComplete
    // Plan view only reloads on _loadComplete if specifically requested
149
    if (_flyView || 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, _flyView, *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) {
190
            _addMissionSettings(_visualItems, !_flyView && _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, _flyView, 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
int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
{
    int sequenceNumber = _nextSequenceNumber();
366
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
367
    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 392
    ComplexMissionItem* newItem;

393
    int sequenceNumber = _nextSequenceNumber();
394
    if (itemName == _surveyMissionItemName) {
395
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
396
        newItem->setCoordinate(mapCenterCoordinate);
397
    } else if (itemName == _fwLandingMissionItemName) {
398
        newItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, _visualItems /* parent */);
399
    } else if (itemName == _structureScanMissionItemName) {
400
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
401
    } else if (itemName == _corridorScanMissionItemName) {
402
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
403 404 405 406 407
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }

408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433
    return _insertComplexMissionItemWorker(newItem, i);
}

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

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

    return _insertComplexMissionItemWorker(newItem, i);
}

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

434
    if (surveyStyleItem) {
435 436 437
        bool rollSupported = false;
        bool pitchSupported = false;
        bool yawSupported = false;
438 439 440

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

441 442
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
        CameraSection* cameraSection = settingsItem->cameraSection();
443

444
        // Set camera to photo mode (leave alone if user already specified)
445
        if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
446
            cameraSection->setSpecifyCameraMode(true);
447
            cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
448
        }
449

450
        // Point gimbal straight down
451
        if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
452 453 454
            // If the user already specified a gimbal angle leave it alone
            if (!cameraSection->specifyGimbal()) {
                cameraSection->setSpecifyGimbal(true);
455
                cameraSection->gimbalPitch()->setRawValue(-90.0);
456 457
            }
        }
458
    }
459

460 461
    complexItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(complexItem);
462

463 464 465 466 467
    if (i == -1) {
        _visualItems->append(complexItem);
    } else {
        _visualItems->insert(i, complexItem);
    }
468 469 470

    _recalcAll();

471
    return complexItem->sequenceNumber();
472 473
}

474 475
void MissionController::removeMissionItem(int index)
{
476 477 478 479 480
    if (index <= 0 || index >= _visualItems->count()) {
        qWarning() << "MissionController::removeMissionItem called with bad index - count:index" << _visualItems->count() << index;
        return;
    }

481
    bool removeSurveyStyle = _visualItems->value<SurveyComplexItem*>(index) || _visualItems->value<CorridorScanComplexItem*>(index);
482
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
483

484
    _deinitVisualItem(item);
485
    item->deleteLater();
486

487 488
    if (removeSurveyStyle) {
        // Determine if the mission still has another survey style item in it
489 490
        bool foundSurvey = false;
        for (int i=1; i<_visualItems->count(); i++) {
491
            if (_visualItems->value<SurveyComplexItem*>(i) || _visualItems->value<CorridorScanComplexItem*>(i)) {
492 493 494 495 496
                foundSurvey = true;
                break;
            }
        }

497
        // If there is no longer a survey item in the mission remove added commands
498 499 500 501
        if (!foundSurvey) {
            bool rollSupported = false;
            bool pitchSupported = false;
            bool yawSupported = false;
502 503
            MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
            CameraSection* cameraSection = settingsItem->cameraSection();
504
            if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
505
                if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
506 507 508
                    cameraSection->setSpecifyGimbal(false);
                }
            }
509
            if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
510 511
                cameraSection->setSpecifyCameraMode(false);
            }
512 513 514
        }
    }

515
    _recalcAll();
516
    setDirty(true);
517 518
}

519
void MissionController::removeAll(void)
520
{
521 522
    if (_visualItems) {
        _deinitAllVisualItems();
DonLakeFlyer's avatar
DonLakeFlyer committed
523
        _visualItems->clearAndDeleteContents();
Don Gagne's avatar
Don Gagne committed
524
        _visualItems->deleteLater();
525
        _settingsItem = NULL;
526
        _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
527
        _addMissionSettings(_visualItems, false /* addToCenter */);
528
        _initAllVisualItems();
529
        setDirty(true);
530
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
531 532 533
    }
}

534
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
535 536 537 538 539 540 541 542 543
{
    // 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)) {
544 545 546
        return false;
    }

547
    // Read complex items
548
    QList<SurveyComplexItem*> surveyItems;
549 550 551 552
    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];
553

554 555 556 557 558
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

559
        SurveyComplexItem* item = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems /* parent */);
Don Gagne's avatar
Don Gagne committed
560 561
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
562
            surveyItems.append(item);
563 564
        } else {
            return false;
565
        }
566
    }
567

568 569 570 571 572
    // 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
573
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
574

575
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
576 577 578 579
    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
580
        if (nextComplexItemIndex < surveyItems.count()) {
581
            SurveyComplexItem* complexItem = surveyItems[nextComplexItemIndex];
582 583 584 585 586 587 588 589 590 591 592 593 594 595

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

596 597 598 599 600
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
601
            const QJsonObject itemObject = itemValue.toObject();
602
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
Don Gagne's avatar
Don Gagne committed
603
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
604
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
605
                nextSequenceNumber = item->lastSequenceNumber() + 1;
606
                visualItems->append(item);
607 608 609 610
            } else {
                return false;
            }
        }
611
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
612 613

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

Don Gagne's avatar
Don Gagne committed
616
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
617
            MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
618 619 620
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
621 622 623 624
        } else {
            return false;
        }
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
625
        _addMissionSettings(visualItems, true /* addToCenter */);
626 627 628 629 630
    }

    return true;
}

631
bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
632 633 634 635 636 637
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
638
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
639 640
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
641 642 643 644 645 646 647
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

648
    // Mission Settings
649
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
650

651 652
    if (_masterController->offline()) {
        // We only update if offline since if we are online we use the online vehicle settings
653 654 655 656
        appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType((MAV_AUTOPILOT)json[_jsonFirmwareTypeKey].toInt()));
        if (json.contains(_jsonVehicleTypeKey)) {
            appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType((MAV_TYPE)json[_jsonVehicleTypeKey].toInt()));
        }
657
    }
658
    if (json.contains(_jsonCruiseSpeedKey)) {
659
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
660 661
    }
    if (json.contains(_jsonHoverSpeedKey)) {
662
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
663 664
    }

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

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

797 798 799 800 801 802 803 804
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;
805 806 807 808 809 810
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
811 812

    if (fileVersion == 1) {
813
        return _loadJsonMissionFileV1(json, visualItems, errorString);
814
    } else {
815
        return _loadJsonMissionFileV2(json, visualItems, errorString);
816 817 818
    }
}

819
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
820
{
821 822
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
823 824 825 826 827 828 829 830 831

    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;
832
            plannedHomePositionInFile = true;
833 834 835
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
836
            plannedHomePositionInFile = false;
837 838 839 840
        }
    }

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

845
        while (!stream.atEnd()) {
846
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
847 848

            if (item->load(stream)) {
849 850 851 852 853 854
                if (firstItem && plannedHomePositionInFile) {
                    settingsItem->setCoordinate(item->coordinate());
                } else {
                    visualItems->append(item);
                }
                firstItem = false;
855
            } else {
856
                errorString = tr("The mission file is corrupted.");
857 858 859 860
                return false;
            }
        }
    } else {
861
        errorString = tr("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
862 863 864
        return false;
    }

865
    if (!plannedHomePositionInFile) {
866 867 868
        // 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));
869
            if (item && item->command() == MAV_CMD_DO_JUMP) {
870
                item->missionItem().setParam1((int)item->missionItem().param1() + 1);
Don Gagne's avatar
Don Gagne committed
871 872
            }
        }
873 874 875
    }

    return true;
876 877
}

878
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
879
{
Don Gagne's avatar
Don Gagne committed
880 881 882
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
883
        _settingsItem = NULL;
Don Gagne's avatar
Don Gagne committed
884 885
    }

886
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
887 888

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

892
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
893

Don Gagne's avatar
Don Gagne committed
894
    _initAllVisualItems();
895
}
896

897 898 899 900 901 902
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

903
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928
        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;
929
    }
930

931 932 933 934 935 936 937 938 939 940 941 942 943
    _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);
944
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
945 946 947 948 949 950
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
951
    return true;
952 953
}

954 955 956 957 958 959 960 961 962 963 964 965
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;
}

966
void MissionController::save(QJsonObject& json)
967
{
968
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
969

970
    // Mission settings
971

972 973 974 975 976 977 978 979
    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;
980 981 982 983
    json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
984

985
    // Save the visual items
986

987 988 989
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
990

991 992
        visualItem->save(rgJsonMissionItems);
    }
993

994 995 996
    // Mission settings has a special case for end mission action
    if (settingsItem) {
        QList<MissionItem*> rgMissionItems;
997

998 999 1000 1001 1002
        if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
1003
        }
1004 1005
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
1006 1007 1008
        }
    }

1009
    json[_jsonItemsKey] = rgJsonMissionItems;
1010 1011
}

1012
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
1013
{
Don Gagne's avatar
Don Gagne committed
1014
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
1015
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
1016 1017 1018 1019
    bool            distanceOk =    false;

    // Convert to fixed altitudes

1020
    distanceOk = true;
1021
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
1022 1023
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
1024
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
1025
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
1026 1027 1028
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
1029 1030 1031
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
1032
    } else {
Don Gagne's avatar
Don Gagne committed
1033
        *altDifference = 0.0;
1034
        *azimuth = 0.0;
1035
        *distance = 0.0;
1036 1037 1038
    }
}

1039
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
1040 1041 1042 1043 1044 1045 1046
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

1047
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
1048 1049
}

1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071
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;
    }
}

1072 1073
void MissionController::_recalcWaypointLines(void)
{
1074 1075 1076
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

1077
    bool homePositionValid = _settingsItem->coordinate().isValid();
1078

1079
    qCDebug(MissionControllerLog) << "_recalcWaypointLines homePositionValid" << homePositionValid;
1080

Nate Weibley's avatar
Nate Weibley committed
1081 1082
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
1083
    _waypointLines.clear();
1084
    _waypointPath.clear();
1085

1086 1087 1088 1089 1090 1091 1092 1093 1094
    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;
1095 1096 1097
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));

1098 1099 1100 1101 1102 1103
        // 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;
1104
            }
1105 1106
        }

1107 1108 1109
        if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
            firstCoordinateItem = false;
            if (lastCoordinateItem != _settingsItem || (homePositionValid && linkStartToHome)) {
1110
                if (!_flyView) {
1111 1112
                    VisualItemPair pair(lastCoordinateItem, item);
                    _addWaypointLineSegment(old_table, pair);
1113 1114
                }
            }
1115 1116
            _waypointPath.append(QVariant::fromValue(item->coordinate()));
            lastCoordinateItem = item;
1117 1118
        }
    }
1119 1120 1121 1122 1123 1124

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

    if (linkEndToHome && lastCoordinateItem != _settingsItem && homePositionValid) {
1125
        if (!_flyView) {
1126 1127 1128 1129 1130
            VisualItemPair pair(lastCoordinateItem, _settingsItem);
            _addWaypointLineSegment(old_table, pair);
        } else {
            _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
        }
1131
    }
1132 1133 1134 1135

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1136 1137
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
1138 1139 1140 1141 1142 1143 1144 1145 1146 1147
            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
1148
    _recalcMissionFlightStatus();
1149

1150 1151 1152 1153 1154 1155 1156 1157
    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)));
    }

1158
    emit waypointLinesChanged();
1159
    emit waypointPathChanged();
1160 1161
}

1162 1163 1164 1165 1166 1167
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);
1168 1169 1170
        // 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.
1171
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194
            _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);
}

1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241
/// 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
1242
void MissionController::_recalcMissionFlightStatus()
1243
{
1244
    if (!_visualItems->count()) {
1245
        return;
1246
    }
1247 1248 1249 1250

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

1251
    bool showHomePosition = _settingsItem->coordinate().isValid();
1252

DonLakeFlyer's avatar
DonLakeFlyer committed
1253
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1254

1255 1256 1257
    // 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.
1258

1259
    // No values for first item
1260
    lastCoordinateItem->setAltDifference(0.0);
1261
    lastCoordinateItem->setAzimuth(0.0);
1262
    lastCoordinateItem->setDistance(0.0);
1263

1264 1265
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1266 1267
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1268

1269
    _resetMissionFlightStatus();
1270

DonLakeFlyer's avatar
DonLakeFlyer committed
1271
    bool vtolInHover = true;
1272
    bool linkStartToHome = false;
1273 1274 1275 1276 1277 1278 1279 1280 1281 1282
    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();
        }
    }
1283

DonLakeFlyer's avatar
DonLakeFlyer committed
1284
    for (int i=0; i<_visualItems->count(); i++) {
1285
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1286 1287 1288
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1289 1290
        // Assume the worst
        item->setAzimuth(0.0);
1291
        item->setDistance(0.0);
1292

DonLakeFlyer's avatar
DonLakeFlyer committed
1293 1294 1295
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1296
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1297
                _missionFlightStatus.hoverSpeed = newSpeed;
1298
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1299 1300
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1301
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1302
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1303
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1304 1305
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1306
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1307 1308 1309 1310
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1311 1312 1313 1314 1315 1316 1317
        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
1318 1319 1320 1321 1322
        }

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

1325
        // Link back to home if first item is takeoff and we have home position
1326
        if (firstCoordinateItem && simpleItem && (simpleItem->command() == MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
1327
            if (showHomePosition) {
1328
                linkStartToHome = true;
1329 1330 1331 1332 1333 1334 1335
                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);
                }
1336 1337 1338 1339
            }
        }

        // Update VTOL state
1340
        if (simpleItem && _controllerVehicle->vtol()) {
1341
            switch (simpleItem->command()) {
1342
            case MAV_CMD_NAV_TAKEOFF:
1343 1344
                vtolInHover = false;
                break;
1345
            case MAV_CMD_NAV_VTOL_TAKEOFF:
DonLakeFlyer's avatar
DonLakeFlyer committed
1346 1347
                vtolInHover = true;
                break;
1348
            case MAV_CMD_NAV_LAND:
1349 1350
                vtolInHover = false;
                break;
1351
            case MAV_CMD_NAV_VTOL_LAND:
DonLakeFlyer's avatar
DonLakeFlyer committed
1352 1353
                vtolInHover = true;
                break;
1354
            case MAV_CMD_DO_VTOL_TRANSITION:
1355 1356 1357 1358 1359 1360
            {
                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;
1361 1362
                }
            }
1363 1364 1365
                break;
            default:
                break;
1366
            }
Don Gagne's avatar
Don Gagne committed
1367 1368
        }

1369 1370 1371
        // Check for command specific time delays
        _addCommandTimeDelay(simpleItem, vtolInHover);

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

1375
            double absoluteAltitude = item->coordinate().altitude();
1376
            if (item->coordinateHasRelativeAltitude()) {
1377 1378 1379 1380 1381
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1382 1383 1384 1385
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1386 1387 1388
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1389
                firstCoordinateItem = false;
1390 1391 1392 1393 1394 1395 1396

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

1397
                if (lastCoordinateItem != _settingsItem || linkStartToHome) {
1398 1399
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1400

1401
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1402 1403 1404
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1405

1406
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1407

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

1414
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1415 1416
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1417
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1418

1419 1420
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1421 1422
                    double extraTime = complexItem->additionalTimeDelay();
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, extraTime, distance, item->sequenceNumber());
1423
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1424 1425

                item->setMissionFlightStatus(_missionFlightStatus);
1426

1427 1428
                lastCoordinateItem = item;
            }
1429 1430
        }
    }
1431
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1432

1433 1434 1435 1436 1437 1438 1439 1440
    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();
1441
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1442 1443
    }

1444 1445 1446
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1447

DonLakeFlyer's avatar
DonLakeFlyer committed
1448 1449 1450 1451 1452 1453 1454
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1455 1456
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1457

1458 1459
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1460 1461
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1462 1463 1464

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1465
            if (item->coordinateHasRelativeAltitude()) {
1466 1467 1468 1469
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1470
                item->setTerrainPercent(qQNaN());
1471 1472
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1473 1474 1475
                if (!qIsNaN(item->terrainAltitude())) {
                    item->setTerrainPercent((item->terrainAltitude() - minAltSeen) / altRange);
                }
1476
            }
1477 1478 1479 1480
        }
    }
}

1481 1482 1483
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1484 1485 1486 1487 1488 1489
    // 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));

1490 1491
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1492 1493 1494
    }
}

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

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

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

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

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

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

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


1532 1533
void MissionController::_recalcAll(void)
{
1534
    if (!_flyView) {
1535 1536
        _setPlannedHomePositionFromFirstCoordinate();
    }
1537
    _recalcSequence();
1538 1539 1540 1541
    _recalcChildItems();
    _recalcWaypointLines();
}

1542
/// Initializes a new set of mission items
1543
void MissionController::_initAllVisualItems(void)
1544
{
1545 1546
    // Setup home position at index 0

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

1556
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1557
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1558
    }
1559

1560 1561 1562
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1563

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

1569
    _recalcAll();
1570

1571
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1572 1573 1574
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1575
    emit containsItemsChanged(containsItems());
1576
    emit plannedHomePositionChanged(plannedHomePosition());
1577

1578
    setDirty(false);
1579 1580
}

1581
void MissionController::_deinitAllVisualItems(void)
1582
{
1583 1584 1585
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1586 1587
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1588 1589
    }

1590
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1591
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1592 1593
}

1594
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1595
{
1596
    setDirty(false);
1597

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

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

1627
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1628
{
1629 1630
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1631 1632
}

1633
void MissionController::_itemCommandChanged(void)
1634
{
1635 1636
    _recalcChildItems();
    _recalcWaypointLines();
1637 1638
}

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

1648 1649
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1650
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1651 1652
        return;
    }
1653

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

1669 1670
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1671
    }
1672

1673
    emit complexMissionItemNamesChanged();
1674
    emit resumeMissionIndexChanged();
1675 1676
}

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

void MissionController::_inProgressChanged(bool inProgress)
1693
{
1694
    emit syncInProgressChanged(inProgress);
1695
}
1696

1697
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1698
{
1699 1700
    bool        found = false;
    double      foundAltitude;
1701
    int         foundAltitudeMode;
1702

1703 1704 1705 1706 1707 1708
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

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

1724
    if (found) {
1725
        *prevAltitude = foundAltitude;
1726
        *prevAltitudeMode = foundAltitudeMode;
1727 1728 1729
    }

    return found;
1730
}
1731 1732 1733 1734 1735 1736 1737 1738 1739 1740 1741 1742 1743

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

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

Don Gagne's avatar
Don Gagne committed
1749 1750
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1751
    visualItems->insert(0, settingsItem);
1752

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

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

1790
int MissionController::resumeMissionIndex(void) const
1791
{
1792

1793
    int resumeIndex = 0;
1794

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

    return resumeIndex;
}
1807

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

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

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

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

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1851
    }
1852
}
1853

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

1859 1860 1861 1862 1863 1864
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

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

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

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

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

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

    return complexItems;
}
1922

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

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

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

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

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
1963 1964 1965

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

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

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

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