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


#include "MissionController.h"
#include "MultiVehicleManager.h"
#include "MissionManager.h"
#include "CoordinateVector.h"
15
#include "FirmwarePlugin.h"
16
#include "QGCApplication.h"
17
#include "SimpleMissionItem.h"
18
#include "SurveyMissionItem.h"
19
#include "FixedWingLandingComplexItem.h"
20
#include "JsonHelper.h"
21
#include "ParameterManager.h"
22
#include "QGroundControlQmlGlobal.h"
23
#include "SettingsManager.h"
24
#include "MissionSettingsItem.h"
25

26
#ifndef __mobile__
27
#include "MainWindow.h"
28 29 30
#include "QGCFileDialog.h"
#endif

31 32
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

33
const char* MissionController::_settingsGroup =                 "MissionController";
Don Gagne's avatar
Don Gagne committed
34 35
const char* MissionController::_jsonFileTypeValue =             "Mission";
const char* MissionController::_jsonItemsKey =                  "items";
36
const char* MissionController::_jsonPlannedHomePositionKey =    "plannedHomePosition";
Don Gagne's avatar
Don Gagne committed
37
const char* MissionController::_jsonFirmwareTypeKey =           "firmwareType";
38 39 40
const char* MissionController::_jsonVehicleTypeKey =            "vehicleType";
const char* MissionController::_jsonCruiseSpeedKey =            "cruiseSpeed";
const char* MissionController::_jsonHoverSpeedKey =             "hoverSpeed";
Don Gagne's avatar
Don Gagne committed
41 42 43 44 45 46 47
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;
48 49

MissionController::MissionController(QObject *parent)
50
    : PlanElementController(parent)
51
    , _visualItems(NULL)
52
    , _settingsItem(NULL)
53
    , _firstItemsFromVehicle(false)
54 55
    , _missionItemsRequested(false)
    , _queuedSend(false)
56 57
    , _surveyMissionItemName(tr("Survey"))
    , _fwLandingMissionItemName(tr("Fixed Wing Landing"))
58
{
DonLakeFlyer's avatar
DonLakeFlyer committed
59 60 61 62 63 64 65 66 67 68
    _missionFlightStatus.maxTelemetryDistance = 0;
    _missionFlightStatus.totalDistance = 0;
    _missionFlightStatus.totalTime = 0;
    _missionFlightStatus.hoverDistance = 0;
    _missionFlightStatus.hoverTime = 0;
    _missionFlightStatus.cruiseDistance = 0;
    _missionFlightStatus.cruiseTime = 0;
    _missionFlightStatus.cruiseSpeed = 0;
    _missionFlightStatus.hoverSpeed = 0;
    _missionFlightStatus.gimbalYaw = 0;
69 70 71 72
}

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

74 75 76 77
}

void MissionController::start(bool editMode)
{
78 79
    qCDebug(MissionControllerLog) << "start editMode" << editMode;

80
    PlanElementController::start(editMode);
81 82 83 84 85 86
    _init();
}

void MissionController::startStaticActiveVehicle(Vehicle *vehicle)
{
    qCDebug(MissionControllerLog) << "startStaticActiveVehicle";
87

88 89 90 91 92 93
    PlanElementController::startStaticActiveVehicle(vehicle);
    _init();
}

void MissionController::_init(void)
{
94
    // We start with an empty mission
95
    _visualItems = new QmlObjectListModel(this);
96
    _addMissionSettings(_activeVehicle, _visualItems, false /* addToCenter */);
97
    _initAllVisualItems();
98 99
}

100
// Called when new mission items have completed downloading from Vehicle
101
void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllRequested)
102
{
103 104
    qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle";

105 106
    if (!_editMode || removeAllRequested || _missionItemsRequested || _visualItems->count() == 1) {
        // Fly Mode (accept if):
Don Gagne's avatar
Don Gagne committed
107
        //      - Always accepts new items from the vehicle so Fly view is kept up to date
108
        // Edit Mode (accept if):
109
        //      - Either a load from vehicle was manually requested or
Don Gagne's avatar
Don Gagne committed
110
        //      - The initial automatic load from a vehicle completed and the current editor is empty
111
        //      - Remove all way requested from Fly view (clear mission on flight end)
112

113 114
        QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
        const QList<MissionItem*>& newMissionItems = _activeVehicle->missionManager()->missionItems();
115 116 117 118 119 120
        qCDebug(MissionControllerLog) << "loading from vehicle: count"<< newMissionItems.count();

        int i = 0;
        if (_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() && newMissionItems.count() != 0) {
            // First item is fake home position
            _addMissionSettings(_activeVehicle, newControllerMissionItems, false /* addToCenter */);
121
            MissionSettingsItem* settingsItem = newControllerMissionItems->value<MissionSettingsItem*>(0);
122 123 124 125 126 127 128
            if (!settingsItem) {
                qWarning() << "First item is not settings item";
                return;
            }
            settingsItem->setCoordinate(newMissionItems[0]->coordinate());
            i = 1;
        }
129

130 131
        for (; i<newMissionItems.count(); i++) {
            const MissionItem* missionItem = newMissionItems[i];
132 133 134 135
            newControllerMissionItems->append(new SimpleMissionItem(_activeVehicle, *missionItem, this));
        }

        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
136
        _visualItems->deleteLater();
137
        _settingsItem = NULL;
138 139 140
        _visualItems = newControllerMissionItems;

        if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
141
            _addMissionSettings(_activeVehicle, _visualItems, _visualItems->count() > 0 /* addToCenter */);
142 143
        }

144
        _missionItemsRequested = false;
145

146
        if (_editMode) {
147
            MissionController::_scanForAdditionalSettings(_visualItems, _activeVehicle);
148
        }
149

150
        _initAllVisualItems();
151
        emit newItemsFromVehicle();
152 153 154
    }
}

