MissionController.cc 61.9 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 "MissionSettingsComplexItem.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
    , _firstItemsFromVehicle(false)
53 54
    , _missionItemsRequested(false)
    , _queuedSend(false)
55
{
DonLakeFlyer's avatar
DonLakeFlyer committed
56 57 58 59 60 61 62 63 64 65 66
    _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;

67 68 69
    _surveyMissionItemName = tr("Survey");
    _fwLandingMissionItemName = tr("Fixed Wing Landing");
    _complexMissionItemNames << _surveyMissionItemName << _fwLandingMissionItemName;
70 71 72 73
}

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

75 76 77 78
}

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

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

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

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

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

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

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

114 115
        QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
        const QList<MissionItem*>& newMissionItems = _activeVehicle->missionManager()->missionItems();
116 117 118 119 120 121 122 123 124 125 126 127 128 129
        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 */);
            MissionSettingsComplexItem* settingsItem = newControllerMissionItems->value<MissionSettingsComplexItem*>(0);
            if (!settingsItem) {
                qWarning() << "First item is not settings item";
                return;
            }
            settingsItem->setCoordinate(newMissionItems[0]->coordinate());
            i = 1;
        }
130

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

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

        if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
141
            _addMissionSettings(_activeVehicle, _visualItems, true /* 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 171 172 173
    sendItemsToVehicle(_activeVehicle, _visualItems);
    _visualItems->setDirty(false);
}

void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
174 175 176
        // Convert to MissionItems so we can send to vehicle
        QList<MissionItem*> missionItems;

Don Gagne's avatar
Don Gagne committed
177 178
        for (int i=0; i<visualMissionItems->count(); i++) {
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(visualMissionItems->get(i));
179 180

            visualItem->appendMissionItems(missionItems, NULL);
181 182
        }

Don Gagne's avatar
Don Gagne committed
183
        vehicle->missionManager()->writeMissionItems(missionItems);
184 185

        for (int i=0; i<missionItems.count(); i++) {
Don Gagne's avatar
Don Gagne committed
186
            missionItems[i]->deleteLater();
187
        }
188 189
    }
}
190

191 192 193 194 195 196
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
197 198
        VisualMissionItem* lastItem = _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1);
        return lastItem->lastSequenceNumber() + 1;
199 200 201
    }
}

202
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
203
{
204
    int sequenceNumber = _nextSequenceNumber();
205
    SimpleMissionItem * newItem = new SimpleMissionItem(_activeVehicle, this);
206
    newItem->setSequenceNumber(sequenceNumber);
207
    newItem->setCoordinate(coordinate);
208 209 210
    newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
    _initVisualItem(newItem);
    if (_visualItems->count() == 1) {
211 212
        newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
    }
213
    newItem->setDefaultsForCommand();
Don Gagne's avatar
Don Gagne committed
214
    if ((MAV_CMD)newItem->command() == MAV_CMD_NAV_WAYPOINT) {
215 216
        double      prevAltitude;
        MAV_FRAME   prevFrame;
217

218 219 220
        if (_findPreviousAltitude(i, &prevAltitude, &prevFrame)) {
            newItem->missionItem().setFrame(prevFrame);
            newItem->missionItem().setParam7(prevAltitude);
221
        }
222
    }
223
    _visualItems->insert(i, newItem);
224 225 226

    _recalcAll();

227
    return newItem->sequenceNumber();
228 229
}

230
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
231
{
232 233
    ComplexMissionItem* newItem;

234
    int sequenceNumber = _nextSequenceNumber();
235 236
    if (itemName == _surveyMissionItemName) {
        newItem = new SurveyMissionItem(_activeVehicle, _visualItems);
237
        newItem->setCoordinate(mapCenterCoordinate);
238
    } else if (itemName == _fwLandingMissionItemName) {
239
        newItem = new FixedWingLandingComplexItem(_activeVehicle, _visualItems);
240 241 242 243
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }
244
    newItem->setSequenceNumber(sequenceNumber);
245
    _initVisualItem(newItem);
246

247
    _visualItems->insert(i, newItem);
248 249 250

    _recalcAll();

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

254 255
void MissionController::removeMissionItem(int index)
{
256
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
257

258
    _deinitVisualItem(item);
259
    item->deleteLater();
260 261

    _recalcAll();
262
    _visualItems->setDirty(true);
263 264
}

265
void MissionController::removeAll(void)
266
{
267 268
    if (_visualItems) {
        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
269
        _visualItems->deleteLater();
270
        _visualItems = new QmlObjectListModel(this);
271
        _addMissionSettings(_activeVehicle, _visualItems, false /* addToCenter */);
