MissionController.cc 56.6 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 208
        double      prevAltitude;
        MAV_FRAME   prevFrame;
209

210 211 212
        if (_findPreviousAltitude(i, &prevAltitude, &prevFrame)) {
            newItem->missionItem().setFrame(prevFrame);
            newItem->missionItem().setParam7(prevAltitude);
213
        }
214
    }
215
    _visualItems->insert(i, newItem);
216 217 218

    _recalcAll();

219
    return newItem->sequenceNumber();
220 221
}

222
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
223
{
224 225
    ComplexMissionItem* newItem;

226
    int sequenceNumber = _nextSequenceNumber();
227 228 229 230 231 232 233 234
    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;
    }
235
    newItem->setSequenceNumber(sequenceNumber);
236
    newItem->setCoordinate(mapCenterCoordinate);
237
    _initVisualItem(newItem);
238

239 240
    _visualItems->insert(i, newItem);
    _complexItems->append(newItem);
241 242 243

    _recalcAll();

244
    return newItem->sequenceNumber();
245 246
}

247 248
void MissionController::removeMissionItem(int index)
{
249
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
250

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

    _recalcAll();

    // Set the new current item

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

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

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

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

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

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

332 333 334 335 336
    // 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];
337

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

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

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

    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()) {
365
            SurveyMissionItem* complexItem = qobject_cast<SurveyMissionItem*>(complexItems->get(nextComplexItemIndex));
366 367 368 369 370 371 372 373 374 375 376 377 378 379

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

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

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

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

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

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

    return true;
}

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

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

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

Don Gagne's avatar
Don Gagne committed
446
    SimpleMissionItem* homeItem = new SimpleMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
447 448 449 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
    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
476
            SimpleMissionItem* simpleItem = new SimpleMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492
            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
493
                SurveyMissionItem* surveyItem = new SurveyMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513
                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
514
            if ((MAV_CMD)doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537
                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
538
bool MissionController::_loadTextMissionFile(Vehicle* vehicle, QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558
{
    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
559
            SimpleMissionItem* item = new SimpleMissionItem(vehicle, visualItems);
560 561

            if (item->load(stream)) {
562
                visualItems->append(item);
563 564 565 566 567 568 569 570 571 572
            } 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;
    }

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

576 577 578 579 580
        // 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
581 582
            }
        }
583 584 585
    }

    return true;
586 587
}

588
void MissionController::loadFromFile(const QString& filename)
589
{
Don Gagne's avatar
Don Gagne committed
590 591 592 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
    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;

620 621 622
    QString errorString;

    if (filename.isEmpty()) {
Don Gagne's avatar
Don Gagne committed
623
        return false;
624 625
    }

Don Gagne's avatar
Don Gagne committed
626 627
    *visualItems = new QmlObjectListModel();
    *complexItems = new QmlObjectListModel();
628 629 630 631

    QFile file(filename);

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

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

646
    if (!errorString.isEmpty()) {
Don Gagne's avatar
Don Gagne committed
647 648
        (*visualItems)->deleteLater();
        (*complexItems)->deleteLater();
649

650
        qgcApp()->showMessage(errorString);
Don Gagne's avatar
Don Gagne committed
651
        return false;
652 653
    }

Don Gagne's avatar
Don Gagne committed
654
    return true;
655 656
}

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

    if (filename.isEmpty()) {
        return;
    }
665
    loadFromFile(filename);
666 667 668
#endif
}

669
void MissionController::saveToFile(const QString& filename)
670 671
{
    qDebug() << filename;
672 673 674 675

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

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

682
    QFile file(missionFilename);
683

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

Don Gagne's avatar
Don Gagne committed
689
        missionFileObject[JsonHelper::jsonVersionKey] =         _missionFileVersion;
690
        missionFileObject[JsonHelper::jsonGroundStationKey] =   JsonHelper::jsonGroundStationValue;
691

692
        // Mission settings
693

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

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

712
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
713
            visualItem->save(itemObject);
Don Gagne's avatar
Don Gagne committed
714
            rgMissionItems.append(itemObject);
715
        }
Don Gagne's avatar
Don Gagne committed
716
        missionFileObject[_jsonItemsKey] = rgMissionItems;
717 718

        QJsonDocument saveDoc(missionFileObject);
719
        file.write(saveDoc.toJson());
720 721
    }

722
    _visualItems->setDirty(false);
723 724
}

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

    if (filename.isEmpty()) {
        return;
    }
