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

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

30 31
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

32

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 52
    , _visualItems(NULL)
    , _complexItems(NULL)
53
    , _firstItemsFromVehicle(false)
54 55
    , _missionItemsRequested(false)
    , _queuedSend(false)
56
    , _missionDistance(0.0)
57 58 59 60 61
    , _missionTime(0.0)
    , _missionHoverDistance(0.0)
    , _missionHoverTime(0.0)
    , _missionCruiseDistance(0.0)
    , _missionCruiseTime(0.0)
62
    , _missionMaxTelemetry(0.0)
63
{
64 65 66
    _surveyMissionItemName = tr("Survey");
    _fwLandingMissionItemName = tr("Fixed Wing Landing");
    _complexMissionItemNames << _surveyMissionItemName << _fwLandingMissionItemName;
67 68 69 70
}

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

72 73 74 75
}

void MissionController::start(bool editMode)
{
76 77
    qCDebug(MissionControllerLog) << "start editMode" << editMode;

78
    PlanElementController::start(editMode);
79 80 81 82 83 84
    _init();
}

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

86 87 88 89 90 91
    PlanElementController::startStaticActiveVehicle(vehicle);
    _init();
}

void MissionController::_init(void)
{
92
    // We start with an empty mission
93
    _visualItems = new QmlObjectListModel(this);
Don Gagne's avatar
Don Gagne committed
94
    _addPlannedHomePosition(_activeVehicle, _visualItems, false /* addToCenter */);
95
    _initAllVisualItems();
96 97
}

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

103
    if (!_editMode || _missionItemsRequested || _visualItems->count() == 1) {
104
        // Fly Mode:
Don Gagne's avatar
Don Gagne committed
105
        //      - Always accepts new items from the vehicle so Fly view is kept up to date
106 107
        // Edit Mode:
        //      - Either a load from vehicle was manually requested or
Don Gagne's avatar
Don Gagne committed
108
        //      - The initial automatic load from a vehicle completed and the current editor is empty
109

110 111
        QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
        const QList<MissionItem*>& newMissionItems = _activeVehicle->missionManager()->missionItems();
112

113 114 115 116 117 118 119
        qCDebug(MissionControllerLog) << "loading from vehicle: count"<< _visualItems->count();
        foreach(const MissionItem* missionItem, newMissionItems) {
            newControllerMissionItems->append(new SimpleMissionItem(_activeVehicle, *missionItem, this));
        }

        _deinitAllVisualItems();

Don Gagne's avatar
Don Gagne committed
120
        _visualItems->deleteLater();
121 122 123
        _visualItems = newControllerMissionItems;

        if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
Don Gagne's avatar
Don Gagne committed
124
            _addPlannedHomePosition(_activeVehicle, _visualItems,true /* addToCenter */);
125 126
        }

127
        _missionItemsRequested = false;
128

129
        _initAllVisualItems();
130
        emit newItemsFromVehicle();
131 132 133
    }
}

134
void MissionController::loadFromVehicle(void)
135
{
136
    Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
137

138 139 140 141 142 143
    if (activeVehicle) {
        _missionItemsRequested = true;
        activeVehicle->missionManager()->requestMissionItems();
    }
}

144
void MissionController::sendToVehicle(void)
145
{
Don Gagne's avatar
Don Gagne committed
146 147 148 149 150 151 152
    sendItemsToVehicle(_activeVehicle, _visualItems);
    _visualItems->setDirty(false);
}

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

Don Gagne's avatar
Don Gagne committed
156 157
        for (int i=0; i<visualMissionItems->count(); i++) {
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(visualMissionItems->get(i));
158
            if (visualItem->isSimpleItem()) {
159
                missionItems.append(new MissionItem(qobject_cast<SimpleMissionItem*>(visualItem)->missionItem()));
160
            } else {
161
                ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
162 163 164
                QmlObjectListModel* complexMissionItems = complexItem->getMissionItems();
                for (int j=0; j<complexMissionItems->count(); j++) {
                    missionItems.append(new MissionItem(*qobject_cast<MissionItem*>(complexMissionItems->get(j))));
165
                }
Don Gagne's avatar
Don Gagne committed
166
                complexMissionItems->deleteLater();
167 168 169
            }
        }