272
        _initAllVisualItems();
Don Gagne's avatar
Don Gagne committed
273
        _visualItems->setDirty(true);
274
    }
275
}
276

277
bool MissionController::_loadJsonMissionFile(Vehicle* vehicle, const QByteArray& bytes, QmlObjectListModel* visualItems, QString& errorString)
278 279 280 281 282 283 284 285 286 287
{
    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
288 289 290
    // 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;
291 292
    }

Don Gagne's avatar
Don Gagne committed
293 294 295 296 297 298 299
    int fileVersion;
    if (!JsonHelper::validateQGCJsonFile(json,
                                         _jsonFileTypeValue,    // expected file type
                                         1,                     // minimum supported version
                                         2,                     // maximum supported version
                                         fileVersion,
                                         errorString)) {
300 301
        return false;
    }
302

Don Gagne's avatar
Don Gagne committed
303
    if (fileVersion == 1) {
304
        return _loadJsonMissionFileV1(vehicle, json, visualItems, errorString);
Don Gagne's avatar
Don Gagne committed
305
    } else {
306
        return _loadJsonMissionFileV2(vehicle, json, visualItems, errorString);
Don Gagne's avatar
Don Gagne committed
307 308 309
    }
}

310
bool MissionController::_loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
311 312 313 314 315 316 317 318 319
{
    // 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)) {
320 321 322
        return false;
    }

323
    // Read complex items
324
    QList<SurveyMissionItem*> surveyItems;
325 326 327 328
    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];
329

330 331 332 333 334
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

Don Gagne's avatar
Don Gagne committed
335
        SurveyMissionItem* item = new SurveyMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
336 337
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
338
            surveyItems.append(item);
339 340
        } else {
            return false;
341
        }
342
    }
343

344 345 346 347 348
    // 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
349
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
350

351
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
352 353 354 355
    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
356 357
        if (nextComplexItemIndex < surveyItems.count()) {
            SurveyMissionItem* complexItem = surveyItems[nextComplexItemIndex];
358 359 360 361 362 363 364 365 366 367 368 369 370 371

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

372 373 374 375 376
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
377
            const QJsonObject itemObject = itemValue.toObject();
Don Gagne's avatar
Don Gagne committed
378
            SimpleMissionItem* item = new SimpleMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
379
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
380
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
381
                nextSequenceNumber = item->lastSequenceNumber() + 1;
382
                visualItems->append(item);
383 384 385 386
            } else {
                return false;
            }
        }
387
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
388 389

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

Don Gagne's avatar
Don Gagne committed
392
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
393 394 395 396
            MissionSettingsComplexItem* settingsItem = new MissionSettingsComplexItem(vehicle, visualItems);
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
397 398 399 400
        } else {
            return false;
        }
    } else {
401
        _addMissionSettings(vehicle, visualItems, true /* addToCenter */);
402 403 404 405 406
    }

    return true;
}

407
bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
408 409 410 411 412 413
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
414 415 416
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
417 418 419 420 421 422 423
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

424
    // Mission Settings
Don Gagne's avatar
Don Gagne committed
425
    QGeoCoordinate homeCoordinate;
426
    SettingsManager* settingsManager = qgcApp()->toolbox()->settingsManager();
Don Gagne's avatar
Don Gagne committed
427 428 429
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
Don Gagne's avatar
Don Gagne committed
430
    if (json.contains(_jsonVehicleTypeKey) && vehicle->isOfflineEditingVehicle()) {
431
        settingsManager->appSettings()->offlineEditingVehicleType()->setRawValue(json[_jsonVehicleTypeKey].toDouble());
432 433
    }
    if (json.contains(_jsonCruiseSpeedKey)) {
434
        settingsManager->appSettings()->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
435 436
    }
    if (json.contains(_jsonHoverSpeedKey)) {
437
        settingsManager->appSettings()->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
438 439
    }

440 441 442
    MissionSettingsComplexItem* settingsItem = new MissionSettingsComplexItem(vehicle, visualItems);
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469
    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) {
            qCDebug(MissionControllerLog) << "Loading MISSION_ITEM: nextSequenceNumber" << nextSequenceNumber;
Don Gagne's avatar
Don Gagne committed
470
            SimpleMissionItem* simpleItem = new SimpleMissionItem(vehicle, visualItems);
471 472
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
473 474 475 476 477 478 479 480 481 482 483 484 485 486 487
                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
488
                SurveyMissionItem* surveyItem = new SurveyMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
489 490 491 492 493 494
                if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(surveyItem);
495
            } else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
