MissionController.cc 84.5 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
    : PlanElementController         (masterController, parent)
    , _missionManager               (_managerVehicle->missionManager())
59 60 61
    , _missionItemCount             (0)
    , _visualItems                  (nullptr)
    , _settingsItem                 (nullptr)
62 63 64 65 66 67 68 69 70 71
    , _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)
72
    , _currentPlanViewItem          (nullptr)
73
{
74
    _resetMissionFlightStatus();
75
    managerVehicleChanged(_managerVehicle);
76 77 78 79
}

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

81 82
}

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

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

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

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

126 127
}

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

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

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

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

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

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

163 164 165
        _missionItemCount = newMissionItems.count();
        emit missionItemCountChanged(_missionItemCount);

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

182 183
        for (; i<newMissionItems.count(); i++) {
            const MissionItem* missionItem = newMissionItems[i];
184
            newControllerMissionItems->append(new SimpleMissionItem(_controllerVehicle, _flyView, *missionItem, this));
185 186 187
        }

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

194
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
195
            _addMissionSettings(_visualItems, !_flyView && _visualItems->count() > 0 /* addToCenter */);
196 197
        }

198
        MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
199

200
        _initAllVisualItems();
201
        _updateContainsItems();
202
        emit newItemsFromVehicle();
203
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
204
    _itemsRequested = false;
205 206
}

207
void MissionController::loadFromVehicle(void)
208
{
DonLakeFlyer's avatar
DonLakeFlyer committed
209 210 211 212 213 214 215 216
    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();
    }
217 218
}

219 220 221 222 223 224 225 226 227 228 229
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;
        }
    }
}

230
void MissionController::sendToVehicle(void)
231
{
DonLakeFlyer's avatar
DonLakeFlyer committed
232 233 234 235 236
    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
237
        qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
238
        _warnIfTerrainFrameUsed();
DonLakeFlyer's avatar
DonLakeFlyer committed
239 240 241 242 243 244 245 246 247
        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
248 249
}

250 251 252 253 254
/// 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
255 256 257 258
    if (visualMissionItems->count() == 0) {
        return false;
    }

259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274
    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
275
    MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
276 277 278 279 280 281 282
    if (settingsItem) {
        endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
    }

    return endActionSet;
}

283 284
void MissionController::convertToKMLDocument(QDomDocument& document)
{
285 286 287 288 289
    QObject*            deleteParent = new QObject();
    QList<MissionItem*> rgMissionItems;

    _convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
    if (rgMissionItems.count() == 0) {
290 291
        return;
    }
292

293
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
294 295 296 297 298

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

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

    deleteParent->deleteLater();

320 321 322 323 324
    Kml kml;
    kml.points(coords);
    kml.save(document);
}

Don Gagne's avatar
Don Gagne committed
325 326 327
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
328
        QList<MissionItem*> rgMissionItems;
329

330
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
331

332
        // PlanManager takes control of MissionItems so no need to delete
333
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
334 335
    }
}
336

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

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

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

374 375
    // We send the click coordinate through here to be able to set the planned home position from the user click location if needed
    _recalcAllWithClickCoordinate(coordinate);
376

377
    return newItem->sequenceNumber();
378 379
}

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

391 392
    double  prevAltitude;
    int     prevAltitudeMode;
393

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

    _recalcAll();

    return newItem->sequenceNumber();
}

405
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
406
{
407 408
    ComplexMissionItem* newItem;

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

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

450
    if (surveyStyleItem) {
451 452 453
        bool rollSupported = false;
        bool pitchSupported = false;
        bool yawSupported = false;
454 455 456

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

457 458
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
        CameraSection* cameraSection = settingsItem->cameraSection();
459

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

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

476 477
    complexItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(complexItem);
478

479 480 481 482 483
    if (i == -1) {
        _visualItems->append(complexItem);
    } else {
        _visualItems->insert(i, complexItem);
    }
484 485 486

    _recalcAll();

487
    return complexItem->sequenceNumber();
488 489
}

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

497
    bool removeSurveyStyle = _visualItems->value<SurveyComplexItem*>(index) || _visualItems->value<CorridorScanComplexItem*>(index);
498
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
499

500
    _deinitVisualItem(item);
501
    item->deleteLater();
502

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

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

531
    _recalcAll();
532
    setDirty(true);
533 534
}

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

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

