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


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

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

38 39
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

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

const int   MissionController::_missionFileVersion =            2;
55

56
MissionController::MissionController(PlanMasterController* masterController, QObject *parent)
57 58 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 216 217 218 219 220 221 222 223 224 225
void MissionController::_warnIfTerrainFrameUsed(void)
{
    for (int i=1; i<_visualItems->count(); i++) {
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(i));
        if (simpleItem && simpleItem->altitudeMode() == SimpleMissionItem::AltitudeTerrainFrame) {
            qgcApp()->showMessage(tr("Warning: You are using MAV_FRAME_GLOBAL_TERRAIN_ALT in a mission. %1 does not support sending terrain tiles to vehicle.").arg(qgcApp()->applicationName()));
            break;
        }
    }
}

226
void MissionController::sendToVehicle(void)
227
{
DonLakeFlyer's avatar
DonLakeFlyer committed
228 229 230 231 232
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::sendToVehicle called while offline";
    } else if (syncInProgress()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::sendToVehicle called while syncInProgress";
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
233
        qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
234
        _warnIfTerrainFrameUsed();
DonLakeFlyer's avatar
DonLakeFlyer committed
235 236 237 238 239 240 241 242 243
        if (_visualItems->count() == 1) {
            // This prevents us from sending a possibly bogus home position to the vehicle
            QmlObjectListModel emptyModel;
            sendItemsToVehicle(_managerVehicle, &emptyModel);
        } else {
            sendItemsToVehicle(_managerVehicle, _visualItems);
        }
        setDirty(false);
    }
Don Gagne's avatar
Don Gagne committed
244 245
}

246 247 248 249 250
/// Converts from visual items to MissionItems
///     @param missionItemParent QObject parent for newly allocated MissionItems
/// @return true: Mission end action was added to end of list
bool MissionController::_convertToMissionItems(QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
251 252 253 254
    if (visualMissionItems->count() == 0) {
        return false;
    }

255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270
    bool endActionSet = false;
    int lastSeqNum = 0;

    for (int i=0; i<visualMissionItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(visualMissionItems->get(i));

        lastSeqNum = visualItem->lastSequenceNumber();
        visualItem->appendMissionItems(rgMissionItems, missionItemParent);

        qCDebug(MissionControllerLog) << "_convertToMissionItems seqNum:lastSeqNum:command"
                                      << visualItem->sequenceNumber()
                                      << lastSeqNum
                                      << visualItem->commandName();
    }

    // Mission settings has a special case for end mission action
271
    MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
272 273 274 275 276 277 278
    if (settingsItem) {
        endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
    }

    return endActionSet;
}

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

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

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

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

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

    deleteParent->deleteLater();

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

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

326
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
327

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

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

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

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

    _recalcAll();

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

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

388 389
    double  prevAltitude;
    int     prevAltitudeMode;
390

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

    _recalcAll();

    return newItem->sequenceNumber();
}

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

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

421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446
    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);

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

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

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

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

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

473 474
    complexItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(complexItem);
475

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

    _recalcAll();

484
    return complexItem->sequenceNumber();
485 486
}

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

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

497
    _deinitVisualItem(item);
498
    item->deleteLater();
499

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

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

528
    _recalcAll();
529
    setDirty(true);
530 531
}

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

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

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

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

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

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

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

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

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

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

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

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

    return true;
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

    return true;
889 890
}

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

899
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
900 901

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

905
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
906

Don Gagne's avatar
Don Gagne committed
907
    _initAllVisualItems();
908
}
909

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

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

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

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
964
    return true;
965 966
}

967 968 969 970 971 972 973 974 975 976 977 978
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;
}

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

983
    // Mission settings
984

985 986 987 988 989 990 991 992
    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;
993 994 995 996
    json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
997

998
    // Save the visual items
999

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

1004 1005
        visualItem->save(rgJsonMissionItems);
    }
1006

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

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

1022
    json[_jsonItemsKey] = rgJsonMissionItems;
1023 1024
}

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

    // Convert to fixed altitudes

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

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

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

    distanceOk = true;

1060
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
1061 1062
}

1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084
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;
    }
}

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

1090
    bool homePositionValid = _settingsItem->coordinate().isValid();
1091

1092
    qCDebug(MissionControllerLog) << "_recalcWaypointLines homePositionValid" << homePositionValid;
1093

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

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

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

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

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

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

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1149 1150
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
1151 1152 1153 1154 1155 1156 1157 1158 1159 1160
            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
1161
    _recalcMissionFlightStatus();
1162

1163 1164 1165 1166 1167 1168 1169 1170
    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)));
    }