496 497 498 499 500 501 502 503
                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);
504
            } else if (complexItemType == MissionSettingsComplexItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
505 506 507 508 509 510 511 512
                qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
                MissionSettingsComplexItem* settingsItem = new MissionSettingsComplexItem(vehicle, visualItems);
                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
513 514 515 516 517 518 519 520 521 522 523 524 525
            } 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
526
            if ((MAV_CMD)doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549
                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
550
bool MissionController::_loadTextMissionFile(Vehicle* vehicle, QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570
{
    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
571
            SimpleMissionItem* item = new SimpleMissionItem(vehicle, visualItems);
572 573

            if (item->load(stream)) {
574
                visualItems->append(item);
575 576 577 578 579 580
            } else {
                errorString = QStringLiteral("The mission file is corrupted.");
                return false;
            }
        }
    } else {
581
        errorString = QStringLiteral("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
582 583 584
        return false;
    }

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

588 589 590 591 592
        // 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
593 594
            }
        }
595 596 597
    }

    return true;
598 599
}

600
void MissionController::loadFromFile(const QString& filename)
601
{
Don Gagne's avatar
Don Gagne committed
602 603
    QmlObjectListModel* newVisualItems = NULL;

604
    if (!loadItemsFromFile(_activeVehicle, filename, &newVisualItems)) {
Don Gagne's avatar
Don Gagne committed
605 606 607 608 609 610 611 612 613 614 615
        return;
    }

    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
    }

    _visualItems = newVisualItems;

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

619
    MissionController::_scanForAdditionalSettings(_visualItems, _activeVehicle);
620

Don Gagne's avatar
Don Gagne committed
621 622 623
    _initAllVisualItems();
}

624
bool MissionController::loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems)
Don Gagne's avatar
Don Gagne committed
625 626 627
{
    *visualItems = NULL;

628 629 630
    QString errorString;

    if (filename.isEmpty()) {
Don Gagne's avatar
Don Gagne committed
631
        return false;
632 633
    }

Don Gagne's avatar
Don Gagne committed
634
    *visualItems = new QmlObjectListModel();
635 636 637 638

    QFile file(filename);

    if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
Don Gagne's avatar
Don Gagne committed
639
        errorString = file.errorString() + QStringLiteral(" ") + filename;
640
    } else {
641 642
        QByteArray  bytes = file.readAll();
        QTextStream stream(&bytes);
643

644 645 646
        QString firstLine = stream.readLine();
        if (firstLine.contains(QRegExp("QGC.*WPL"))) {
            stream.seek(0);
Don Gagne's avatar
Don Gagne committed
647
            _loadTextMissionFile(vehicle, stream, *visualItems, errorString);
648
        } else {
649
            _loadJsonMissionFile(vehicle, bytes, *visualItems, errorString);
650 651
        }
    }
652

653
    if (!errorString.isEmpty()) {
Don Gagne's avatar
Don Gagne committed
654
        (*visualItems)->deleteLater();
655

656
        qgcApp()->showMessage(errorString);
Don Gagne's avatar
Don Gagne committed
657
        return false;
658 659
    }

Don Gagne's avatar
Don Gagne committed
660
    return true;
661 662
}

663
void MissionController::loadFromFilePicker(void)
664
{
665
#ifndef __mobile__
666
    QString filename = QGCFileDialog::getOpenFileName(MainWindow::instance(), "Select Mission File to load", QString(), "Mission file (*.mission);;All Files (*.*)");
667 668 669 670

    if (filename.isEmpty()) {
        return;
    }
671
    loadFromFile(filename);
672 673 674
#endif
}