Don Gagne's avatar
Don Gagne committed
170
        vehicle->missionManager()->writeMissionItems(missionItems);
171 172

        for (int i=0; i<missionItems.count(); i++) {
Don Gagne's avatar
Don Gagne committed
173
            missionItems[i]->deleteLater();
174
        }
175 176
    }
}
177

178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
        VisualMissionItem* lastItem = qobject_cast<VisualMissionItem*>(_visualItems->get(_visualItems->count() - 1));

        if (lastItem->isSimpleItem()) {
            return lastItem->sequenceNumber() + 1;
        } else {
            return qobject_cast<ComplexMissionItem*>(lastItem)->lastSequenceNumber() + 1;
        }
    }
}

194
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
195
{
196
    int sequenceNumber = _nextSequenceNumber();
197
    SimpleMissionItem * newItem = new SimpleMissionItem(_activeVehicle, this);
198
    newItem->setSequenceNumber(sequenceNumber);
199
    newItem->setCoordinate(coordinate);
200 201 202
    newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
    _initVisualItem(newItem);
    if (_visualItems->count() == 1) {
203 204
        newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
    }
205
    newItem->setDefaultsForCommand();
Don Gagne's avatar
Don Gagne committed
206
    if ((MAV_CMD)newItem->command() == MAV_CMD_NAV_WAYPOINT) {
207
        double lastValue;
208
        MAV_FRAME lastFrame;
209 210

        if (_findLastAcceptanceRadius(&lastValue)) {
211
            newItem->missionItem().setParam2(lastValue);
212
        }
213 214
        if (_findLastAltitude(&lastValue, &lastFrame)) {
            newItem->missionItem().setFrame(lastFrame);
215
            newItem->missionItem().setParam7(lastValue);
216
        }
217
    }
218
    _visualItems->insert(i, newItem);
219 220 221

    _recalcAll();

222
    return newItem->sequenceNumber();
223 224
}

225
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
226
{
227 228
    ComplexMissionItem* newItem;

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

242 243
    _visualItems->insert(i, newItem);
    _complexItems->append(newItem);
244 245 246

    _recalcAll();

247
    return newItem->sequenceNumber();
248 249
}

250 251
void MissionController::removeMissionItem(int index)
{
252
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
253

254 255 256
    _deinitVisualItem(item);
    if (!item->isSimpleItem()) {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(_complexItems->removeOne(item));
257
        if (!complexItem) {
258 259 260
            qWarning() << "Complex item missing";
        }
    }
261
    item->deleteLater();
262 263 264 265 266

    _recalcAll();

    // Set the new current item

267
    if (index >= _visualItems->count()) {
268 269
        index--;
    }
270
    for (int i=0; i<_visualItems->count(); i++) {
Don Gagne's avatar
Don Gagne committed
271
        VisualMissionItem* item =  qobject_cast<VisualMissionItem*>(_visualItems->get(i));
272 273
        item->setIsCurrentItem(i == index);
    }
274
    _visualItems->setDirty(true);
275 276
}

277
void MissionController::removeAll(void)
278
{
279 280
    if (_visualItems) {
        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
281
        _visualItems->deleteLater();
282
        _visualItems = new QmlObjectListModel(this);
Don Gagne's avatar
Don Gagne committed
283
        _addPlannedHomePosition(_activeVehicle, _visualItems, false /* addToCenter */);
284
        _initAllVisualItems();
Don Gagne's avatar
Don Gagne committed
285
        _visualItems->setDirty(true);
286
    }
287
}
288

Don Gagne's avatar
Don Gagne committed
289
bool MissionController::_loadJsonMissionFile(Vehicle* vehicle, const QByteArray& bytes, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString)
290 291 292 293 294 295 296 297 298 299
{
    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
300 301 302
    // 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;
303 304
    }

Don Gagne's avatar
Don Gagne committed
305 306 307 308 309 310 311
    int fileVersion;
    if (!JsonHelper::validateQGCJsonFile(json,
                                         _jsonFileTypeValue,    // expected file type
                                         1,                     // minimum supported version
                                         2,                     // maximum supported version
                                         fileVersion,
                                         errorString)) {
312 313
        return false;
    }
314