155
void MissionController::loadFromVehicle(void)
156
{
157
    Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
158

159 160 161 162 163 164
    if (activeVehicle) {
        _missionItemsRequested = true;
        activeVehicle->missionManager()->requestMissionItems();
    }
}

165
void MissionController::sendToVehicle(void)
166
{
Don Gagne's avatar
Don Gagne committed
167 168 169 170
    sendItemsToVehicle(_activeVehicle, _visualItems);
    _visualItems->setDirty(false);
}

171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191
/// 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)
{
    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
192
    MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
193 194 195 196 197 198 199
    if (settingsItem) {
        endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
    }

    return endActionSet;
}

Don Gagne's avatar
Don Gagne committed
200 201 202
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
203
        QList<MissionItem*> rgMissionItems;
204

205
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
206

207
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
208

209 210
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
211
        }
212 213
    }
}
214

215 216 217 218 219 220
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
221 222
        VisualMissionItem* lastItem = _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1);
        return lastItem->lastSequenceNumber() + 1;
223 224 225
    }
}

226
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
227
{
228
    int sequenceNumber = _nextSequenceNumber();
229
    SimpleMissionItem * newItem = new SimpleMissionItem(_activeVehicle, this);
230
    newItem->setSequenceNumber(sequenceNumber);
231
    newItem->setCoordinate(coordinate);
232 233 234
    newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
    _initVisualItem(newItem);
    if (_visualItems->count() == 1) {
235 236
        newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
    }
237
    newItem->setDefaultsForCommand();
Don Gagne's avatar
Don Gagne committed
238
    if ((MAV_CMD)newItem->command() == MAV_CMD_NAV_WAYPOINT) {
239 240
        double      prevAltitude;
        MAV_FRAME   prevFrame;
241

242 243 244
        if (_findPreviousAltitude(i, &prevAltitude, &prevFrame)) {
            newItem->missionItem().setFrame(prevFrame);
            newItem->missionItem().setParam7(prevAltitude);
245
        }
246
    }
247
    _visualItems->insert(i, newItem);
248 249 250

    _recalcAll();

251
    return newItem->sequenceNumber();
252 253
}

254
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
255
{
256 257
    ComplexMissionItem* newItem;

258
    int sequenceNumber = _nextSequenceNumber();
259 260
    if (itemName == _surveyMissionItemName) {
        newItem = new SurveyMissionItem(_activeVehicle, _visualItems);
261
        newItem->setCoordinate(mapCenterCoordinate);
262
    } else if (itemName == _fwLandingMissionItemName) {
263
        newItem = new FixedWingLandingComplexItem(_activeVehicle, _visualItems);
264 265 266 267
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }
268
    newItem->setSequenceNumber(sequenceNumber);
269
    _initVisualItem(newItem);
270

271
    _visualItems->insert(i, newItem);
272 273 274

    _recalcAll();

275
    return newItem->sequenceNumber();
276 277
}

278 279
void MissionController::removeMissionItem(int index)
{
280
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
281

282
    _deinitVisualItem(item);
283
    item->deleteLater();
284 285

    _recalcAll();
286
    _visualItems->setDirty(true);
287 288
}

289
void MissionController::removeAll(void)
290
{
291 292
    if (_visualItems) {
        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
293
        _visualItems->deleteLater();
294
        _settingsItem = NULL;
295
        _visualItems = new QmlObjectListModel(this);
296
        _addMissionSettings(_activeVehicle, _visualItems, false /* addToCenter */);
297
        _initAllVisualItems();
Don Gagne's avatar
Don Gagne committed
298
        _visualItems->setDirty(true);
299
    }
300
}
301

302
bool MissionController::_loadJsonMissionFile(Vehicle* vehicle, const QByteArray& bytes, QmlObjectListModel* visualItems, QString& errorString)
303 304 305 306 307 308 309 310 311 312
{
    QJsonParseError jsonParseError;
    QJsonDocument   jsonDoc(QJsonDocument::fromJson(bytes, &jsonParseError));

    if (jsonParseError.error != QJsonParseError::NoError) {
        errorString = jsonParseError.errorString();
        return false;
    }
    QJsonObject json = jsonDoc.object();

Don Gagne's avatar
Don Gagne committed
313 314 315
    // 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;
316 317
    }

Don Gagne's avatar
Don Gagne committed
318 319 320 321 322 323 324
    int fileVersion;
    if (!JsonHelper::validateQGCJsonFile(json,
                                         _jsonFileTypeValue,    // expected file type
                                         1,                     // minimum supported version
                                         2,                     // maximum supported version
                                         fileVersion,
                                         errorString)) {
325 326
        return false;
    }
327

Don Gagne's avatar
Don Gagne committed
328
    if (fileVersion == 1) {
329
        return _loadJsonMissionFileV1(vehicle, json, visualItems, errorString);
Don Gagne's avatar
Don Gagne committed
330
    } else {
331
        return _loadJsonMissionFileV2(vehicle, json, visualItems, errorString);
Don Gagne's avatar
Don Gagne committed
332 333 334
    }
}

335
bool MissionController::_loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
336 337 338 339 340 341 342 343 344
{
    // 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)) {
345 346 347
        return false;
    }