675
void MissionController::saveToFile(const QString& filename)
676 677
{
    qDebug() << filename;
678 679 680 681

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

683
    QString missionFilename = filename;
684
    if (!QFileInfo(filename).fileName().contains(".")) {
Don Gagne's avatar
Don Gagne committed
685
        missionFilename += QString(".%1").arg(QGCApplication::missionFileExtension);
686 687
    }

688
    QFile file(missionFilename);
689

690
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
691
        qgcApp()->showMessage(file.errorString());
692
    } else {
693
        QJsonObject missionFileObject;      // top level json object
694

Don Gagne's avatar
Don Gagne committed
695
        missionFileObject[JsonHelper::jsonVersionKey] =         _missionFileVersion;
696
        missionFileObject[JsonHelper::jsonGroundStationKey] =   JsonHelper::jsonGroundStationValue;
697

698
        // Mission settings
699

700 701 702
        MissionSettingsComplexItem* settingsItem = _visualItems->value<MissionSettingsComplexItem*>(0);
        if (!settingsItem) {
            qWarning() << "First item is not MissionSettingsComplexItem";
703 704
            return;
        }
Don Gagne's avatar
Don Gagne committed
705
        QJsonValue coordinateValue;
706
        JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
Don Gagne's avatar
Don Gagne committed
707
        missionFileObject[_jsonPlannedHomePositionKey] = coordinateValue;
708 709
        missionFileObject[_jsonFirmwareTypeKey] = _activeVehicle->firmwareType();
        missionFileObject[_jsonVehicleTypeKey] = _activeVehicle->vehicleType();
DonLakeFlyer's avatar
DonLakeFlyer committed
710 711
        missionFileObject[_jsonCruiseSpeedKey] = _activeVehicle->defaultCruiseSpeed();
        missionFileObject[_jsonHoverSpeedKey] = _activeVehicle->defaultHoverSpeed();
712

713
        // Save the visual items
Don Gagne's avatar
Don Gagne committed
714
        QJsonArray  rgMissionItems;
715
        for (int i=0; i<_visualItems->count(); i++) {
716
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
717
            visualItem->save(rgMissionItems);
718
        }
Don Gagne's avatar
Don Gagne committed
719
        missionFileObject[_jsonItemsKey] = rgMissionItems;
720 721

        QJsonDocument saveDoc(missionFileObject);
722
        file.write(saveDoc.toJson());
723 724
    }

725
    _visualItems->setDirty(false);
726 727
}

728
void MissionController::saveToFilePicker(void)
729 730
{
#ifndef __mobile__
731
    QString filename = QGCFileDialog::getSaveFileName(MainWindow::instance(), "Select file to save mission to", QString(), "Mission file (*.mission);;All Files (*.*)");
732 733 734 735

    if (filename.isEmpty()) {
        return;
    }
736
    saveToFile(filename);
737
#endif
738 739
}

740
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
741
{
Don Gagne's avatar
Don Gagne committed
742
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
743
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
744 745 746 747
    bool            distanceOk =    false;

    // Convert to fixed altitudes

748
    qCDebug(MissionControllerLog) << homeAlt
749 750
                                  << currentItem->coordinateHasRelativeAltitude() << currentItem->coordinate().altitude()
                                  << prevItem->exitCoordinateHasRelativeAltitude() << prevItem->exitCoordinate().altitude();
751

752
    distanceOk = true;
753
    if (currentItem->coordinateHasRelativeAltitude()) {
754 755
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
756
    if (prevItem->exitCoordinateHasRelativeAltitude()) {
757
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
758 759 760 761 762
    }

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

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
763 764 765
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
766
    } else {
Don Gagne's avatar
Don Gagne committed
767
        *altDifference = 0.0;
768
        *azimuth = 0.0;
769
        *distance = 0.0;
770 771 772
    }
}

773
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
774 775 776 777 778 779 780 781 782
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

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

783
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
784 785
}

786 787
void MissionController::_recalcWaypointLines(void)
{
788 789 790
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

791
    MissionSettingsComplexItem*  settingsItem = qobject_cast<MissionSettingsComplexItem*>(lastCoordinateItem);
792

793 794
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsComplexItem";
795 796
    }

797
    bool showHomePosition = settingsItem->showHomePosition();
798 799 800

    qCDebug(MissionControllerLog) << "_recalcWaypointLines";

Nate Weibley's avatar
Nate Weibley committed
801 802
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
803 804 805 806 807 808 809
    _waypointLines.clear();

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


810
        // If we still haven't found the first coordinate item and we hit a takeoff command, link back to home