Don Gagne's avatar
Don Gagne committed
315
    if (fileVersion == 1) {
Don Gagne's avatar
Don Gagne committed
316
        return _loadJsonMissionFileV1(vehicle, json, visualItems, complexItems, errorString);
Don Gagne's avatar
Don Gagne committed
317
    } else {
Don Gagne's avatar
Don Gagne committed
318
        return _loadJsonMissionFileV2(vehicle, json, visualItems, complexItems, errorString);
Don Gagne's avatar
Don Gagne committed
319 320 321
    }
}

Don Gagne's avatar
Don Gagne committed
322
bool MissionController::_loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
323 324 325 326 327 328 329 330 331
{
    // 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)) {
332 333 334
        return false;
    }

335 336 337 338 339
    // Read complex items
    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];
340

341 342 343 344 345
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

Don Gagne's avatar
Don Gagne committed
346
        SurveyMissionItem* item = new SurveyMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
347 348
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
349 350 351
            complexItems->append(item);
        } else {
            return false;
352
        }
353
    }
354

355 356 357 358 359
    // 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
360
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
361 362 363 364 365 366 367

    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << complexItems->count();
    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
        if (nextComplexItemIndex < complexItems->count()) {
368
            SurveyMissionItem* complexItem = qobject_cast<SurveyMissionItem*>(complexItems->get(nextComplexItemIndex));
369 370 371 372 373 374 375 376 377 378 379 380 381 382

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

383 384 385 386 387
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
388
            const QJsonObject itemObject = itemValue.toObject();
Don Gagne's avatar
Don Gagne committed
389
            SimpleMissionItem* item = new SimpleMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
390
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
391 392
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
                visualItems->append(item);
393 394 395
            } else {
                return false;
            }
396 397

            nextSequenceNumber++;
398
        }
Don Gagne's avatar
Don Gagne committed
399
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < complexItems->count());
400 401

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

Don Gagne's avatar
Don Gagne committed
404
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
405
            visualItems->insert(0, item);
406 407 408 409
        } else {
            return false;
        }
    } else {
Don Gagne's avatar
Don Gagne committed
410
        _addPlannedHomePosition(vehicle, visualItems, true /* addToCenter */);
411 412 413 414 415
    }

    return true;
}

Don Gagne's avatar
Don Gagne committed
416
bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
417 418 419 420 421 422
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
423 424 425
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
426 427 428 429 430 431 432
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

433
    // Mission Settings
Don Gagne's avatar
Don Gagne committed
434
    QGeoCoordinate homeCoordinate;
435
    SettingsManager* settingsManager = qgcApp()->toolbox()->settingsManager();
Don Gagne's avatar
Don Gagne committed
436 437 438
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
Don Gagne's avatar
Don Gagne committed
439
    if (json.contains(_jsonVehicleTypeKey) && vehicle->isOfflineEditingVehicle()) {
440
        settingsManager->offlineEditingVehicleType()->setRawValue(json[_jsonVehicleTypeKey].toDouble());
441 442
    }
    if (json.contains(_jsonCruiseSpeedKey)) {
443
        settingsManager->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
444 445
    }
    if (json.contains(_jsonHoverSpeedKey)) {
446
        settingsManager->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
447 448
    }

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

            if (item->load(stream)) {
565
                visualItems->append(item);
566 567 568 569 570 571 572 573 574 575
            } else {
                errorString = QStringLiteral("The mission file is corrupted.");
                return false;
            }
        }
    } else {
        errorString = QStringLiteral("The mission file is not compatible with this version of QGroundControl.");
        return false;
    }

576
    if (addPlannedHomePosition || visualItems->count() == 0) {
Don Gagne's avatar
Don Gagne committed
577
        _addPlannedHomePosition(vehicle, visualItems, true /* addToCenter */);
Don Gagne's avatar
Don Gagne committed
578

579 580 581 582 583
        // 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
584 585
            }
        }
586 587 588
    }

    return true;
589 590
}

591
void MissionController::loadFromFile(const QString& filename)
592
{
Don Gagne's avatar
Don Gagne committed
593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622
    QmlObjectListModel* newVisualItems = NULL;
    QmlObjectListModel* newComplexItems = NULL;

    if (!loadItemsFromFile(_activeVehicle, filename, &newVisualItems, &newComplexItems)) {
        return;
    }

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

    _visualItems = newVisualItems;
    _complexItems = newComplexItems;

    if (_visualItems->count() == 0) {
        _addPlannedHomePosition(_activeVehicle, _visualItems, true /* addToCenter */);
    }

    _initAllVisualItems();
}

