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


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

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

38 39
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

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

const int   MissionController::_missionFileVersion =            2;
55

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

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

80 81
}

82 83 84 85 86 87 88 89 90
void MissionController::_resetMissionFlightStatus(void)
{
    _missionFlightStatus.totalDistance =        0.0;
    _missionFlightStatus.maxTelemetryDistance = 0.0;
    _missionFlightStatus.totalTime =            0.0;
    _missionFlightStatus.hoverTime =            0.0;
    _missionFlightStatus.cruiseTime =           0.0;
    _missionFlightStatus.hoverDistance =        0.0;
    _missionFlightStatus.cruiseDistance =       0.0;
91 92 93
    _missionFlightStatus.cruiseSpeed =          _controllerVehicle->defaultCruiseSpeed();
    _missionFlightStatus.hoverSpeed =           _controllerVehicle->defaultHoverSpeed();
    _missionFlightStatus.vehicleSpeed =         _controllerVehicle->multiRotor() || _managerVehicle->vtol() ? _missionFlightStatus.hoverSpeed : _missionFlightStatus.cruiseSpeed;
94
    _missionFlightStatus.vehicleYaw =           0.0;
95
    _missionFlightStatus.gimbalYaw =            std::numeric_limits<double>::quiet_NaN();
96
    _missionFlightStatus.gimbalPitch =          std::numeric_limits<double>::quiet_NaN();
97 98 99 100 101 102 103 104 105 106 107 108

    // Battery information

    _missionFlightStatus.mAhBattery =           0;
    _missionFlightStatus.hoverAmps =            0;
    _missionFlightStatus.cruiseAmps =           0;
    _missionFlightStatus.ampMinutesAvailable =  0;
    _missionFlightStatus.hoverAmpsTotal =       0;
    _missionFlightStatus.cruiseAmpsTotal =      0;
    _missionFlightStatus.batteryChangePoint =   -1;
    _missionFlightStatus.batteriesRequired =    -1;

109 110 111 112
    _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);
113
    }
114 115 116 117 118 119 120 121 122 123 124

    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionTimeChanged();
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);

125 126
}

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

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

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

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

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

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

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

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

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

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

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

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

203
void MissionController::loadFromVehicle(void)
204
{
DonLakeFlyer's avatar
DonLakeFlyer committed
205 206 207 208 209 210 211 212
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::loadFromVehicle called while offline";
    } else if (syncInProgress()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::loadFromVehicle called while syncInProgress";
    } else {
        _itemsRequested = true;
        _managerVehicle->missionManager()->loadFromVehicle();
    }
213 214
}

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

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

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

    return endActionSet;
}

267 268
void MissionController::convertToKMLDocument(QDomDocument& document)
{
269 270 271 272 273
    QObject*            deleteParent = new QObject();
    QList<MissionItem*> rgMissionItems;

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

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

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

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

    deleteParent->deleteLater();

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

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

314
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
315

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

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

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

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

    _recalcAll();

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

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

376 377
    double  prevAltitude;
    int     prevAltitudeMode;
378

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

    _recalcAll();

    return newItem->sequenceNumber();
}

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

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

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

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

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

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

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

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

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

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

    _recalcAll();

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

    return true;
}

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

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

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

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

666 667 668 669
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
670
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
671 672
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
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 698
    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) {
699
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
700
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
701
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
702
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
703 704 705 706 707 708 709 710 711 712 713 714 715
                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();

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

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

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

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

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

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

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

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

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

    return true;
877 878
}

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

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

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

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

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

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

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

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

    _initLoadedVisualItems(loadedVisualItems);

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

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

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

971
    // Mission settings
972

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

986
    // Save the visual items
987

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

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

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

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

1010
    json[_jsonItemsKey] = rgJsonMissionItems;
1011 1012
}

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

    // Convert to fixed altitudes

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

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

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

    distanceOk = true;

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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 1242
/// 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
1243
void MissionController::_recalcMissionFlightStatus()
1244
{
1245
    if (!_visualItems->count()) {
1246
        return;
1247
    }
1248 1249 1250 1251

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

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

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

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

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

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

1270
    _resetMissionFlightStatus();
1271

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

                item->setMissionFlightStatus(_missionFlightStatus);
1427

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

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

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

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

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

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

1482 1483 1484
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1485 1486 1487 1488 1489
    if (_inRecalcSequence) {
        // Don't let this call recurse due to signalling
        return;
    }

1490 1491
    // Setup ascending sequence numbers for all visual items

1492
    _inRecalcSequence = true;
1493 1494 1495
    int sequenceNumber = 0;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1496 1497
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1498 1499
    }    
    _inRecalcSequence = false;