811 812
        if (firstCoordinateItem &&
                item->isSimpleItem() &&
813 814
                (qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF ||
                 qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) {
815 816 817 818 819 820 821
            linkBackToHome = true;
        }

        if (item->specifiesCoordinate()) {
            if (!item->isStandaloneCoordinate()) {
                firstCoordinateItem = false;
                VisualItemPair pair(lastCoordinateItem, item);
822
                if (lastCoordinateItem != settingsItem || (showHomePosition && linkBackToHome)) {
823 824
                    if (old_table.contains(pair)) {
                        // Do nothing, this segment already exists and is wired up
Nate Weibley's avatar
Nate Weibley committed
825
                        _linesTable[pair] = old_table.take(pair);
826 827 828 829
                    } 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
830
                                endNotifier    = &VisualMissionItem::coordinateChanged;
831 832 833 834 835 836
                        // 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
837
                        connect(item, &VisualMissionItem::coordinateChanged, this, &MissionController::_recalcMissionFlightStatus);
Nate Weibley's avatar
Nate Weibley committed
838
                        _linesTable[pair] = linevect;
839 840 841 842 843 844 845 846 847 848
                    }
                }
                lastCoordinateItem = item;
            }
        }
    }

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
849 850
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
851 852 853 854 855 856 857 858 859 860
            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
861
    _recalcMissionFlightStatus();
862 863 864 865

    emit waypointLinesChanged();
}

DonLakeFlyer's avatar
DonLakeFlyer committed
866
void MissionController::_recalcMissionFlightStatus()
867
{
868
    if (!_visualItems->count()) {
869
        return;
870
    }
871 872 873

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

876 877
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsComplexItem";
878 879
    }

880
    bool showHomePosition = settingsItem->showHomePosition();
881

DonLakeFlyer's avatar
DonLakeFlyer committed
882
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
883

884 885 886
    // 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.
887

888
    // No values for first item
889
    lastCoordinateItem->setAltDifference(0.0);
890
    lastCoordinateItem->setAzimuth(0.0);
891
    lastCoordinateItem->setDistance(0.0);
892

893 894
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
895 896
    const double homePositionAltitude = settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = settingsItem->coordinate().altitude();
897

DonLakeFlyer's avatar
DonLakeFlyer committed
898 899 900 901 902 903 904 905 906 907 908 909 910
    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();
911

DonLakeFlyer's avatar
DonLakeFlyer committed
912
    bool vtolInHover = true;
Don Gagne's avatar
Don Gagne committed
913
    bool linkBackToHome = false;
914

DonLakeFlyer's avatar
DonLakeFlyer committed
915
    for (int i=0; i<_visualItems->count(); i++) {
916
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
917 918 919
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

920 921
        // Assume the worst
        item->setAzimuth(0.0);
922
        item->setDistance(0.0);
923

DonLakeFlyer's avatar
DonLakeFlyer committed
924 925 926 927 928 929 930 931
        // 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;
932
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
933
                    _missionFlightStatus.cruiseSpeed = newSpeed;
934
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
935 936
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
937
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
938 939 940 941 942 943 944 945 946 947 948 949
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
        double gimbalYaw = item->specifiedGimbalYaw();
        if (!qIsNaN(gimbalYaw)) {
            _missionFlightStatus.gimbalYaw = gimbalYaw;
        }

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

952 953 954 955 956 957 958 959
        // 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
960
        if (simpleItem && _activeVehicle->vtol()) {
961 962 963 964 965 966 967 968 969 970 971 972 973 974
            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;
975 976
                }
            }
977 978 979
                break;
            default:
                break;
980
            }
Don Gagne's avatar
Don Gagne committed
981 982
        }

983
        if (item->specifiesCoordinate()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
984 985 986 987 988 989
            // Update vehicle yaw assuming direction to next waypoint
            if (item != lastCoordinateItem) {
                lastVehicleYaw = lastCoordinateItem->exitCoordinate().azimuthTo(item->coordinate());
                lastCoordinateItem->setMissionVehicleYaw(lastVehicleYaw);
            }

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

992
            double absoluteAltitude = item->coordinate().altitude();
993
            if (item->coordinateHasRelativeAltitude()) {
994 995 996 997 998
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

999 1000 1001 1002 1003 1004 1005 1006 1007 1008
            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
1009
                firstCoordinateItem = false;
1010
                if (lastCoordinateItem != settingsItem || linkBackToHome) {
1011 1012
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1013

1014
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1015 1016 1017
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1018

DonLakeFlyer's avatar
DonLakeFlyer committed
1019 1020
                    _missionFlightStatus.totalDistance += distance;
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, settingsItem));
1021

DonLakeFlyer's avatar
DonLakeFlyer committed
1022 1023 1024 1025
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
                    if (_activeVehicle->vtol()) {
1026
                        if (vtolInHover) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1027 1028 1029
                            _missionFlightStatus.totalTime += hoverTime;
                            _missionFlightStatus.hoverTime += hoverTime;
                            _missionFlightStatus.hoverDistance += distance;
1030
                        } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1031 1032 1033
                            _missionFlightStatus.totalTime += cruiseTime;
                            _missionFlightStatus.cruiseTime += cruiseTime;
                            _missionFlightStatus.cruiseDistance += distance;
1034 1035
                        }
                    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1036 1037 1038 1039 1040 1041 1042 1043 1044 1045
                        if (_activeVehicle->multiRotor()) {
                            _missionFlightStatus.totalTime += hoverTime;
                            _missionFlightStatus.hoverTime += hoverTime;
                            _missionFlightStatus.hoverDistance += distance;
                        } else {
                            _missionFlightStatus.totalTime += cruiseTime;
                            _missionFlightStatus.cruiseTime += cruiseTime;
                            _missionFlightStatus.cruiseDistance += distance;

                        }