bool MissionController::loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems, QmlObjectListModel** complexItems)
{
    *visualItems = NULL;
    *complexItems = NULL;

623 624 625
    QString errorString;

    if (filename.isEmpty()) {
Don Gagne's avatar
Don Gagne committed
626
        return false;
627 628
    }

Don Gagne's avatar
Don Gagne committed
629 630
    *visualItems = new QmlObjectListModel();
    *complexItems = new QmlObjectListModel();
631 632 633 634

    QFile file(filename);

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

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

649
    if (!errorString.isEmpty()) {
Don Gagne's avatar
Don Gagne committed
650 651
        (*visualItems)->deleteLater();
        (*complexItems)->deleteLater();
652

653
        qgcApp()->showMessage(errorString);
Don Gagne's avatar
Don Gagne committed
654
        return false;
655 656
    }

Don Gagne's avatar
Don Gagne committed
657
    return true;
658 659
}

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

    if (filename.isEmpty()) {
        return;
    }
668
    loadFromFile(filename);
669 670 671
#endif
}

672
void MissionController::saveToFile(const QString& filename)
673 674
{
    qDebug() << filename;
675 676 677 678

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

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

685
    QFile file(missionFilename);
686

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

Don Gagne's avatar
Don Gagne committed
692
        missionFileObject[JsonHelper::jsonVersionKey] =         _missionFileVersion;
693
        missionFileObject[JsonHelper::jsonGroundStationKey] =   JsonHelper::jsonGroundStationValue;
694

695
        // Mission settings
696

697
        SimpleMissionItem* homeItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(0));
Don Gagne's avatar
Don Gagne committed
698
        if (!homeItem) {
699 700 701
            qgcApp()->showMessage(QStringLiteral("Internal error: VisualMissionItem at index 0 not SimpleMissionItem"));
            return;
        }
Don Gagne's avatar
Don Gagne committed
702 703 704
        QJsonValue coordinateValue;
        JsonHelper::saveGeoCoordinate(homeItem->coordinate(), true /* writeAltitude */, coordinateValue);
        missionFileObject[_jsonPlannedHomePositionKey] = coordinateValue;
705 706 707 708
        missionFileObject[_jsonFirmwareTypeKey] = _activeVehicle->firmwareType();
        missionFileObject[_jsonVehicleTypeKey] = _activeVehicle->vehicleType();
        missionFileObject[_jsonCruiseSpeedKey] = _activeVehicle->cruiseSpeed();
        missionFileObject[_jsonHoverSpeedKey] = _activeVehicle->hoverSpeed();
709

710
        // Save the visual items
Don Gagne's avatar
Don Gagne committed
711
        QJsonArray  rgMissionItems;
712
        for (int i=1; i<_visualItems->count(); i++) {
713 714
            QJsonObject itemObject;

715
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
716
            visualItem->save(itemObject);
Don Gagne's avatar
Don Gagne committed
717
            rgMissionItems.append(itemObject);
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 791 792 793 794 795 796 797
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

    SimpleMissionItem*  homeItem = qobject_cast<SimpleMissionItem*>(lastCoordinateItem);

    if (!homeItem) {
        qWarning() << "Home item is not SimpleMissionItem";
    }

    bool    showHomePosition =  homeItem->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 822 823 824
            linkBackToHome = true;
        }

        if (item->specifiesCoordinate()) {
            if (!item->isStandaloneCoordinate()) {
                firstCoordinateItem = false;
                VisualItemPair pair(lastCoordinateItem, item);
                if (lastCoordinateItem != homeItem || (showHomePosition && linkBackToHome)) {
                    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 837
                        // 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
                        connect(item, &VisualMissionItem::coordinateChanged, this, &MissionController::_recalcAltitudeRangeBearing);
Nate Weibley's avatar
Nate Weibley committed
838
                        _linesTable[pair] = linevect;
839 840 841 842 843 844 845 846 847 848 849
                    }
                }
                lastCoordinateItem = item;
            }
        }
    }


    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
850 851
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880
            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);

    _recalcAltitudeRangeBearing();

    emit waypointLinesChanged();
}