733
    saveToFile(filename);
734
#endif
735 736
}

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

    // Convert to fixed altitudes

745
    qCDebug(MissionControllerLog) << homeAlt
746 747
                                  << currentItem->coordinateHasRelativeAltitude() << currentItem->coordinate().altitude()
                                  << prevItem->exitCoordinateHasRelativeAltitude() << prevItem->exitCoordinate().altitude();
748

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

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

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

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

    distanceOk = true;

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

780
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
781 782
}

783 784
void MissionController::_recalcWaypointLines(void)
{
785 786 787 788 789 790 791 792 793 794
    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();
795 796 797

    qCDebug(MissionControllerLog) << "_recalcWaypointLines";

Nate Weibley's avatar
Nate Weibley committed
798 799
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
800 801 802 803 804 805 806
    _waypointLines.clear();

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


807
        // If we still haven't found the first coordinate item and we hit a takeoff command, link back to home
808 809
        if (firstCoordinateItem &&
                item->isSimpleItem() &&
810 811
                (qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF ||
                 qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) {
812 813 814 815 816 817 818 819 820 821
            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
822
                        _linesTable[pair] = old_table.take(pair);
823 824 825 826
                    } 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
827
                                endNotifier    = &VisualMissionItem::coordinateChanged;
828 829 830 831 832 833 834
                        // 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
835
                        _linesTable[pair] = linevect;
836 837 838 839 840 841 842 843 844 845 846
                    }
                }
                lastCoordinateItem = item;
            }
        }
    }


    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
847 848
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
849 850 851 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
            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";
    }

878
    bool showHomePosition =  homeItem->showHomePosition();
879 880 881

    qCDebug(MissionControllerLog) << "_recalcAltitudeRangeBearing";

882 883 884
    // 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.
885

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

891 892
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
893
    const double homePositionAltitude = homeItem->coordinate().altitude();
894 895
    minAltSeen = maxAltSeen = homeItem->coordinate().altitude();

896 897
    double missionDistance = 0.0;
    double missionMaxTelemetry = 0.0;
898 899 900 901 902 903 904
    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();
905

906 907
    bool vtolVehicle = _activeVehicle->vtol();
    bool vtolInHover = true;
908

Don Gagne's avatar
Don Gagne committed
909
    bool linkBackToHome = false;
910

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

916 917
        // Assume the worst
        item->setAzimuth(0.0);
918
        item->setDistance(0.0);
919

920 921 922 923 924 925 926 927 928 929
        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;
                }
            }
930 931
        }

932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954
        // 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;
955 956
                }
            }
957 958 959
                break;
            default:
                break;
960
            }
Don Gagne's avatar
Don Gagne committed
961 962
        }

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

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

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

988
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
989 990 991
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
992 993

                    missionDistance += distance;
994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007
                    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;
1008 1009
                        }
                    } else {
1010
                        missionTime += distance / (_activeVehicle->multiRotor() ? currentHoverSpeed : currentCruiseSpeed);
1011
                    }
1012
                }
1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023
                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);
1024
                }
1025
            }
1026 1027

            lastCoordinateItem = item;
1028 1029 1030
        }
    }

1031 1032 1033 1034 1035 1036 1037
    _setMissionMaxTelemetry(missionMaxTelemetry);
    _setMissionDistance(missionDistance);
    _setMissionTime(missionTime);
    _setMissionHoverDistance(vtolHoverDistance);
    _setMissionHoverTime(vtolHoverTime);
    _setMissionCruiseDistance(vtolCruiseDistance);
    _setMissionCruiseTime(vtolCruiseTime);
1038

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

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

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

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

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

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

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

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

1100 1101
void MissionController::_recalcAll(void)
{
1102
    _recalcSequence();
1103 1104 1105 1106
    _recalcChildItems();
    _recalcWaypointLines();
}

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

    // Setup home position at index 0

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

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

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

1131 1132 1133 1134
    emit plannedHomePositionChanged(plannedHomePosition());

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

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

1140 1141 1142
        // Set up complex item list
        if (!item->isSimpleItem()) {
            ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);
1143

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

1152 1153 1154 1155
    if (_complexItems) {
        _complexItems->deleteLater();
    }
    _complexItems = newComplexItems;
1156

1157
    _recalcAll();
1158

1159 1160
    emit visualItemsChanged();
    emit complexVisualItemsChanged();
1161

1162
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1163