1046
                    }
1047
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1048

1049
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
                    _missionFlightStatus.totalDistance += distance;
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(settingsItem->exitCoordinate()));

                    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;

                        }
                    }
1079
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1080 1081

                item->setMissionFlightStatus(_missionFlightStatus);
1082
            }
1083 1084

            lastCoordinateItem = item;
1085 1086
        }
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1087
    lastCoordinateItem->setMissionVehicleYaw(lastVehicleYaw);
1088 1089


DonLakeFlyer's avatar
DonLakeFlyer committed
1090 1091 1092 1093 1094 1095 1096
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1097

1098 1099
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1100 1101
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1102 1103 1104

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1105
            if (item->coordinateHasRelativeAltitude()) {
1106 1107 1108 1109 1110 1111
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1112
            }
1113 1114 1115 1116
        }
    }
}

1117 1118 1119
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1120 1121 1122 1123 1124 1125
    // 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));

1126 1127
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1128 1129 1130
    }
}

1131 1132 1133
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1134
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1135 1136 1137

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

1138 1139
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1140 1141 1142 1143 1144

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1145
        } else if (item->isSimpleItem()) {
1146 1147 1148 1149 1150
            currentParentItem->childItems()->append(item);
        }
    }
}

1151 1152
void MissionController::_recalcAll(void)
{
1153
    _recalcSequence();
1154 1155 1156 1157
    _recalcChildItems();
    _recalcWaypointLines();
}

1158
/// Initializes a new set of mission items
1159
void MissionController::_initAllVisualItems(void)
1160
{
1161
    MissionSettingsComplexItem* settingsItem = NULL;
1162 1163 1164

    // Setup home position at index 0

1165 1166 1167
    settingsItem = qobject_cast<MissionSettingsComplexItem*>(_visualItems->get(0));
    if (!settingsItem) {
        qWarning() << "First item not MissionSettingsComplexItem";
1168 1169
        return;
    }
1170

1171 1172
    settingsItem->setShowHomePosition(_editMode);
    settingsItem->setIsCurrentItem(true);
1173 1174

    if (!_editMode && _activeVehicle && _activeVehicle->homePositionAvailable()) {
1175 1176
        settingsItem->setCoordinate(_activeVehicle->homePosition());
        settingsItem->setShowHomePosition(true);
1177
    }
1178

1179 1180
    emit plannedHomePositionChanged(plannedHomePosition());

1181
    connect(settingsItem, &VisualMissionItem::coordinateChanged, this, &MissionController::_homeCoordinateChanged);
1182

1183 1184 1185 1186
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1187

1188
    _recalcAll();
1189

1190
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1191 1192 1193
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1194

1195
    _visualItems->setDirty(false);
1196 1197
}

1198
void MissionController::_deinitAllVisualItems(void)
1199
{
1200 1201
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1202 1203
    }

1204
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1205
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1206 1207
}

1208
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1209
{
1210 1211
    _visualItems->setDirty(false);

1212
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1213 1214
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1215 1216
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1217
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1218

1219 1220 1221 1222 1223 1224 1225 1226
    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";
        }
1227 1228
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1229
        if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1230
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcMissionFlightStatus);
1231 1232 1233
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1234
    }
1235 1236
}

1237
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1238
{
1239 1240
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1241 1242
}

1243
void MissionController::_itemCommandChanged(void)
1244
{
1245 1246
    _recalcChildItems();
    _recalcWaypointLines();
1247 1248
}