563
    // Read complex items
564
    QList<SurveyComplexItem*> surveyItems;
565 566 567 568
    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];
569

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

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

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

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

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

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

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

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

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

    return true;
}

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

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

664
    // Mission Settings
665
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
666

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

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

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

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

    if (fileVersion == 1) {
829
        return _loadJsonMissionFileV1(json, visualItems, errorString);
830
    } else {
831
        return _loadJsonMissionFileV2(json, visualItems, errorString);
832 833 834
    }
}

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

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

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

861
        while (!stream.atEnd()) {
862
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
863 864

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

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

    return true;
892 893
}

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

902
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
903 904

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

908
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
909

Don Gagne's avatar
Don Gagne committed
910
    _initAllVisualItems();
911
}
912

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

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

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

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
967
    return true;
968 969
}

970 971 972 973 974 975 976 977 978 979 980 981
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;
}

982
void MissionController::save(QJsonObject& json)
983
{
984
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
985

986
    // Mission settings
987

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

1001
    // Save the visual items
1002

1003 1004 1005
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1006

1007 1008
        visualItem->save(rgJsonMissionItems);
    }
1009

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

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

1025
    json[_jsonItemsKey] = rgJsonMissionItems;
1026 1027
}

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

    // Convert to fixed altitudes

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

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

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

    distanceOk = true;

1063
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
1064 1065
}

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

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

1093
    bool homePositionValid = _settingsItem->coordinate().isValid();
1094

1095
    qCDebug(MissionControllerLog) << "_recalcWaypointLines homePositionValid" << homePositionValid;
1096

Nate Weibley's avatar
Nate Weibley committed
1097 1098
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
1099
    _waypointLines.clear();
1100
    _waypointPath.clear();
1101

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

1114 1115 1116 1117 1118 1119
        // 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;
1120
            }
1121 1122
        }

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

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

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

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

1166 1167 1168 1169 1170 1171 1172 1173
    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)));
    }

1174
    emit waypointLinesChanged();
1175
    emit waypointPathChanged();
1176 1177
}

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

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
/// 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
1238
void MissionController::_recalcMissionFlightStatus()
1239
{
1240
    if (!_visualItems->count()) {
1241
        return;
1242
    }
1243 1244 1245 1246

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

1247
    bool showHomePosition = _settingsItem->coordinate().isValid();
1248

DonLakeFlyer's avatar
DonLakeFlyer committed
1249
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1250

1251 1252 1253
    // 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.
1254

1255
    // No values for first item
1256
    lastCoordinateItem->setAltDifference(0.0);
1257
    lastCoordinateItem->setAzimuth(0.0);
1258
    lastCoordinateItem->setDistance(0.0);
1259

1260 1261
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1262 1263
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1264

1265
    _resetMissionFlightStatus();
1266

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1280
    for (int i=0; i<_visualItems->count(); i++) {
1281
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1282 1283 1284
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1285 1286
        // Assume the worst
        item->setAzimuth(0.0);
1287
        item->setDistance(0.0);
1288

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

        // Look for gimbal change
1307 1308 1309 1310 1311 1312 1313
        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
1314 1315 1316 1317 1318
        }

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

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

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

1365
        _addTimeDistance(vtolInHover, 0, 0, item->additionalTimeDelay(), 0, -1);
1366

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

1370
            double absoluteAltitude = item->coordinate().altitude();
1371
            if (item->coordinateHasRelativeAltitude()) {
1372 1373 1374 1375 1376
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1377 1378 1379 1380
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1381 1382 1383
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1384
                firstCoordinateItem = false;
1385 1386 1387 1388 1389 1390 1391

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

1392
                if (lastCoordinateItem != _settingsItem || linkStartToHome) {
1393 1394
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1395

1396
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1397 1398 1399
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1400

1401
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1402

DonLakeFlyer's avatar
DonLakeFlyer committed
1403 1404 1405
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1406
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1407
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1408

1409
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1410 1411
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1412
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1413

1414 1415
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1416
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1417
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1418 1419

                item->setMissionFlightStatus(_missionFlightStatus);
1420

1421 1422
                lastCoordinateItem = item;
            }
1423 1424
        }
    }