void MissionController::_recalcAltitudeRangeBearing()
{
    if (!_visualItems->count())
        return;

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

    if (!homeItem) {
        qWarning() << "Home item is not SimpleMissionItem";
    }

881
    bool showHomePosition =  homeItem->showHomePosition();
882 883 884

    qCDebug(MissionControllerLog) << "_recalcAltitudeRangeBearing";

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

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

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

899 900
    double missionDistance = 0.0;
    double missionMaxTelemetry = 0.0;
901 902 903 904 905 906 907
    double missionTime = 0.0;
    double vtolHoverTime = 0.0;
    double vtolCruiseTime = 0.0;
    double vtolHoverDistance = 0.0;
    double vtolCruiseDistance = 0.0;
    double currentCruiseSpeed = _activeVehicle->cruiseSpeed();
    double currentHoverSpeed = _activeVehicle->hoverSpeed();
908

909 910
    bool vtolVehicle = _activeVehicle->vtol();
    bool vtolInHover = true;
911

Don Gagne's avatar
Don Gagne committed
912
    bool linkBackToHome = false;
913

914 915
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
916 917 918
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

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

923 924 925 926 927 928 929 930 931 932
        if (simpleItem && simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_DO_CHANGE_SPEED) {
            // Adjust cruise speed for time calculations
            double newSpeed = simpleItem->missionItem().param2();
            if (newSpeed > 0) {
                if (_activeVehicle->multiRotor()) {
                    currentHoverSpeed = newSpeed;
                } else {
                    currentCruiseSpeed = newSpeed;
                }
            }
933 934
        }

935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957
        // 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
        if (simpleItem && vtolVehicle) {
            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;
958 959
                }
            }
960 961 962
                break;
            default:
                break;
963
            }
Don Gagne's avatar
Don Gagne committed
964 965
        }

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

969
            double absoluteAltitude = item->coordinate().altitude();
970
            if (item->coordinateHasRelativeAltitude()) {
971 972 973 974 975
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

976 977 978 979 980 981 982 983 984 985
            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
986
                firstCoordinateItem = false;
987 988 989
                if (lastCoordinateItem != homeItem || linkBackToHome) {
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
990

991
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
992 993 994
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
995 996

                    missionDistance += distance;
997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010
                    missionMaxTelemetry = qMax(missionMaxTelemetry, _calcDistanceToHome(item, homeItem));

                    // Calculate mission time
                    if (vtolVehicle) {
                        if (vtolInHover) {
                            double hoverTime = distance / _activeVehicle->hoverSpeed();
                            missionTime += hoverTime;
                            vtolHoverTime += hoverTime;
                            vtolHoverDistance += distance;
                        } else {
                            double cruiseTime = distance / currentCruiseSpeed;
                            missionTime += cruiseTime;
                            vtolCruiseTime += cruiseTime;
                            vtolCruiseDistance += distance;
1011 1012
                        }
                    } else {
1013
                        missionTime += distance / (_activeVehicle->multiRotor() ? currentHoverSpeed : currentCruiseSpeed);
1014
                    }
1015
                }
1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026
                if (complexItem) {
                    // Add in distance/time inside survey as well
                    // This code assumes all surveys are done cruise not hover
                    double complexDistance = complexItem->complexDistance();
                    double cruiseSpeed = _activeVehicle->multiRotor() ? currentHoverSpeed : currentCruiseSpeed;
                    missionDistance += complexDistance;
                    missionTime += complexDistance / cruiseSpeed;
                    missionMaxTelemetry = qMax(missionMaxTelemetry, complexItem->greatestDistanceTo(homeItem->exitCoordinate()));

                    // Let the complex item know the current cruise speed
                    complexItem->setCruiseSpeed(cruiseSpeed);
1027
                }
1028
            }
1029 1030

            lastCoordinateItem = item;
1031 1032 1033
        }
    }

1034 1035 1036 1037 1038 1039 1040
    _setMissionMaxTelemetry(missionMaxTelemetry);
    _setMissionDistance(missionDistance);
    _setMissionTime(missionTime);
    _setMissionHoverDistance(vtolHoverDistance);
    _setMissionHoverTime(vtolHoverTime);
    _setMissionCruiseDistance(vtolCruiseDistance);
    _setMissionCruiseTime(vtolCruiseTime);