1171
    emit waypointLinesChanged();
1172
    emit waypointPathChanged();
1173 1174
}

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

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 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254
/// 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
1255
void MissionController::_recalcMissionFlightStatus()
1256
{
1257
    if (!_visualItems->count()) {
1258
        return;
1259
    }
1260 1261 1262 1263

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

1264
    bool showHomePosition = _settingsItem->coordinate().isValid();
1265

DonLakeFlyer's avatar
DonLakeFlyer committed
1266
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1267

1268 1269 1270
    // 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.
1271

1272
    // No values for first item
1273
    lastCoordinateItem->setAltDifference(0.0);
1274
    lastCoordinateItem->setAzimuth(0.0);
1275
    lastCoordinateItem->setDistance(0.0);
1276

1277 1278
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1279 1280
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1281

1282
    _resetMissionFlightStatus();
1283

DonLakeFlyer's avatar
DonLakeFlyer committed
1284
    bool vtolInHover = true;
1285
    bool linkStartToHome = false;
1286 1287 1288 1289 1290 1291 1292 1293 1294 1295
    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();
        }
    }
1296

DonLakeFlyer's avatar
DonLakeFlyer committed
1297
    for (int i=0; i<_visualItems->count(); i++) {
1298
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1299 1300 1301
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1302 1303
        // Assume the worst
        item->setAzimuth(0.0);
1304
        item->setDistance(0.0);
1305

DonLakeFlyer's avatar
DonLakeFlyer committed
1306 1307 1308
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1309
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1310
                _missionFlightStatus.hoverSpeed = newSpeed;
1311
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1312 1313
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1314
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1315
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1316
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1317 1318
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1319
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1320 1321 1322 1323
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1324 1325 1326 1327 1328 1329 1330
        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
1331 1332 1333 1334 1335
        }

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

1338
        // Link back to home if first item is takeoff and we have home position
1339
        if (firstCoordinateItem && simpleItem && (simpleItem->command() == MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
1340
            if (showHomePosition) {
1341
                linkStartToHome = true;
1342 1343 1344 1345 1346 1347 1348
                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);
                }
1349 1350 1351 1352
            }
        }

        // Update VTOL state
1353
        if (simpleItem && _controllerVehicle->vtol()) {
1354
            switch (simpleItem->command()) {
1355
            case MAV_CMD_NAV_TAKEOFF:
1356 1357
                vtolInHover = false;
                break;
1358
            case MAV_CMD_NAV_VTOL_TAKEOFF:
DonLakeFlyer's avatar
DonLakeFlyer committed
1359 1360
                vtolInHover = true;
                break;
1361
            case MAV_CMD_NAV_LAND:
1362 1363
                vtolInHover = false;
                break;
1364
            case MAV_CMD_NAV_VTOL_LAND:
DonLakeFlyer's avatar
DonLakeFlyer committed
1365 1366
                vtolInHover = true;
                break;
1367
            case MAV_CMD_DO_VTOL_TRANSITION:
1368 1369 1370 1371 1372 1373
            {
                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;
1374 1375
                }
            }
1376 1377 1378
                break;
            default:
                break;
1379
            }
Don Gagne's avatar
Don Gagne committed
1380 1381
        }

1382 1383 1384
        // Check for command specific time delays
        _addCommandTimeDelay(simpleItem, vtolInHover);

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

1388
            double absoluteAltitude = item->coordinate().altitude();
1389
            if (item->coordinateHasRelativeAltitude()) {
1390 1391 1392 1393 1394
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1395 1396 1397 1398
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1399 1400 1401
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1402
                firstCoordinateItem = false;
1403 1404 1405 1406 1407 1408 1409

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

1410
                if (lastCoordinateItem != _settingsItem || linkStartToHome) {
1411 1412
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1413

1414
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1415 1416 1417
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1418

1419
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1420

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

1427
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1428 1429
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1430
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1431

1432 1433
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1434 1435
                    double extraTime = complexItem->additionalTimeDelay();
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, extraTime, distance, item->sequenceNumber());
1436
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1437 1438

                item->setMissionFlightStatus(_missionFlightStatus);
1439

1440 1441
                lastCoordinateItem = item;
            }
1442 1443
        }
    }
1444
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1445

1446 1447 1448 1449 1450 1451 1452 1453
    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();
1454
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1455 1456
    }

1457 1458 1459
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1460

DonLakeFlyer's avatar
DonLakeFlyer committed
1461 1462 1463 1464 1465 1466 1467
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1468 1469
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1470