1164
    _visualItems->setDirty(false);
1165 1166
}

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

1173
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1174 1175
}

1176
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1177
{
1178 1179
    _visualItems->setDirty(false);

1180
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1181 1182
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
1183
    connect(visualItem, &VisualMissionItem::flightSpeedChanged,                         this, &MissionController::_recalcAltitudeRangeBearing);
1184

1185 1186 1187 1188 1189 1190 1191 1192
    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";
        }
1193 1194 1195 1196
    } 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);
1197
        connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcAltitudeRangeBearing);
1198
    }
1199 1200
}

1201
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1202
{
1203 1204
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1205 1206
}

1207
void MissionController::_itemCommandChanged(void)
1208
{
1209 1210
    _recalcChildItems();
    _recalcWaypointLines();
1211 1212
}

1213
void MissionController::_activeVehicleBeingRemoved(void)
1214
{
1215
    qCDebug(MissionControllerLog) << "MissionController::_activeVehicleBeingRemoved";
1216

1217
    MissionManager* missionManager = _activeVehicle->missionManager();
1218 1219 1220 1221

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

Don Gagne's avatar
Don Gagne committed
1225 1226
    // 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
1227 1228
    removeAll();
}
Don Gagne's avatar
Don Gagne committed
1229

1230 1231 1232 1233 1234
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();
1235

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

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

1252 1253
    _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
    _activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
1254 1255 1256 1257
}

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

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

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
1273
    if (!_editMode && _visualItems) {
1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284
        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";
        }
1285
    }
1286 1287
}

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

void MissionController::_setMissionDistance(double missionDistance)
1297 1298 1299 1300 1301 1302 1303
{
    if (!qFuzzyCompare(_missionDistance, missionDistance)) {
        _missionDistance = missionDistance;
        emit missionDistanceChanged(_missionDistance);
    }
}

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

void MissionController::_setMissionHoverTime(double missionHoverTime)
{
    if (!qFuzzyCompare(_missionHoverTime, missionHoverTime)) {
        _missionHoverTime = missionHoverTime;
        emit missionHoverTimeChanged();
1317 1318 1319
    }
}

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

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

void MissionController::_setMissionCruiseDistance(double missionCruiseDistance)
{
    if (!qFuzzyCompare(_missionCruiseDistance, missionCruiseDistance)) {
        _missionCruiseDistance = missionCruiseDistance;
        emit missionCruiseDistanceChanged(_missionCruiseDistance);
1341 1342 1343
    }
}

1344
void MissionController::_inProgressChanged(bool inProgress)
1345
{
1346
    emit syncInProgressChanged(inProgress);
1347
}
1348

1349
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
1350
{
1351 1352 1353
    bool        found = false;
    double      foundAltitude;
    MAV_FRAME   foundFrame;
1354

1355 1356 1357 1358 1359 1360
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1363 1364 1365
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1366
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
1367 1368 1369
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1370
                    break;
1371 1372
                }
            }
1373 1374 1375
        }
    }

1376
    if (found) {
1377 1378
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1379 1380 1381
    }

    return found;
1382
}
1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396

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
1397
void MissionController::_addPlannedHomePosition(Vehicle* vehicle, QmlObjectListModel* visualItems, bool addToCenter)
1398
{
1399 1400
    bool homePositionSet = false;

Don Gagne's avatar
Don Gagne committed
1401
    SimpleMissionItem* homeItem = new SimpleMissionItem(vehicle, visualItems);
1402
    visualItems->insert(0, homeItem);
1403

1404
    if (visualItems->count() > 1  && addToCenter) {
1405 1406
        double north, south, east, west;
        bool firstCoordSet = false;
1407

1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427
        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;
                }
            }
        }
1428

1429 1430 1431
        if (firstCoordSet) {
            homePositionSet = true;
            homeItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
1432
        }
1433
    }
1434

1435
    if (!homePositionSet) {
1436 1437 1438
        homeItem->setCoordinate(qgcApp()->lastKnownHomePosition());
    }
}
1439 1440 1441 1442 1443 1444 1445 1446

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

1447 1448
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1449 1450 1451 1452
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
    }
}
1453

1454
bool MissionController::syncInProgress(void) const
1455
{
1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468
    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);
1469
    }
1470
}
1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488

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();
}
1489 1490 1491 1492 1493

QString MissionController::fileExtension(void) const
{
    return QGCApplication::missionFileExtension;
}
1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511

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