348
    // Read complex items
349
    QList<SurveyMissionItem*> surveyItems;
350 351 352 353
    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];
354

355 356 357 358 359
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

Don Gagne's avatar
Don Gagne committed
360
        SurveyMissionItem* item = new SurveyMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
361 362
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
363
            surveyItems.append(item);
364 365
        } else {
            return false;
366
        }
367
    }
368

369 370 371 372 373
    // 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
374
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
375

376
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
377 378 379 380
    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
381 382
        if (nextComplexItemIndex < surveyItems.count()) {
            SurveyMissionItem* complexItem = surveyItems[nextComplexItemIndex];
383 384 385 386 387 388 389 390 391 392 393 394 395 396

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

397 398 399 400 401
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
402
            const QJsonObject itemObject = itemValue.toObject();
Don Gagne's avatar
Don Gagne committed
403
            SimpleMissionItem* item = new SimpleMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
404
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
405
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
406
                nextSequenceNumber = item->lastSequenceNumber() + 1;
407
                visualItems->append(item);
408 409 410 411
            } else {
                return false;
            }
        }
412
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
413 414

    if (json.contains(_jsonPlannedHomePositionKey)) {
Don Gagne's avatar
Don Gagne committed
415
        SimpleMissionItem* item = new SimpleMissionItem(vehicle, visualItems);
416

Don Gagne's avatar
Don Gagne committed
417
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
418
            MissionSettingsItem* settingsItem = new MissionSettingsItem(vehicle, visualItems);
419 420 421
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
422 423 424 425
        } else {
            return false;
        }
    } else {
426
        _addMissionSettings(vehicle, visualItems, true /* addToCenter */);
427 428 429 430 431
    }

    return true;
}

432
bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
433 434 435 436 437 438
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
439 440 441
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
442 443 444 445 446 447 448
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

449
    // Mission Settings
Don Gagne's avatar
Don Gagne committed
450
    QGeoCoordinate homeCoordinate;
451
    SettingsManager* settingsManager = qgcApp()->toolbox()->settingsManager();
Don Gagne's avatar
Don Gagne committed
452 453 454
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
Don Gagne's avatar
Don Gagne committed
455
    if (json.contains(_jsonVehicleTypeKey) && vehicle->isOfflineEditingVehicle()) {
456
        settingsManager->appSettings()->offlineEditingVehicleType()->setRawValue(json[_jsonVehicleTypeKey].toDouble());
457 458
    }
    if (json.contains(_jsonCruiseSpeedKey)) {
459
        settingsManager->appSettings()->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
460 461
    }
    if (json.contains(_jsonHoverSpeedKey)) {
462
        settingsManager->appSettings()->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
463 464
    }

465
    MissionSettingsItem* settingsItem = new MissionSettingsItem(vehicle, visualItems);
466 467
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493
    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) {
Don Gagne's avatar
Don Gagne committed
494
            SimpleMissionItem* simpleItem = new SimpleMissionItem(vehicle, visualItems);
495
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
496
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
497
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
498 499 500 501 502 503 504 505 506 507 508 509 510 511 512
                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();

            if (complexItemType == SurveyMissionItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Survey: nextSequenceNumber" << nextSequenceNumber;
Don Gagne's avatar
Don Gagne committed
513
                SurveyMissionItem* surveyItem = new SurveyMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
514 515 516 517 518 519
                if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(surveyItem);
520
            } else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
521 522 523 524 525 526 527 528
                qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
                FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(vehicle, visualItems);
                if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(landingItem);
529
            } else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
530
                qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
531
                MissionSettingsItem* settingsItem = new MissionSettingsItem(vehicle, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
532 533 534 535 536 537
                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
538 539 540 541 542 543 544 545 546 547 548 549 550
            } 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
551
            if ((MAV_CMD)doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574
                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;
}

Don Gagne's avatar
Don Gagne committed
575
bool MissionController::_loadTextMissionFile(Vehicle* vehicle, QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595
{
    bool addPlannedHomePosition = false;

    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;
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
            addPlannedHomePosition = true;
        }
    }

    if (versionOk) {
        while (!stream.atEnd()) {
Don Gagne's avatar
Don Gagne committed
596
            SimpleMissionItem* item = new SimpleMissionItem(vehicle, visualItems);
597 598

            if (item->load(stream)) {
599
                visualItems->append(item);
600 601 602 603 604 605
            } else {
                errorString = QStringLiteral("The mission file is corrupted.");
                return false;
            }
        }
    } else {
606
        errorString = QStringLiteral("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
607 608 609
        return false;
    }

610
    if (addPlannedHomePosition || visualItems->count() == 0) {
611
        _addMissionSettings(vehicle, visualItems, true /* addToCenter */);
Don Gagne's avatar
Don Gagne committed
612

613 614 615 616 617
        // 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));
            if (item && item->command() == MavlinkQmlSingleton::MAV_CMD_DO_JUMP) {
                item->missionItem().setParam1((int)item->missionItem().param1() + 1);
Don Gagne's avatar
Don Gagne committed
618 619
            }
        }
620 621 622
    }

    return true;
623 624
}

625
void MissionController::loadFromFile(const QString& filename)
626
{
Don Gagne's avatar
Don Gagne committed
627 628
    QmlObjectListModel* newVisualItems = NULL;

629
    if (!loadItemsFromFile(_activeVehicle, filename, &newVisualItems)) {
Don Gagne's avatar
Don Gagne committed
630 631 632 633 634 635
        return;
    }

    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
636
        _settingsItem = NULL;
Don Gagne's avatar
Don Gagne committed
637 638 639 640 641
    }

    _visualItems = newVisualItems;

    if (_visualItems->count() == 0) {
642
        _addMissionSettings(_activeVehicle, _visualItems, true /* addToCenter */);
Don Gagne's avatar
Don Gagne committed
643 644
    }