1471 1472
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1473 1474
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1475 1476 1477

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1478
            if (item->coordinateHasRelativeAltitude()) {
1479 1480 1481 1482
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1483
                item->setTerrainPercent(qQNaN());
1484 1485
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1486 1487 1488
                if (!qIsNaN(item->terrainAltitude())) {
                    item->setTerrainPercent((item->terrainAltitude() - minAltSeen) / altRange);
                }
1489
            }
1490 1491 1492 1493
        }
    }
}

1494 1495 1496
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1497 1498 1499 1500 1501
    if (_inRecalcSequence) {
        // Don't let this call recurse due to signalling
        return;
    }

1502 1503
    // Setup ascending sequence numbers for all visual items

1504
    _inRecalcSequence = true;
1505 1506 1507
    int sequenceNumber = 0;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1508 1509
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1510 1511
    }    
    _inRecalcSequence = false;
1512 1513
}

1514 1515 1516
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1517
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1518 1519 1520

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

1521 1522
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1523 1524 1525 1526 1527

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1528
        } else if (item->isSimpleItem()) {
1529 1530 1531 1532 1533
            currentParentItem->childItems()->append(item);
        }
    }
}

1534 1535 1536 1537 1538 1539
void MissionController::_setPlannedHomePositionFromFirstCoordinate(void)
{
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1540
    // Set the planned home position to be a delta from first coordinate
1541 1542 1543 1544 1545 1546 1547 1548 1549 1550
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

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


1551 1552
void MissionController::_recalcAll(void)
{
1553
    if (!_flyView) {
1554 1555
        _setPlannedHomePositionFromFirstCoordinate();
    }
1556
    _recalcSequence();
1557 1558 1559 1560
    _recalcChildItems();
    _recalcWaypointLines();
}

1561
/// Initializes a new set of mission items
1562
void MissionController::_initAllVisualItems(void)
1563
{
1564 1565
    // Setup home position at index 0

1566 1567 1568
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1569 1570
        return;
    }
1571
    if (!_flyView) {
1572 1573
        _settingsItem->setIsCurrentItem(true);
    }
1574

1575
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1576
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1577
    }
1578

1579 1580 1581
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1582

1583 1584 1585 1586
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1587

1588
    _recalcAll();
1589

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

    emit visualItemsChanged();
1594
    emit containsItemsChanged(containsItems());
1595
    emit plannedHomePositionChanged(plannedHomePosition());
1596

1597
    setDirty(false);
1598 1599
}

1600
void MissionController::_deinitAllVisualItems(void)
1601
{
1602 1603 1604
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1605 1606
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1607 1608
    }

1609
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1610
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1611 1612
}

1613
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1614
{
1615
    setDirty(false);
1616

1617
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1618 1619
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1620 1621
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1622
    connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged,                this, &MissionController::_recalcMissionFlightStatus);
1623
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1624
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1625

1626 1627 1628 1629 1630 1631 1632 1633
    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";
        }
1634 1635
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1636
        if (complexItem) {
1637
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
1638
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
1639
            connect(complexItem, &ComplexMissionItem::additionalTimeDelayChanged,   this, &MissionController::_recalcMissionFlightStatus);
1640 1641 1642
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1643
    }
1644 1645
}

1646
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1647
{
1648 1649
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1650 1651
}

1652
void MissionController::_itemCommandChanged(void)
1653
{
1654 1655
    _recalcChildItems();
    _recalcWaypointLines();
1656 1657
}

1658
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1659
{
1660 1661 1662 1663 1664 1665
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1666

1667 1668
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1669
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1670 1671
        return;
    }
1672

1673 1674
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1675 1676
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1677 1678 1679 1680 1681
    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);
1682
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1683 1684 1685 1686
    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);
1687

1688 1689
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1690
    }
1691

1692
    emit complexMissionItemNamesChanged();
1693
    emit resumeMissionIndexChanged();
1694 1695
}

1696
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1697
{
1698 1699
    if (_visualItems) {
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1700
        if (settingsItem) {
1701
            settingsItem->setHomePositionFromVehicle(homePosition);
1702
        } else {
1703
            qWarning() << "First item is not MissionSettingsItem";
1704
        }
1705 1706 1707
        // Don't let this trip the dirty bit. Otherwise plan will keep getting marked dirty if vehicle home
        // changes.
        _visualItems->setDirty(false);
1708
    }
1709 1710 1711
}

void MissionController::_inProgressChanged(bool inProgress)
1712
{
1713
    emit syncInProgressChanged(inProgress);
1714
}
1715