1249
void MissionController::_activeVehicleBeingRemoved(void)
1250
{
1251
    qCDebug(MissionControllerLog) << "MissionController::_activeVehicleBeingRemoved";
1252

1253
    MissionManager* missionManager = _activeVehicle->missionManager();
1254 1255 1256 1257

    disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailableFromVehicle);
    disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
    disconnect(missionManager, &MissionManager::currentItemChanged,         this, &MissionController::_currentMissionItemChanged);
1258 1259
    disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged,      this, &MissionController::_activeVehicleHomePositionAvailableChanged);
    disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
Don Gagne's avatar
Don Gagne committed
1260

Don Gagne's avatar
Don Gagne committed
1261 1262
    // 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
1263 1264
    removeAll();
}
Don Gagne's avatar
Don Gagne committed
1265

1266 1267 1268 1269 1270
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();
1271

1272 1273 1274 1275 1276 1277 1278
    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::homePositionAvailableChanged,     this, &MissionController::_activeVehicleHomePositionAvailableChanged);
    connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);
DonLakeFlyer's avatar
DonLakeFlyer committed
1279 1280
    connect(_activeVehicle, &Vehicle::defaultCruiseSpeedChanged,        this, &MissionController::_recalcMissionFlightStatus);
    connect(_activeVehicle, &Vehicle::defaultHoverSpeedChanged,         this, &MissionController::_recalcMissionFlightStatus);
1281

1282
    if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
1283 1284 1285
        // 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();
1286
    }
1287

1288 1289
    _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
    _activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
1290 1291 1292 1293
}

void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
1294
    if (!_editMode && _visualItems) {
1295
        MissionSettingsComplexItem* settingsItem = qobject_cast<MissionSettingsComplexItem*>(_visualItems->get(0));
1296

1297 1298
        if (settingsItem) {
            settingsItem->setShowHomePosition(homePositionAvailable);
1299
            emit plannedHomePositionChanged(plannedHomePosition());
1300 1301
            _recalcWaypointLines();
        } else {
1302
            qWarning() << "First item is not MissionSettingsComplexItem";
1303
        }
1304
    }
1305 1306 1307 1308
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
1309
    if (!_editMode && _visualItems) {
1310 1311 1312 1313 1314
        MissionSettingsComplexItem* settingsItem = qobject_cast<MissionSettingsComplexItem*>(_visualItems->get(0));
        if (settingsItem) {
            if (settingsItem->coordinate() != homePosition) {
                settingsItem->setCoordinate(homePosition);
                settingsItem->setShowHomePosition(true);
1315 1316 1317 1318 1319
                qCDebug(MissionControllerLog) << "Home position update" << homePosition;
                emit plannedHomePositionChanged(plannedHomePosition());
                _recalcWaypointLines();
            }
        } else {
1320
            qWarning() << "First item is not MissionSettingsComplexItem";
1321
        }
1322
    }
1323 1324
}

1325 1326
void MissionController::_setMissionMaxTelemetry(double missionMaxTelemetry)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1327 1328 1329
    if (!qFuzzyCompare(_missionFlightStatus.maxTelemetryDistance, missionMaxTelemetry)) {
        _missionFlightStatus.maxTelemetryDistance = missionMaxTelemetry;
        emit missionMaxTelemetryChanged(missionMaxTelemetry);
1330 1331 1332 1333
    }
}

void MissionController::_setMissionDistance(double missionDistance)
1334
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1335 1336 1337
    if (!qFuzzyCompare(_missionFlightStatus.totalDistance, missionDistance)) {
        _missionFlightStatus.totalDistance = missionDistance;
        emit missionDistanceChanged(missionDistance);
1338 1339 1340
    }
}

1341
void MissionController::_setMissionTime(double missionTime)
1342
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1343 1344
    if (!qFuzzyCompare(_missionFlightStatus.totalTime, missionTime)) {
        _missionFlightStatus.totalTime = missionTime;
1345 1346 1347 1348 1349 1350
        emit missionTimeChanged();
    }
}

void MissionController::_setMissionHoverTime(double missionHoverTime)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1351 1352
    if (!qFuzzyCompare(_missionFlightStatus.hoverTime, missionHoverTime)) {
        _missionFlightStatus.hoverTime = missionHoverTime;
1353
        emit missionHoverTimeChanged();
1354 1355 1356
    }
}