645
    MissionController::_scanForAdditionalSettings(_visualItems, _activeVehicle);
646

Don Gagne's avatar
Don Gagne committed
647 648 649
    _initAllVisualItems();
}

650
bool MissionController::loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems)
Don Gagne's avatar
Don Gagne committed
651 652 653
{
    *visualItems = NULL;

654 655 656
    QString errorString;

    if (filename.isEmpty()) {
Don Gagne's avatar
Don Gagne committed
657
        return false;
658 659
    }

Don Gagne's avatar
Don Gagne committed
660
    *visualItems = new QmlObjectListModel();
661 662 663 664

    QFile file(filename);

    if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
Don Gagne's avatar
Don Gagne committed
665
        errorString = file.errorString() + QStringLiteral(" ") + filename;
666
    } else {
667 668
        QByteArray  bytes = file.readAll();
        QTextStream stream(&bytes);
669

670 671 672
        QString firstLine = stream.readLine();
        if (firstLine.contains(QRegExp("QGC.*WPL"))) {
            stream.seek(0);
Don Gagne's avatar
Don Gagne committed
673
            _loadTextMissionFile(vehicle, stream, *visualItems, errorString);
674
        } else {
675
            _loadJsonMissionFile(vehicle, bytes, *visualItems, errorString);
676 677
        }
    }
678

679
    if (!errorString.isEmpty()) {
Don Gagne's avatar
Don Gagne committed
680
        (*visualItems)->deleteLater();
681

682
        qgcApp()->showMessage(errorString);
Don Gagne's avatar
Don Gagne committed
683
        return false;
684 685
    }

Don Gagne's avatar
Don Gagne committed
686
    return true;
687 688
}

689
void MissionController::loadFromFilePicker(void)
690
{
691
#ifndef __mobile__
692
    QString filename = QGCFileDialog::getOpenFileName(MainWindow::instance(), "Select Mission File to load", QString(), "Mission file (*.mission);;All Files (*.*)");
693 694 695 696

    if (filename.isEmpty()) {
        return;
    }
697
    loadFromFile(filename);
698 699 700
#endif
}

701
void MissionController::saveToFile(const QString& filename)
702 703
{
    qDebug() << filename;
704 705 706 707

    if (filename.isEmpty()) {
        return;
    }
708

709
    QString missionFilename = filename;
710
    if (!QFileInfo(filename).fileName().contains(".")) {
Don Gagne's avatar
Don Gagne committed
711
        missionFilename += QString(".%1").arg(QGCApplication::missionFileExtension);
712 713
    }

714
    QFile file(missionFilename);
715

716
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
717
        qgcApp()->showMessage(file.errorString());
718
    } else {
719
        QJsonObject missionFileObject;      // top level json object
720

Don Gagne's avatar
Don Gagne committed
721
        missionFileObject[JsonHelper::jsonVersionKey] =         _missionFileVersion;
722
        missionFileObject[JsonHelper::jsonGroundStationKey] =   JsonHelper::jsonGroundStationValue;
723

724
        // Mission settings
725

726
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
727
        if (!settingsItem) {
728
            qWarning() << "First item is not MissionSettingsItem";
729 730
            return;
        }
Don Gagne's avatar
Don Gagne committed
731
        QJsonValue coordinateValue;
732
        JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
Don Gagne's avatar
Don Gagne committed
733
        missionFileObject[_jsonPlannedHomePositionKey] = coordinateValue;
734 735
        missionFileObject[_jsonFirmwareTypeKey] = _activeVehicle->firmwareType();
        missionFileObject[_jsonVehicleTypeKey] = _activeVehicle->vehicleType();
DonLakeFlyer's avatar
DonLakeFlyer committed
736 737
        missionFileObject[_jsonCruiseSpeedKey] = _activeVehicle->defaultCruiseSpeed();
        missionFileObject[_jsonHoverSpeedKey] = _activeVehicle->defaultHoverSpeed();
738

739
        // Save the visual items
740

DonLakeFlyer's avatar
DonLakeFlyer committed
741
        QJsonArray rgJsonMissionItems;
742
        for (int i=0; i<_visualItems->count(); i++) {
743
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760

            visualItem->save(rgJsonMissionItems);
        }

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

            if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
                QJsonObject saveObject;
                MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
                missionItem->save(saveObject);
                rgJsonMissionItems.append(saveObject);
            }
            for (int i=0; i<rgMissionItems.count(); i++) {
                rgMissionItems[i]->deleteLater();
            }
761
        }
762 763

        missionFileObject[_jsonItemsKey] = rgJsonMissionItems;
764 765

        QJsonDocument saveDoc(missionFileObject);
766
        file.write(saveDoc.toJson());
767 768
    }

769
    _visualItems->setDirty(false);
770 771
}

772
void MissionController::saveToFilePicker(void)
773 774
{
#ifndef __mobile__
775
    QString filename = QGCFileDialog::getSaveFileName(MainWindow::instance(), "Select file to save mission to", QString(), "Mission file (*.mission);;All Files (*.*)");
776 777 778 779

    if (filename.isEmpty()) {
        return;
    }
780
    saveToFile(filename);
781
#endif
782 783
}