1041

1042 1043
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1044 1045
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1046 1047 1048

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1049
            if (item->coordinateHasRelativeAltitude()) {
1050 1051 1052 1053 1054 1055
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1056
            }
1057 1058 1059 1060
        }
    }
}

1061 1062 1063
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1064 1065 1066 1067 1068 1069 1070 1071 1072
    // 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));

        item->setSequenceNumber(sequenceNumber++);
        if (!item->isSimpleItem()) {
            ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);
1073

1074
            if (complexItem) {
Don Gagne's avatar
Don Gagne committed
1075
                sequenceNumber = complexItem->lastSequenceNumber() + 1;
1076 1077 1078 1079
            } else {
                qWarning() << "isSimpleItem == false, yet not ComplexMissionItem";
            }
        }
1080 1081 1082
    }
}

1083 1084 1085
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1086
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1087 1088 1089

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

1090 1091
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1092 1093 1094 1095 1096

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1097
        } else if (item->isSimpleItem()) {
1098 1099 1100 1101 1102
            currentParentItem->childItems()->append(item);
        }
    }
}

1103 1104
void MissionController::_recalcAll(void)
{
1105
    _recalcSequence();
1106 1107 1108 1109
    _recalcChildItems();
    _recalcWaypointLines();
}

1110
/// Initializes a new set of mission items
1111
void MissionController::_initAllVisualItems(void)
1112
{
1113 1114 1115 1116 1117 1118 1119 1120 1121
    SimpleMissionItem* homeItem = NULL;

    // Setup home position at index 0

    homeItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(0));
    if (!homeItem) {
        qWarning() << "homeItem not SimpleMissionItem";
        return;
    }
1122

Don Gagne's avatar
Don Gagne committed
1123
    homeItem->setHomePositionSpecialCase(true);
1124
    homeItem->setShowHomePosition(_editMode);
1125 1126
    homeItem->missionItem().setCommand(MAV_CMD_NAV_WAYPOINT);
    homeItem->missionItem().setFrame(MAV_FRAME_GLOBAL);
1127 1128 1129 1130 1131
    homeItem->setIsCurrentItem(true);

    if (!_editMode && _activeVehicle && _activeVehicle->homePositionAvailable()) {
        homeItem->setCoordinate(_activeVehicle->homePosition());
        homeItem->setShowHomePosition(true);
1132
    }
1133

1134 1135 1136 1137
    emit plannedHomePositionChanged(plannedHomePosition());

    connect(homeItem, &VisualMissionItem::coordinateChanged, this, &MissionController::_homeCoordinateChanged);

1138
    QmlObjectListModel* newComplexItems = new QmlObjectListModel(this);
1139 1140 1141
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
1142

1143 1144 1145
        // Set up complex item list
        if (!item->isSimpleItem()) {
            ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);
1146

1147 1148 1149 1150 1151
            if (complexItem) {
                newComplexItems->append(item);
            } else {
                qWarning() << "isSimpleItem == false, but not ComplexMissionItem";
            }
1152
        }
1153 1154
    }

1155 1156 1157 1158
    if (_complexItems) {
        _complexItems->deleteLater();
    }
    _complexItems = newComplexItems;
1159

1160
    _recalcAll();
1161

1162 1163
    emit visualItemsChanged();
    emit complexVisualItemsChanged();
1164

1165
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1166

1167
    _visualItems->setDirty(false);
1168 1169
}

1170
void MissionController::_deinitAllVisualItems(void)
1171
{
1172 1173
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1174 1175
    }

1176
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1177 1178
}

1179
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1180
{
1181 1182
    _visualItems->setDirty(false);

1183
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1184 1185
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
1186
    connect(visualItem, &VisualMissionItem::flightSpeedChanged,                         this, &MissionController::_recalcAltitudeRangeBearing);
1187

1188 1189 1190 1191 1192 1193 1194 1195
    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";
        }
1196 1197 1198 1199
    } else {
        // We need to track changes of lastSequenceNumber so we can recalc sequence numbers for subsequence items
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
        connect(complexItem, &ComplexMissionItem::lastSequenceNumberChanged, this, &MissionController::_recalcSequence);
1200
        connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcAltitudeRangeBearing);
1201
    }
1202 1203
}