1716
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1717
{
1718 1719
    bool        found = false;
    double      foundAltitude;
1720
    int         foundAltitudeMode;
1721

1722 1723 1724 1725 1726 1727
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1730 1731 1732
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1733 1734 1735
                if (simpleItem->specifiesAltitude()) {
                    foundAltitude = simpleItem->altitude()->rawValue().toDouble();
                    foundAltitudeMode = simpleItem->altitudeMode();
1736
                    found = true;
1737
                    break;
1738 1739
                }
            }
1740 1741 1742
        }
    }

1743
    if (found) {
1744
        *prevAltitude = foundAltitude;
1745
        *prevAltitudeMode = foundAltitudeMode;
1746 1747 1748
    }

    return found;
1749
}
1750 1751 1752 1753 1754 1755 1756 1757 1758 1759 1760 1761 1762

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

1763
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1764
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1765
{
1766
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
1767

Don Gagne's avatar
Don Gagne committed
1768 1769
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1770
    visualItems->insert(0, settingsItem);
1771

1772 1773 1774 1775 1776 1777 1778 1779 1780 1781 1782 1783 1784 1785 1786 1787 1788 1789 1790 1791 1792 1793 1794 1795 1796
    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;
                    }
1797 1798
                }
            }
1799

1800 1801 1802
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1803
        }
Don Gagne's avatar
Don Gagne committed
1804 1805
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1806 1807
    }
}
1808

1809
int MissionController::resumeMissionIndex(void) const
1810
{
1811

1812
    int resumeIndex = 0;
1813

1814
    if (_flyView) {
1815
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1816
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1817 1818
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1819 1820
        } else {
            resumeIndex = 0;
1821 1822 1823 1824 1825
        }
    }

    return resumeIndex;
}
1826

1827 1828
int MissionController::currentMissionIndex(void) const
{
1829
    if (!_flyView) {
1830 1831 1832 1833 1834 1835 1836 1837 1838 1839
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

1840
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1841
{
1842
    if (_flyView) {
1843
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1844 1845 1846
            sequenceNumber++;
        }

1847 1848
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1849 1850
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1851
        emit currentMissionIndexChanged(currentMissionIndex());
1852 1853
    }
}
1854

1855
bool MissionController::syncInProgress(void) const
1856
{
1857
    return _missionManager->inProgress();
1858 1859 1860 1861 1862 1863 1864 1865 1866 1867 1868 1869
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1870
    }
1871
}
1872

1873 1874
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1875 1876
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, vehicle);
1877

1878 1879 1880 1881 1882 1883
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1884
        if (!_flyView) {
1885 1886 1887 1888 1889 1890
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
1891 1892 1893
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1894
        if (simpleItem) {
1895 1896 1897 1898 1899
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
1900 1901 1902
        }
    }
}
1903 1904 1905 1906 1907 1908 1909 1910 1911 1912 1913 1914 1915

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
1916 1917 1918 1919 1920 1921 1922 1923
    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();
    }
1924
}
1925 1926 1927 1928 1929 1930

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

    complexItems.append(_surveyMissionItemName);
1931
    complexItems.append(_corridorScanMissionItemName);
1932
    if (_controllerVehicle->fixedWing()) {
1933 1934
        complexItems.append(_fwLandingMissionItemName);
    }
1935 1936 1937
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
        complexItems.append(_structureScanMissionItemName);
    }
1938 1939 1940

    return complexItems;
}
1941

1942 1943
void MissionController::resumeMission(int resumeIndex)
{
1944
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1945 1946
        resumeIndex--;
    }
1947
    _missionManager->generateResumeMission(resumeIndex);
1948
}
1949 1950 1951 1952 1953 1954 1955 1956 1957

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1958 1959 1960 1961 1962 1963 1964 1965 1966 1967

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

1969 1970 1971 1972 1973 1974 1975
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
1976 1977 1978 1979 1980 1981

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
1982 1983 1984

bool MissionController::showPlanFromManagerVehicle (void)
{
1985
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
DonLakeFlyer's avatar
DonLakeFlyer committed
1986 1987
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
1988
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
1989 1990 1991 1992 1993 1994 1995 1996 1997 1998 1999 2000 2001 2002 2003 2004 2005 2006 2007
    } 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;
        }
    }
}

2008
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2009
{
2010
    // Fly view always reloads on send complete
2011
    if (!error && _flyView) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2012 2013 2014 2015
        showPlanFromManagerVehicle();
    }
}

2016
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2017
{
2018 2019 2020 2021
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2022
}
2023 2024 2025 2026 2027 2028 2029 2030 2031 2032 2033 2034 2035 2036 2037 2038 2039 2040 2041 2042 2043 2044 2045 2046 2047 2048 2049 2050 2051 2052

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