784
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
785
{
Don Gagne's avatar
Don Gagne committed
786
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
787
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
788 789 790 791
    bool            distanceOk =    false;

    // Convert to fixed altitudes

792
    qCDebug(MissionControllerLog) << homeAlt
793 794
                                  << currentItem->coordinateHasRelativeAltitude() << currentItem->coordinate().altitude()
                                  << prevItem->exitCoordinateHasRelativeAltitude() << prevItem->exitCoordinate().altitude();
795

796
    distanceOk = true;
797
    if (currentItem->coordinateHasRelativeAltitude()) {
798 799
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
800
    if (prevItem->exitCoordinateHasRelativeAltitude()) {
801
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
802 803 804 805 806
    }

    qCDebug(MissionControllerLog) << "distanceOk" << distanceOk;

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
807 808 809
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
810
    } else {
Don Gagne's avatar
Don Gagne committed
811
        *altDifference = 0.0;
812
        *azimuth = 0.0;
813
        *distance = 0.0;
814 815 816
    }
}

817
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
818 819 820 821 822 823 824 825 826
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

    qCDebug(MissionControllerLog) << "distanceOk" << distanceOk;

827
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
828 829
}

830 831
void MissionController::_recalcWaypointLines(void)
{
832 833 834
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

835
    bool showHomePosition = _settingsItem->coordinate().isValid();
836 837 838

    qCDebug(MissionControllerLog) << "_recalcWaypointLines";

Nate Weibley's avatar
Nate Weibley committed
839 840
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
841 842 843 844 845 846 847
    _waypointLines.clear();

    bool linkBackToHome = false;
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));


848
        // If we still haven't found the first coordinate item and we hit a takeoff command, link back to home
849 850
        if (firstCoordinateItem &&
                item->isSimpleItem() &&
851 852
                (qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF ||
                 qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) {
853 854 855 856 857 858 859
            linkBackToHome = true;
        }

        if (item->specifiesCoordinate()) {
            if (!item->isStandaloneCoordinate()) {
                firstCoordinateItem = false;
                VisualItemPair pair(lastCoordinateItem, item);
860
                if (lastCoordinateItem != _settingsItem || (showHomePosition && linkBackToHome)) {
861 862
                    if (old_table.contains(pair)) {
                        // Do nothing, this segment already exists and is wired up
Nate Weibley's avatar
Nate Weibley committed
863
                        _linesTable[pair] = old_table.take(pair);
864 865 866 867
                    } else {
                        // Create a new segment and wire update notifiers
                        auto linevect       = new CoordinateVector(lastCoordinateItem->isSimpleItem() ? lastCoordinateItem->coordinate() : lastCoordinateItem->exitCoordinate(), item->coordinate(), this);
                        auto originNotifier = lastCoordinateItem->isSimpleItem() ? &VisualMissionItem::coordinateChanged : &VisualMissionItem::exitCoordinateChanged,
Don Gagne's avatar
Don Gagne committed
868
                                endNotifier    = &VisualMissionItem::coordinateChanged;
869 870 871 872 873 874
                        // Use signals/slots to update the coordinate endpoints
                        connect(lastCoordinateItem, originNotifier, linevect, &CoordinateVector::setCoordinate1);
                        connect(item,               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
DonLakeFlyer's avatar
DonLakeFlyer committed
875
                        connect(item, &VisualMissionItem::coordinateChanged, this, &MissionController::_recalcMissionFlightStatus);
Nate Weibley's avatar
Nate Weibley committed
876
                        _linesTable[pair] = linevect;
877 878 879 880 881 882 883 884 885 886
                    }
                }
                lastCoordinateItem = item;
            }
        }
    }

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
887 888
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
889 890 891 892 893 894 895 896 897 898
            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
899
    _recalcMissionFlightStatus();
900 901 902 903

    emit waypointLinesChanged();
}