1425
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1426

1427 1428 1429 1430 1431 1432 1433 1434
    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();
1435
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1436 1437
    }

1438 1439 1440
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1441

DonLakeFlyer's avatar
DonLakeFlyer committed
1442 1443 1444 1445 1446 1447 1448
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1449 1450
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1451

1452 1453
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1454 1455
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1456 1457 1458

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

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

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

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

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

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

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

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

1521
void MissionController::_setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate)
1522
{
1523 1524
    QGeoCoordinate firstCoordinate;

1525 1526 1527 1528
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

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

        if (item->specifiesCoordinate()) {
1534 1535
            firstCoordinate = item->coordinate();
            break;
1536 1537 1538
        }
    }

1539 1540 1541 1542
    // No item specifying a coordinate was found, in this case it we have a clickCoordinate use that
    if (!firstCoordinate.isValid()) {
        firstCoordinate = clickCoordinate;
    }
1543

1544 1545 1546 1547 1548 1549 1550 1551 1552
    if (firstCoordinate.isValid()) {
        QGeoCoordinate plannedHomeCoord = firstCoordinate.atDistanceAndAzimuth(30, 0);
        plannedHomeCoord.setAltitude(0);
        _settingsItem->setCoordinate(plannedHomeCoord);
    }
}

/// @param clickCoordinate The location of the user click when inserting a new item
void MissionController::_recalcAllWithClickCoordinate(QGeoCoordinate& clickCoordinate)
1553
{
1554
    if (!_flyView) {
1555
        _setPlannedHomePositionFromFirstCoordinate(clickCoordinate);
1556
    }
1557
    _recalcSequence();
1558 1559 1560 1561
    _recalcChildItems();
    _recalcWaypointLines();
}

1562 1563 1564 1565 1566 1567
void MissionController::_recalcAll(void)
{
    QGeoCoordinate emptyCoord;
    _recalcAllWithClickCoordinate(emptyCoord);
}

1568
/// Initializes a new set of mission items
1569
void MissionController::_initAllVisualItems(void)
1570
{
1571 1572
    // Setup home position at index 0

1573 1574 1575
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1576 1577
        return;
    }
1578
    if (!_flyView) {
1579 1580
        _settingsItem->setIsCurrentItem(true);
    }
1581

1582
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1583
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1584
    }
1585

1586 1587 1588
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1589

1590 1591 1592 1593
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1594

1595
    _recalcAll();
1596

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

    emit visualItemsChanged();
1601
    emit containsItemsChanged(containsItems());
1602
    emit plannedHomePositionChanged(plannedHomePosition());
1603

1604
    setDirty(false);
1605 1606
}

1607
void MissionController::_deinitAllVisualItems(void)
1608
{
1609 1610 1611
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1612 1613
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1614 1615
    }

1616
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1617
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1618 1619
}

1620
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1621
{
1622
    setDirty(false);
1623

1624
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1625 1626
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1627 1628
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1629
    connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged,                this, &MissionController::_recalcMissionFlightStatus);
1630
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1631
    connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged,                 this, &MissionController::_recalcMissionFlightStatus);
1632
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1633

1634 1635 1636 1637 1638 1639 1640 1641
    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";
        }
1642 1643
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1644
        if (complexItem) {
1645
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
1646
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
1647 1648 1649
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1650
    }
1651 1652
}

1653
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1654
{
1655 1656
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1657 1658
}

1659
void MissionController::_itemCommandChanged(void)
1660
{
1661 1662
    _recalcChildItems();
    _recalcWaypointLines();
1663 1664
}

1665
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1666
{
1667 1668 1669 1670 1671 1672
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1673

1674 1675
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1676
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1677 1678
        return;
    }
1679

1680 1681
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1682 1683
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1684 1685 1686 1687 1688
    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);
1689
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1690 1691 1692 1693
    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);
1694

1695 1696
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1697
    }
1698

1699
    emit complexMissionItemNamesChanged();
1700
    emit resumeMissionIndexChanged();
1701 1702
}

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