1357
void MissionController::_setMissionHoverDistance(double missionHoverDistance)
1358
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1359 1360 1361
    if (!qFuzzyCompare(_missionFlightStatus.hoverDistance, missionHoverDistance)) {
        _missionFlightStatus.hoverDistance = missionHoverDistance;
        emit missionHoverDistanceChanged(missionHoverDistance);
1362 1363 1364
    }
}

1365
void MissionController::_setMissionCruiseTime(double missionCruiseTime)
1366
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1367 1368
    if (!qFuzzyCompare(_missionFlightStatus.cruiseTime, missionCruiseTime)) {
        _missionFlightStatus.cruiseTime = missionCruiseTime;
1369 1370 1371 1372 1373 1374
        emit missionCruiseTimeChanged();
    }
}

void MissionController::_setMissionCruiseDistance(double missionCruiseDistance)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1375 1376 1377
    if (!qFuzzyCompare(_missionFlightStatus.cruiseDistance, missionCruiseDistance)) {
        _missionFlightStatus.cruiseDistance = missionCruiseDistance;
        emit missionCruiseDistanceChanged(missionCruiseDistance);
1378 1379 1380
    }
}

1381
void MissionController::_inProgressChanged(bool inProgress)
1382
{
1383
    emit syncInProgressChanged(inProgress);
1384
}
1385

1386
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
1387
{
1388 1389 1390
    bool        found = false;
    double      foundAltitude;
    MAV_FRAME   foundFrame;
1391

1392 1393 1394 1395 1396 1397
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1400 1401 1402
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1403
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
1404 1405 1406
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1407
                    break;
1408 1409
                }
            }
1410 1411 1412
        }
    }

1413
    if (found) {
1414 1415
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1416 1417 1418
    }

    return found;
1419
}
1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432

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

1433 1434
/// Add the Mission Settings complex item to the front of the items
void MissionController::_addMissionSettings(Vehicle* vehicle, QmlObjectListModel* visualItems, bool addToCenter)
1435
{
1436 1437
    bool homePositionSet = false;

1438 1439
    MissionSettingsComplexItem* settingsItem = new MissionSettingsComplexItem(vehicle, visualItems);
    visualItems->insert(0, settingsItem);
1440

1441
    if (visualItems->count() > 1  && addToCenter) {
1442 1443 1444 1445
        double north = 0.0;
        double south = 0.0;
        double east  = 0.0;
        double west  = 0.0;
1446
        bool firstCoordSet = false;
1447

1448 1449 1450 1451 1452 1453 1454 1455
        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);
1456 1457
                    east  = fmax(east, lon);
                    west  = fmin(west, lon);
1458 1459 1460 1461
                } else {
                    firstCoordSet = true;
                    north = _normalizeLat(item->coordinate().latitude());
                    south = north;
1462 1463
                    east  = _normalizeLon(item->coordinate().longitude());
                    west  = east;
1464 1465 1466
                }
            }
        }
1467

1468 1469
        if (firstCoordSet) {
            homePositionSet = true;
1470
            settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
1471
        }
1472
    }
1473

1474
    if (!homePositionSet) {
1475
        settingsItem->setCoordinate(qgcApp()->lastKnownHomePosition());
1476 1477
    }
}
1478 1479 1480 1481 1482 1483 1484 1485

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

1486 1487
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1488 1489 1490 1491
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
    }
}
1492

1493
bool MissionController::syncInProgress(void) const
1494
{
1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507
    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);
1508
    }
1509
}
1510 1511 1512 1513

QGeoCoordinate MissionController::plannedHomePosition(void)
{
    if (_visualItems && _visualItems->count() > 0) {
1514 1515 1516
        MissionSettingsComplexItem* settingsItem = qobject_cast<MissionSettingsComplexItem*>(_visualItems->get(0));
        if (settingsItem && settingsItem->showHomePosition()) {
            return settingsItem->coordinate();
1517 1518 1519 1520 1521 1522 1523 1524 1525
        }
    }

    return QGeoCoordinate();
}

void MissionController::_homeCoordinateChanged(void)
{
    emit plannedHomePositionChanged(plannedHomePosition());
DonLakeFlyer's avatar
DonLakeFlyer committed
1526
    _recalcMissionFlightStatus();
1527
}
1528 1529 1530 1531 1532

QString MissionController::fileExtension(void) const
{
    return QGCApplication::missionFileExtension;
}
1533

1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554 1555 1556
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;

        MissionSettingsComplexItem* settingsItem = qobject_cast<MissionSettingsComplexItem*>(visualItem);
        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++;
    }
}
1557 1558 1559 1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572

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