1500 1501
}

1502 1503 1504
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1505
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1506 1507 1508

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

1509 1510
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1511 1512 1513 1514 1515

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1516
        } else if (item->isSimpleItem()) {
1517 1518 1519 1520 1521
            currentParentItem->childItems()->append(item);
        }
    }
}

1522 1523 1524 1525 1526 1527
void MissionController::_setPlannedHomePositionFromFirstCoordinate(void)
{
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1528
    // Set the planned home position to be a delta from first coordinate
1529 1530 1531 1532 1533 1534 1535 1536 1537 1538
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

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


1539 1540
void MissionController::_recalcAll(void)
{
1541
    if (!_flyView) {
1542 1543
        _setPlannedHomePositionFromFirstCoordinate();
    }
1544
    _recalcSequence();
1545 1546 1547 1548
    _recalcChildItems();
    _recalcWaypointLines();
}

1549
/// Initializes a new set of mission items
1550
void MissionController::_initAllVisualItems(void)
1551
{
1552 1553
    // Setup home position at index 0

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

1563
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1564
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1565
    }
1566

1567 1568 1569
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1570

1571 1572 1573 1574
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1575

1576
    _recalcAll();
1577

1578
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1579 1580 1581
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1582
    emit containsItemsChanged(containsItems());
1583
    emit plannedHomePositionChanged(plannedHomePosition());
1584

1585
    setDirty(false);
1586 1587
}

1588
void MissionController::_deinitAllVisualItems(void)
1589
{
1590 1591 1592
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1593 1594
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1595 1596
    }

1597
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1598
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1599 1600
}

1601
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1602
{
1603
    setDirty(false);
1604

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

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

1634
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1635
{
1636 1637
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1638 1639
}

1640
void MissionController::_itemCommandChanged(void)
1641
{
1642 1643
    _recalcChildItems();
    _recalcWaypointLines();
1644 1645
}

1646
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1647
{
1648 1649 1650 1651 1652 1653
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1654

1655 1656
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1657
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1658 1659
        return;
    }
1660

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

1676 1677
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1678
    }
1679

1680
    emit complexMissionItemNamesChanged();
1681
    emit resumeMissionIndexChanged();
1682 1683
}

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

void MissionController::_inProgressChanged(bool inProgress)
1700
{
1701
    emit syncInProgressChanged(inProgress);
1702
}
1703

1704
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1705
{
1706 1707
    bool        found = false;
    double      foundAltitude;
1708
    int         foundAltitudeMode;
1709

1710 1711 1712 1713 1714 1715
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

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

1731
    if (found) {
1732
        *prevAltitude = foundAltitude;
1733
        *prevAltitudeMode = foundAltitudeMode;
1734 1735 1736
    }

    return found;
1737
}
1738 1739 1740 1741 1742 1743 1744 1745 1746 1747 1748 1749 1750

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

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

Don Gagne's avatar
Don Gagne committed
1756 1757
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1758
    visualItems->insert(0, settingsItem);
1759

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

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

1797
int MissionController::resumeMissionIndex(void) const
1798
{
1799

1800
    int resumeIndex = 0;
1801

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

    return resumeIndex;
}
1814

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

1828
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1829
{
1830
    if (_flyView) {
1831
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1832 1833 1834
            sequenceNumber++;
        }

1835 1836
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1837 1838
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1839
        emit currentMissionIndexChanged(currentMissionIndex());
1840 1841
    }
}
1842

1843
bool MissionController::syncInProgress(void) const
1844
{
1845
    return _missionManager->inProgress();
1846 1847 1848 1849 1850 1851 1852 1853 1854 1855 1856 1857
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1858
    }
1859
}
1860

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

1866 1867 1868 1869 1870 1871
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1872
        if (!_flyView) {
1873 1874 1875 1876 1877 1878
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
1879 1880 1881
        }

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

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
1904 1905 1906 1907 1908 1909 1910 1911
    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();
    }
1912
}
1913 1914 1915 1916 1917 1918

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

    complexItems.append(_surveyMissionItemName);
1919
    complexItems.append(_corridorScanMissionItemName);
1920
    if (_controllerVehicle->fixedWing()) {
1921 1922
        complexItems.append(_fwLandingMissionItemName);
    }
1923 1924 1925
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
        complexItems.append(_structureScanMissionItemName);
    }
1926 1927 1928

    return complexItems;
}
1929

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

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1946 1947 1948 1949 1950 1951 1952 1953 1954 1955

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

1957 1958 1959 1960 1961 1962 1963
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
1964 1965 1966 1967 1968 1969

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
1970 1971 1972

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

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

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

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