void MissionController::_inProgressChanged(bool inProgress)
1719
{
1720
    emit syncInProgressChanged(inProgress);
1721
}
1722

1723
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1724
{
1725 1726
    bool        found = false;
    double      foundAltitude;
1727
    int         foundAltitudeMode;
1728

1729 1730 1731 1732 1733 1734
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1737 1738 1739
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1740 1741 1742
                if (simpleItem->specifiesAltitude()) {
                    foundAltitude = simpleItem->altitude()->rawValue().toDouble();
                    foundAltitudeMode = simpleItem->altitudeMode();
1743
                    found = true;
1744
                    break;
1745 1746
                }
            }
1747 1748 1749
        }
    }

1750
    if (found) {
1751
        *prevAltitude = foundAltitude;
1752
        *prevAltitudeMode = foundAltitudeMode;
1753 1754 1755
    }

    return found;
1756
}
1757 1758 1759 1760 1761 1762 1763 1764 1765 1766 1767 1768 1769

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

1770
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1771
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1772
{
1773
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
1774

Don Gagne's avatar
Don Gagne committed
1775 1776
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1777
    visualItems->insert(0, settingsItem);
1778

1779 1780 1781 1782 1783 1784 1785 1786 1787 1788 1789 1790 1791 1792 1793 1794 1795 1796 1797 1798 1799 1800 1801 1802 1803
    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;
                    }
1804 1805
                }
            }
1806

1807 1808 1809
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1810
        }
Don Gagne's avatar
Don Gagne committed
1811 1812
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1813 1814
    }
}
1815

1816
int MissionController::resumeMissionIndex(void) const
1817
{
1818

1819
    int resumeIndex = 0;
1820

1821
    if (_flyView) {
1822
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1823
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1824 1825
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1826 1827
        } else {
            resumeIndex = 0;
1828 1829 1830 1831 1832
        }
    }

    return resumeIndex;
}
1833

1834 1835
int MissionController::currentMissionIndex(void) const
{
1836
    if (!_flyView) {
1837 1838 1839 1840 1841 1842 1843 1844 1845 1846
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

1847
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1848
{
1849
    if (_flyView) {
1850
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1851 1852 1853
            sequenceNumber++;
        }

1854 1855
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1856 1857
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1858
        emit currentMissionIndexChanged(currentMissionIndex());
1859 1860
    }
}
1861

1862
bool MissionController::syncInProgress(void) const
1863
{
1864
    return _missionManager->inProgress();
1865 1866 1867 1868 1869 1870 1871 1872 1873 1874 1875 1876
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1877
    }
1878
}
1879

1880 1881
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1882 1883
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, vehicle);
1884

1885 1886 1887 1888 1889 1890
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1891
        if (!_flyView) {
1892 1893 1894 1895 1896 1897
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
1898 1899 1900
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1901
        if (simpleItem) {
1902 1903 1904 1905 1906
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
1907 1908 1909
        }
    }
}
1910 1911 1912 1913 1914 1915 1916 1917 1918 1919 1920 1921 1922

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
1923 1924 1925 1926 1927 1928 1929 1930
    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();
    }
1931
}
1932 1933 1934 1935 1936 1937

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

    complexItems.append(_surveyMissionItemName);
1938
    complexItems.append(_corridorScanMissionItemName);
1939
    if (_controllerVehicle->fixedWing()) {
1940 1941
        complexItems.append(_fwLandingMissionItemName);
    }
1942 1943 1944
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
        complexItems.append(_structureScanMissionItemName);
    }
1945 1946 1947

    return complexItems;
}
1948

1949 1950
void MissionController::resumeMission(int resumeIndex)
{
1951
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1952 1953
        resumeIndex--;
    }
1954
    _missionManager->generateResumeMission(resumeIndex);
1955
}
1956 1957 1958 1959 1960 1961 1962 1963 1964

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1965 1966 1967 1968 1969 1970 1971 1972 1973 1974

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

1976 1977 1978 1979 1980 1981 1982
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
1983 1984 1985 1986 1987 1988

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
1989 1990 1991

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

2015
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2016
{
2017
    // Fly view always reloads on send complete
2018
    if (!error && _flyView) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2019 2020 2021 2022
        showPlanFromManagerVehicle();
    }
}

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

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