DonLakeFlyer's avatar
DonLakeFlyer committed
904
void MissionController::_recalcMissionFlightStatus()
905
{
906
    if (!_visualItems->count()) {
907
        return;
908
    }
909 910 911 912

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

913
    bool showHomePosition = _settingsItem->coordinate().isValid();
914

DonLakeFlyer's avatar
DonLakeFlyer committed
915
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
916

917 918 919
    // 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.
920

921
    // No values for first item
922
    lastCoordinateItem->setAltDifference(0.0);
923
    lastCoordinateItem->setAzimuth(0.0);
924
    lastCoordinateItem->setDistance(0.0);
925

926 927
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
928 929
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
930

DonLakeFlyer's avatar
DonLakeFlyer committed
931 932 933 934 935 936 937 938 939 940 941 942 943
    double lastVehicleYaw = 0;

    _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;
    _missionFlightStatus.cruiseSpeed =          _activeVehicle->defaultCruiseSpeed();
    _missionFlightStatus.hoverSpeed =           _activeVehicle->defaultHoverSpeed();
    _missionFlightStatus.vehicleSpeed =         _activeVehicle->multiRotor() || _activeVehicle->vtol() ? _missionFlightStatus.hoverSpeed : _missionFlightStatus.cruiseSpeed;
    _missionFlightStatus.gimbalYaw =            std::numeric_limits<double>::quiet_NaN();
944

DonLakeFlyer's avatar
DonLakeFlyer committed
945
    bool vtolInHover = true;
Don Gagne's avatar
Don Gagne committed
946
    bool linkBackToHome = false;
947

DonLakeFlyer's avatar
DonLakeFlyer committed
948
    for (int i=0; i<_visualItems->count(); i++) {
949
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
950 951 952
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

953 954
        // Assume the worst
        item->setAzimuth(0.0);
955
        item->setDistance(0.0);
956

DonLakeFlyer's avatar
DonLakeFlyer committed
957 958 959 960 961 962 963 964
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
            if (_activeVehicle->multiRotor()) {
                _missionFlightStatus.hoverSpeed = newSpeed;
            } else if (_activeVehicle->vtol()) {
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
965
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
966
                    _missionFlightStatus.cruiseSpeed = newSpeed;
967
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
968 969
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
970
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
971 972 973 974
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
975 976 977 978 979 980
        if (_activeVehicle->vehicleYawsToNextWaypointInMission()) {
            // We current only support gimbal display in this mode
            double gimbalYaw = item->specifiedGimbalYaw();
            if (!qIsNaN(gimbalYaw)) {
                _missionFlightStatus.gimbalYaw = gimbalYaw;
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
981 982 983 984 985
        }

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

988 989 990 991 992 993 994 995
        // Link back to home if first item is takeoff and we have home position
        if (firstCoordinateItem && simpleItem && simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) {
            if (showHomePosition) {
                linkBackToHome = true;
            }
        }

        // Update VTOL state
DonLakeFlyer's avatar
DonLakeFlyer committed
996
        if (simpleItem && _activeVehicle->vtol()) {
997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010
            switch (simpleItem->command()) {
            case MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF:
                vtolInHover = false;
                break;
            case MavlinkQmlSingleton::MAV_CMD_NAV_LAND:
                vtolInHover = false;
                break;
            case MavlinkQmlSingleton::MAV_CMD_DO_VTOL_TRANSITION:
            {
                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;
1011 1012
                }
            }
1013 1014 1015
                break;
            default:
                break;
1016
            }
Don Gagne's avatar
Don Gagne committed
1017 1018
        }

1019
        if (item->specifiesCoordinate()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1020 1021 1022 1023 1024 1025
            // Update vehicle yaw assuming direction to next waypoint
            if (item != lastCoordinateItem) {
                lastVehicleYaw = lastCoordinateItem->exitCoordinate().azimuthTo(item->coordinate());
                lastCoordinateItem->setMissionVehicleYaw(lastVehicleYaw);
            }

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

1028
            double absoluteAltitude = item->coordinate().altitude();
1029
            if (item->coordinateHasRelativeAltitude()) {
1030 1031 1032 1033 1034
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1035 1036 1037 1038 1039 1040 1041 1042 1043 1044
            if (!item->exitCoordinateSameAsEntry()) {
                absoluteAltitude = item->exitCoordinate().altitude();
                if (item->exitCoordinateHasRelativeAltitude()) {
                    absoluteAltitude += homePositionAltitude;
                }
                minAltSeen = std::min(minAltSeen, absoluteAltitude);
                maxAltSeen = std::max(maxAltSeen, absoluteAltitude);
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1045
                firstCoordinateItem = false;
1046
                if (lastCoordinateItem != _settingsItem || linkBackToHome) {
1047 1048
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1049

1050
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1051 1052 1053
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1054

DonLakeFlyer's avatar
DonLakeFlyer committed
1055
                    _missionFlightStatus.totalDistance += distance;
1056
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1057

DonLakeFlyer's avatar
DonLakeFlyer committed
1058 1059 1060 1061
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
                    if (_activeVehicle->vtol()) {
1062
                        if (vtolInHover) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1063 1064 1065
                            _missionFlightStatus.totalTime += hoverTime;
                            _missionFlightStatus.hoverTime += hoverTime;
                            _missionFlightStatus.hoverDistance += distance;
1066
                        } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1067 1068 1069
                            _missionFlightStatus.totalTime += cruiseTime;
                            _missionFlightStatus.cruiseTime += cruiseTime;
                            _missionFlightStatus.cruiseDistance += distance;
1070 1071
                        }
                    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1072 1073 1074 1075 1076 1077 1078 1079 1080 1081
                        if (_activeVehicle->multiRotor()) {
                            _missionFlightStatus.totalTime += hoverTime;
                            _missionFlightStatus.hoverTime += hoverTime;
                            _missionFlightStatus.hoverDistance += distance;
                        } else {
                            _missionFlightStatus.totalTime += cruiseTime;
                            _missionFlightStatus.cruiseTime += cruiseTime;
                            _missionFlightStatus.cruiseDistance += distance;

                        }
1082
                    }
1083
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1084

1085
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1086 1087 1088
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
                    _missionFlightStatus.totalDistance += distance;
1089
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114

                    double hoverTime = _missionFlightStatus.totalDistance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = _missionFlightStatus.totalDistance / _missionFlightStatus.cruiseSpeed;
                    if (_activeVehicle->vtol()) {
                        if (vtolInHover) {
                            _missionFlightStatus.totalTime += hoverTime;
                            _missionFlightStatus.hoverTime += hoverTime;
                            _missionFlightStatus.hoverDistance += distance;
                        } else {
                            _missionFlightStatus.totalTime += cruiseTime;
                            _missionFlightStatus.cruiseTime += cruiseTime;
                            _missionFlightStatus.cruiseDistance += distance;
                        }
                    } else {
                        if (_activeVehicle->multiRotor()) {
                            _missionFlightStatus.totalTime += hoverTime;
                            _missionFlightStatus.hoverTime += hoverTime;
                            _missionFlightStatus.hoverDistance += distance;
                        } else {
                            _missionFlightStatus.totalTime += cruiseTime;
                            _missionFlightStatus.cruiseTime += cruiseTime;
                            _missionFlightStatus.cruiseDistance += distance;

                        }
                    }
1115
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1116 1117

                item->setMissionFlightStatus(_missionFlightStatus);
1118
            }
1119 1120

            lastCoordinateItem = item;
1121 1122
        }
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1123
    lastCoordinateItem->setMissionVehicleYaw(lastVehicleYaw);
1124 1125


DonLakeFlyer's avatar
DonLakeFlyer committed
1126 1127 1128 1129 1130 1131 1132
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1133

1134 1135
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1136 1137
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1138 1139 1140

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1141
            if (item->coordinateHasRelativeAltitude()) {
1142 1143 1144 1145 1146 1147
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1148
            }
1149 1150 1151 1152
        }
    }
}