1204
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1205
{
1206 1207
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1208 1209
}

1210
void MissionController::_itemCommandChanged(void)
1211
{
1212 1213
    _recalcChildItems();
    _recalcWaypointLines();
1214 1215
}

1216
void MissionController::_activeVehicleBeingRemoved(void)
1217
{
1218
    qCDebug(MissionControllerLog) << "MissionController::_activeVehicleBeingRemoved";
1219

1220
    MissionManager* missionManager = _activeVehicle->missionManager();
1221 1222 1223 1224

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

Don Gagne's avatar
Don Gagne committed
1228 1229
    // 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
1230 1231
    removeAll();
}
Don Gagne's avatar
Don Gagne committed
1232

1233 1234 1235 1236 1237
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();
1238

1239 1240 1241 1242 1243 1244 1245
    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);
1246 1247
    connect(_activeVehicle, &Vehicle::cruiseSpeedChanged,               this, &MissionController::_recalcAltitudeRangeBearing);
    connect(_activeVehicle, &Vehicle::hoverSpeedChanged,                this, &MissionController::_recalcAltitudeRangeBearing);
1248

1249
    if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
1250 1251 1252
        // 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();
1253
    }
1254

1255 1256
    _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
    _activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
1257 1258 1259 1260
}

void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
1261 1262 1263 1264 1265
    if (!_editMode && _visualItems) {
        SimpleMissionItem* homeItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(0));

        if (homeItem) {
            homeItem->setShowHomePosition(homePositionAvailable);
1266
            emit plannedHomePositionChanged(plannedHomePosition());
1267 1268 1269 1270
            _recalcWaypointLines();
        } else {
            qWarning() << "Unabled to cast home item to SimpleMissionItem";
        }
1271
    }
1272 1273 1274 1275
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
1276
    if (!_editMode && _visualItems) {
1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
        if (item) {
            if (item->coordinate() != homePosition) {
                item->setCoordinate(homePosition);
                qCDebug(MissionControllerLog) << "Home position update" << homePosition;
                emit plannedHomePositionChanged(plannedHomePosition());
                _recalcWaypointLines();
            }
        } else {
            qWarning() << "Unabled to cast home item to VisualMissionItem";
        }
1288
    }
1289 1290
}

1291 1292 1293 1294 1295 1296 1297 1298 1299
void MissionController::_setMissionMaxTelemetry(double missionMaxTelemetry)
{
    if (!qFuzzyCompare(_missionMaxTelemetry, missionMaxTelemetry)) {
        _missionMaxTelemetry = missionMaxTelemetry;
        emit missionMaxTelemetryChanged(_missionMaxTelemetry);
    }
}

void MissionController::_setMissionDistance(double missionDistance)
1300 1301 1302 1303 1304 1305 1306
{
    if (!qFuzzyCompare(_missionDistance, missionDistance)) {
        _missionDistance = missionDistance;
        emit missionDistanceChanged(_missionDistance);
    }
}

1307
void MissionController::_setMissionTime(double missionTime)
1308
{
1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319
    if (!qFuzzyCompare(_missionTime, missionTime)) {
        _missionTime = missionTime;
        emit missionTimeChanged();
    }
}

void MissionController::_setMissionHoverTime(double missionHoverTime)
{
    if (!qFuzzyCompare(_missionHoverTime, missionHoverTime)) {
        _missionHoverTime = missionHoverTime;
        emit missionHoverTimeChanged();
1320 1321 1322
    }
}

1323
void MissionController::_setMissionHoverDistance(double missionHoverDistance)
1324
{
1325 1326 1327
    if (!qFuzzyCompare(_missionHoverDistance, missionHoverDistance)) {
        _missionHoverDistance = missionHoverDistance;
        emit missionHoverDistanceChanged(_missionHoverDistance);
1328 1329 1330
    }
}

1331
void MissionController::_setMissionCruiseTime(double missionCruiseTime)
1332
{
1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343
    if (!qFuzzyCompare(_missionCruiseTime, missionCruiseTime)) {
        _missionCruiseTime = missionCruiseTime;
        emit missionCruiseTimeChanged();
    }
}