1153 1154 1155
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1156 1157 1158 1159 1160 1161
    // Setup ascending sequence numbers for all visual items

    int sequenceNumber = 0;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));

1162 1163
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1164 1165 1166
    }
}

1167 1168 1169
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1170
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1171 1172 1173

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

1174 1175
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1176 1177 1178 1179 1180

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1181
        } else if (item->isSimpleItem()) {
1182 1183 1184 1185 1186
            currentParentItem->childItems()->append(item);
        }
    }
}

1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203
void MissionController::_setPlannedHomePositionFromFirstCoordinate(void)
{
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

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

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


1204 1205
void MissionController::_recalcAll(void)
{
1206
    _setPlannedHomePositionFromFirstCoordinate();
1207
    _recalcSequence();
1208 1209 1210 1211
    _recalcChildItems();
    _recalcWaypointLines();
}

1212
/// Initializes a new set of mission items
1213
void MissionController::_initAllVisualItems(void)
1214
{
1215 1216
    // Setup home position at index 0

1217 1218 1219
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1220 1221
        return;
    }
1222
    _settingsItem->setIsCurrentItem(true);
1223

1224 1225
    if (!_editMode && _activeVehicle) {
        _settingsItem->setCoordinate(_activeVehicle->homePosition());
1226
    }
1227

1228
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
1229

1230 1231 1232 1233
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1234

1235
    _recalcAll();
1236

1237
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1238 1239 1240
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1241

1242
    _visualItems->setDirty(false);
1243 1244
}

1245
void MissionController::_deinitAllVisualItems(void)
1246
{
1247 1248
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1249 1250
    }

1251
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1252
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1253 1254
}

1255
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1256
{
1257 1258
    _visualItems->setDirty(false);

1259
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1260 1261
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1262 1263
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1264
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1265

1266 1267 1268 1269 1270 1271 1272 1273
    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";
        }
1274 1275
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1276
        if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1277
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcMissionFlightStatus);
1278 1279 1280
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1281
    }
1282 1283
}

1284
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1285
{
1286 1287
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1288 1289
}

1290
void MissionController::_itemCommandChanged(void)
1291
{
1292 1293
    _recalcChildItems();
    _recalcWaypointLines();
1294 1295
}

1296
void MissionController::_activeVehicleBeingRemoved(void)
1297
{
1298
    qCDebug(MissionControllerLog) << "MissionController::_activeVehicleBeingRemoved";
1299

1300
    MissionManager* missionManager = _activeVehicle->missionManager();
1301 1302 1303 1304

    disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailableFromVehicle);
    disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
    disconnect(missionManager, &MissionManager::currentItemChanged,         this, &MissionController::_currentMissionItemChanged);
1305
    disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
Don Gagne's avatar
Don Gagne committed
1306

Don Gagne's avatar
Don Gagne committed
1307 1308
    // We always remove all items on vehicle change. This leaves a user model hole:
    //      If the user has unsaved changes in the Plan view they will lose them
1309 1310
    removeAll();
}
Don Gagne's avatar
Don Gagne committed
1311

1312 1313 1314 1315 1316
void MissionController::_activeVehicleSet(void)
{
    // We always remove all items on vehicle change. This leaves a user model hole:
    //      If the user has unsaved changes in the Plan view they will lose them
    removeAll();
1317

1318 1319 1320 1321 1322 1323
    MissionManager* missionManager = _activeVehicle->missionManager();

    connect(missionManager, &MissionManager::newMissionItemsAvailable,  this, &MissionController::_newMissionItemsAvailableFromVehicle);
    connect(missionManager, &MissionManager::inProgressChanged,         this, &MissionController::_inProgressChanged);
    connect(missionManager, &MissionManager::currentItemChanged,        this, &MissionController::_currentMissionItemChanged);
    connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);
DonLakeFlyer's avatar
DonLakeFlyer committed
1324 1325
    connect(_activeVehicle, &Vehicle::defaultCruiseSpeedChanged,        this, &MissionController::_recalcMissionFlightStatus);
    connect(_activeVehicle, &Vehicle::defaultHoverSpeedChanged,         this, &MissionController::_recalcMissionFlightStatus);
1326
    connect(_activeVehicle, &Vehicle::vehicleTypeChanged,               this, &MissionController::complexMissionItemNamesChanged);
1327

1328
    if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
1329 1330 1331
        // We are switching between two previously existing vehicles. We have to manually ask for the items from the Vehicle.
        // We don't request mission items for new vehicles since that will happen autamatically.
        loadFromVehicle();
1332
    }
1333

1334
    _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
1335 1336

    emit complexMissionItemNamesChanged();
1337 1338 1339 1340
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
1341 1342
    if (_visualItems) {
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1343
        if (settingsItem) {
1344
            settingsItem->setCoordinate(homePosition);
1345
        } else {
1346
            qWarning() << "First item is not MissionSettingsItem";
1347
        }
1348
    }
1349 1350
}

1351 1352
void MissionController::_setMissionMaxTelemetry(double missionMaxTelemetry)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1353 1354 1355
    if (!qFuzzyCompare(_missionFlightStatus.maxTelemetryDistance, missionMaxTelemetry)) {
        _missionFlightStatus.maxTelemetryDistance = missionMaxTelemetry;
        emit missionMaxTelemetryChanged(missionMaxTelemetry);
1356 1357 1358 1359
    }
}

void MissionController::_setMissionDistance(double missionDistance)
1360
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1361 1362 1363
    if (!qFuzzyCompare(_missionFlightStatus.totalDistance, missionDistance)) {
        _missionFlightStatus.totalDistance = missionDistance;
        emit missionDistanceChanged(missionDistance);
1364 1365 1366
    }
}

1367
void MissionController::_setMissionTime(double missionTime)
1368
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1369 1370
    if (!qFuzzyCompare(_missionFlightStatus.totalTime, missionTime)) {
        _missionFlightStatus.totalTime = missionTime;
1371 1372 1373 1374 1375 1376
        emit missionTimeChanged();
    }
}

void MissionController::_setMissionHoverTime(double missionHoverTime)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1377 1378
    if (!qFuzzyCompare(_missionFlightStatus.hoverTime, missionHoverTime)) {
        _missionFlightStatus.hoverTime = missionHoverTime;
1379
        emit missionHoverTimeChanged();
1380 1381 1382
    }
}

1383
void MissionController::_setMissionHoverDistance(double missionHoverDistance)
1384
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1385 1386 1387
    if (!qFuzzyCompare(_missionFlightStatus.hoverDistance, missionHoverDistance)) {
        _missionFlightStatus.hoverDistance = missionHoverDistance;
        emit missionHoverDistanceChanged(missionHoverDistance);
1388 1389 1390
    }
}

1391
void MissionController::_setMissionCruiseTime(double missionCruiseTime)
1392
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1393 1394
    if (!qFuzzyCompare(_missionFlightStatus.cruiseTime, missionCruiseTime)) {
        _missionFlightStatus.cruiseTime = missionCruiseTime;
1395 1396 1397 1398 1399 1400
        emit missionCruiseTimeChanged();
    }
}

void MissionController::_setMissionCruiseDistance(double missionCruiseDistance)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1401 1402 1403
    if (!qFuzzyCompare(_missionFlightStatus.cruiseDistance, missionCruiseDistance)) {
        _missionFlightStatus.cruiseDistance = missionCruiseDistance;
        emit missionCruiseDistanceChanged(missionCruiseDistance);
1404 1405 1406
    }
}

1407
void MissionController::_inProgressChanged(bool inProgress)
1408
{
1409
    emit syncInProgressChanged(inProgress);
1410
}
1411

1412
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
1413
{
1414 1415 1416
    bool        found = false;
    double      foundAltitude;
    MAV_FRAME   foundFrame;
1417

1418 1419 1420 1421 1422 1423
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1426 1427 1428
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1429
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
1430 1431 1432
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1433
                    break;
1434 1435
                }
            }
1436 1437 1438
        }
    }

1439
    if (found) {
1440 1441
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1442 1443 1444
    }

    return found;
1445
}
1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458

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

1459 1460
/// Add the Mission Settings complex item to the front of the items
void MissionController::_addMissionSettings(Vehicle* vehicle, QmlObjectListModel* visualItems, bool addToCenter)
1461
{
1462
    MissionSettingsItem* settingsItem = new MissionSettingsItem(vehicle, visualItems);
1463

1464
    visualItems->insert(0, settingsItem);
1465

1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490
    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;
                    }
1491 1492
                }
            }
1493

1494 1495 1496
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1497
        }
1498 1499
    } else {
        settingsItem->setCoordinate(vehicle->homePosition());
1500 1501
    }
}
1502 1503 1504 1505 1506 1507 1508 1509

void MissionController::_currentMissionItemChanged(int sequenceNumber)
{
    if (!_editMode) {
        if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            sequenceNumber++;
        }

1510 1511
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1512 1513 1514 1515
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
    }
}
1516

1517
bool MissionController::syncInProgress(void) const
1518
{
1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530 1531
    return _activeVehicle ? _activeVehicle->missionManager()->inProgress() : false;
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1532
    }
1533
}
1534

1535 1536 1537 1538
QString MissionController::fileExtension(void) const
{
    return QGCApplication::missionFileExtension;
}
1539

1540 1541 1542 1543 1544 1545 1546 1547
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1548
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559 1560 1561 1562
        if (settingsItem && settingsItem->scanForMissionSettings(visualItems, scanIndex, vehicle)) {
            continue;
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
        if (simpleItem && simpleItem->cameraSection()->available()) {
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
            continue;
        }

        scanIndex++;
    }
}
1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578

void MissionController::_updateContainsItems(void)
{
    emit containsItemsChanged(containsItems());
}

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

void MissionController::removeAllFromVehicle(void)
{
    _missionItemsRequested = true;
    _activeVehicle->missionManager()->removeAll();
}
1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590

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

    complexItems.append(_surveyMissionItemName);
    if (_activeVehicle->fixedWing()) {
        complexItems.append(_fwLandingMissionItemName);
    }

    return complexItems;
}