void MissionController::_setMissionCruiseDistance(double missionCruiseDistance)
{
    if (!qFuzzyCompare(_missionCruiseDistance, missionCruiseDistance)) {
        _missionCruiseDistance = missionCruiseDistance;
        emit missionCruiseDistanceChanged(_missionCruiseDistance);
1344 1345 1346
    }
}

1347
void MissionController::_inProgressChanged(bool inProgress)
1348
{
1349
    emit syncInProgressChanged(inProgress);
1350
}
1351

1352
bool MissionController::_findLastAltitude(double* lastAltitude, MAV_FRAME* frame)
1353
{
1354
    bool found = false;
1355
    double foundAltitude;
1356
    MAV_FRAME foundFrame;
1357

1358
    // Don't use home position
1359
    for (int i=1; i<_visualItems->count(); i++) {
1360
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1361

1362 1363 1364 1365
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {

            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1366 1367 1368 1369
                if ((MAV_CMD)simpleItem->command() != MAV_CMD_NAV_TAKEOFF) {
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1370 1371
                }
            }
1372 1373 1374
        }
    }

1375 1376
    if (found) {
        *lastAltitude = foundAltitude;
1377
        *frame = foundFrame;
1378 1379 1380 1381 1382 1383 1384 1385 1386 1387
    }

    return found;
}

bool MissionController::_findLastAcceptanceRadius(double* lastAcceptanceRadius)
{
    bool found = false;
    double foundAcceptanceRadius;

1388 1389
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1390

1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401
        if (visualItem->isSimpleItem()) {
            SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);

            if (simpleItem) {
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
                    foundAcceptanceRadius = simpleItem->missionItem().param2();
                    found = true;
                }
            } else {
                qWarning() << "isSimpleItem == true, yet not SimpleMissionItem";
            }
1402 1403 1404 1405 1406 1407 1408 1409
        }
    }

    if (found) {
        *lastAcceptanceRadius = foundAcceptanceRadius;
    }

    return found;
1410
}
1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424

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

/// Add the home position item to the front of the list
Don Gagne's avatar
Don Gagne committed
1425
void MissionController::_addPlannedHomePosition(Vehicle* vehicle, QmlObjectListModel* visualItems, bool addToCenter)
1426
{
1427 1428
    bool homePositionSet = false;

Don Gagne's avatar
Don Gagne committed
1429
    SimpleMissionItem* homeItem = new SimpleMissionItem(vehicle, visualItems);
1430
    visualItems->insert(0, homeItem);
1431

1432
    if (visualItems->count() > 1  && addToCenter) {
1433 1434
        double north, south, east, west;
        bool firstCoordSet = false;
1435

1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 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);
                    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;
                }
            }
        }
1456

1457 1458 1459
        if (firstCoordSet) {
            homePositionSet = true;
            homeItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
1460
        }
1461
    }
1462

1463
    if (!homePositionSet) {
1464 1465 1466
        homeItem->setCoordinate(qgcApp()->lastKnownHomePosition());
    }
}
1467 1468 1469 1470 1471 1472 1473 1474

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

1475 1476
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1477 1478 1479 1480
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
    }
}
1481

1482
bool MissionController::syncInProgress(void) const
1483
{
1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496
    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);
1497
    }
1498
}
1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515 1516

QGeoCoordinate MissionController::plannedHomePosition(void)
{
    if (_visualItems && _visualItems->count() > 0) {
        SimpleMissionItem* item = qobject_cast<SimpleMissionItem*>(_visualItems->get(0));
        if (item && item->showHomePosition()) {
            return item->coordinate();
        }
    }

    return QGeoCoordinate();
}

void MissionController::_homeCoordinateChanged(void)
{
    emit plannedHomePositionChanged(plannedHomePosition());
    _recalcAltitudeRangeBearing();
}
1517 1518 1519 1520 1521

QString MissionController::fileExtension(void) const
{
    return QGCApplication::missionFileExtension;
}
1522 1523 1524 1525 1526 1527 1528 1529 1530 1531 1532 1533 1534 1535 1536 1537 1538 1539

double  MissionController::cruiseSpeed(void) const
{
    if (_activeVehicle) {
        return _activeVehicle->cruiseSpeed();
    } else {
        return 0.0f;
    }
}

double  MissionController::hoverSpeed(void) const
{
    if (_activeVehicle) {
        return _activeVehicle->hoverSpeed();
    } else {
        return 0.0f;
    }
}