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


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

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

31 32
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

33
const char* MissionController::_settingsGroup =                 "MissionController";
Don Gagne's avatar
Don Gagne committed
34 35
const char* MissionController::_jsonFileTypeValue =             "Mission";
const char* MissionController::_jsonItemsKey =                  "items";
36
const char* MissionController::_jsonPlannedHomePositionKey =    "plannedHomePosition";
Don Gagne's avatar
Don Gagne committed
37
const char* MissionController::_jsonFirmwareTypeKey =           "firmwareType";
38 39 40
const char* MissionController::_jsonVehicleTypeKey =            "vehicleType";
const char* MissionController::_jsonCruiseSpeedKey =            "cruiseSpeed";
const char* MissionController::_jsonHoverSpeedKey =             "hoverSpeed";
Don Gagne's avatar
Don Gagne committed
41 42 43 44 45 46 47
const char* MissionController::_jsonParamsKey =                 "params";

// Deprecated V1 format keys
const char* MissionController::_jsonComplexItemsKey =           "complexItems";
const char* MissionController::_jsonMavAutopilotKey =           "MAV_AUTOPILOT";

const int   MissionController::_missionFileVersion =            2;
48 49

MissionController::MissionController(QObject *parent)
50
    : PlanElementController(parent)
51
    , _visualItems(NULL)
52
    , _firstItemsFromVehicle(false)
53 54
    , _missionItemsRequested(false)
    , _queuedSend(false)
55
    , _missionDistance(0.0)
56 57 58 59 60
    , _missionTime(0.0)
    , _missionHoverDistance(0.0)
    , _missionHoverTime(0.0)
    , _missionCruiseDistance(0.0)
    , _missionCruiseTime(0.0)
61
    , _missionMaxTelemetry(0.0)
62
{
63 64 65
    _surveyMissionItemName = tr("Survey");
    _fwLandingMissionItemName = tr("Fixed Wing Landing");
    _complexMissionItemNames << _surveyMissionItemName << _fwLandingMissionItemName;
66 67 68 69
}

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

71 72 73 74
}

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

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

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

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

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

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

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

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

112 113 114 115 116 117 118
        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
119
        _visualItems->deleteLater();
120 121 122
        _visualItems = newControllerMissionItems;

        if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
123
            _addMissionSettings(_activeVehicle, _visualItems, true /* addToCenter */);
124 125
        }

126
        _missionItemsRequested = false;
127

128 129 130 131
        if (_editMode) {
            // Scan for mission settings
            MissionSettingsComplexItem::scanForMissionSettings(_visualItems, _activeVehicle);
        }
132

133
        _initAllVisualItems();
134
        emit newItemsFromVehicle();
135 136 137
    }
}

138
void MissionController::loadFromVehicle(void)
139
{
140
    Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
141

142 143 144 145 146 147
    if (activeVehicle) {
        _missionItemsRequested = true;
        activeVehicle->missionManager()->requestMissionItems();
    }
}

148
void MissionController::sendToVehicle(void)
149
{
Don Gagne's avatar
Don Gagne committed
150 151 152 153 154 155 156
    sendItemsToVehicle(_activeVehicle, _visualItems);
    _visualItems->setDirty(false);
}

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

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

Don Gagne's avatar
Don Gagne committed
174
        vehicle->missionManager()->writeMissionItems(missionItems);
175 176

        for (int i=0; i<missionItems.count(); i++) {
Don Gagne's avatar
Don Gagne committed
177
            missionItems[i]->deleteLater();
178
        }
179 180
    }
}
181

182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197
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;
        }
    }
}

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

214 215 216
        if (_findPreviousAltitude(i, &prevAltitude, &prevFrame)) {
            newItem->missionItem().setFrame(prevFrame);
            newItem->missionItem().setParam7(prevAltitude);
217
        }
218
    }
219
    _visualItems->insert(i, newItem);
220 221 222

    _recalcAll();

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

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

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

243
    _visualItems->insert(i, 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
    _deinitVisualItem(item);
255
    item->deleteLater();
256 257

    _recalcAll();
258
    _visualItems->setDirty(true);
259 260
}

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

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

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

Don Gagne's avatar
Don Gagne committed
299
    if (fileVersion == 1) {
300
        return _loadJsonMissionFileV1(vehicle, json, visualItems, errorString);
Don Gagne's avatar
Don Gagne committed
301
    } else {
302
        return _loadJsonMissionFileV2(vehicle, json, visualItems, errorString);
Don Gagne's avatar
Don Gagne committed
303 304 305
    }
}

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

319
    // Read complex items
320
    QList<SurveyMissionItem*> surveyItems;
321 322 323 324
    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];
325

326 327 328 329 330
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

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

340 341 342 343 344
    // 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
345
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
346

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

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

368 369 370 371 372
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
373
            const QJsonObject itemObject = itemValue.toObject();
Don Gagne's avatar
Don Gagne committed
374
            SimpleMissionItem* item = new SimpleMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
375
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
376 377
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
                visualItems->append(item);
378 379 380
            } else {
                return false;
            }
381 382

            nextSequenceNumber++;
383
        }
384
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
385 386

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

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

    return true;
}

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

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

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

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

            if (item->load(stream)) {
570
                visualItems->append(item);
571 572 573 574 575 576 577 578 579 580
            } 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;
    }

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

584 585 586 587 588
        // 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
589 590
            }
        }
591 592 593
    }

    return true;
594 595
}

596
void MissionController::loadFromFile(const QString& filename)
597
{
Don Gagne's avatar
Don Gagne committed
598 599
    QmlObjectListModel* newVisualItems = NULL;

600
    if (!loadItemsFromFile(_activeVehicle, filename, &newVisualItems)) {
Don Gagne's avatar
Don Gagne committed
601 602 603 604 605 606 607 608 609 610 611
        return;
    }

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

    _visualItems = newVisualItems;

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

615 616
    MissionSettingsComplexItem::scanForMissionSettings(_visualItems, _activeVehicle);

Don Gagne's avatar
Don Gagne committed
617 618 619
    _initAllVisualItems();
}

620
bool MissionController::loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems)
Don Gagne's avatar
Don Gagne committed
621 622 623
{
    *visualItems = NULL;

624 625 626
    QString errorString;

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

Don Gagne's avatar
Don Gagne committed
630
    *visualItems = 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 {
645
            _loadJsonMissionFile(vehicle, bytes, *visualItems, errorString);
646 647
        }
    }
648

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

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

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

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

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

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

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

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

684
    QFile file(missionFilename);
685

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

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

694
        // Mission settings
695

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

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

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

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

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

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

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

    // Convert to fixed altitudes

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

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

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

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

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

    distanceOk = true;

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

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

782 783
void MissionController::_recalcWaypointLines(void)
{
784 785 786
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

787
    MissionSettingsComplexItem*  settingsItem = qobject_cast<MissionSettingsComplexItem*>(lastCoordinateItem);
788

789 790
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsComplexItem";
791 792
    }

793
    bool    showHomePosition =  false; // FIXME: settingsItem->showHomePosition();
794 795 796

    qCDebug(MissionControllerLog) << "_recalcWaypointLines";

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

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


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

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

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

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

872 873
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsComplexItem";
874 875
    }

876
    bool showHomePosition = settingsItem->showHomePosition();
877 878 879

    qCDebug(MissionControllerLog) << "_recalcAltitudeRangeBearing";

880 881 882
    // 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.
883

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

889 890
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
891 892
    const double homePositionAltitude = settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = settingsItem->coordinate().altitude();
893

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

904 905
    bool vtolVehicle = _activeVehicle->vtol();
    bool vtolInHover = true;
906

Don Gagne's avatar
Don Gagne committed
907
    bool linkBackToHome = false;
908

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

914 915
        // Assume the worst
        item->setAzimuth(0.0);
916
        item->setDistance(0.0);
917

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

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

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

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

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

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

                    missionDistance += distance;
992
                    missionMaxTelemetry = qMax(missionMaxTelemetry, _calcDistanceToHome(item, settingsItem));
993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005

                    // 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;
1006 1007
                        }
                    } else {
1008
                        missionTime += distance / (_activeVehicle->multiRotor() ? currentHoverSpeed : currentCruiseSpeed);
1009
                    }
1010
                }
1011 1012 1013 1014 1015 1016 1017
                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;
1018
                    missionMaxTelemetry = qMax(missionMaxTelemetry, complexItem->greatestDistanceTo(settingsItem->exitCoordinate()));
1019 1020 1021

                    // Let the complex item know the current cruise speed
                    complexItem->setCruiseSpeed(cruiseSpeed);
1022
                }
1023
            }
1024 1025

            lastCoordinateItem = item;
1026 1027 1028
        }
    }

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

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

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

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

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

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

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

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

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

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

1105
/// Initializes a new set of mission items
1106
void MissionController::_initAllVisualItems(void)
1107
{
1108
    MissionSettingsComplexItem* settingsItem = NULL;
1109 1110 1111

    // Setup home position at index 0

1112 1113 1114
    settingsItem = qobject_cast<MissionSettingsComplexItem*>(_visualItems->get(0));
    if (!settingsItem) {
        qWarning() << "First item not MissionSettingsComplexItem";
1115 1116
        return;
    }
1117

1118 1119
    settingsItem->setShowHomePosition(_editMode);
    settingsItem->setIsCurrentItem(true);
1120 1121

    if (!_editMode && _activeVehicle && _activeVehicle->homePositionAvailable()) {
1122 1123
        settingsItem->setCoordinate(_activeVehicle->homePosition());
        settingsItem->setShowHomePosition(true);
1124
    }
1125

1126 1127
    emit plannedHomePositionChanged(plannedHomePosition());

1128
    connect(settingsItem, &VisualMissionItem::coordinateChanged, this, &MissionController::_homeCoordinateChanged);
1129

1130 1131 1132 1133
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1134

1135
    _recalcAll();
1136

1137
    emit visualItemsChanged();
1138

1139
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1140

1141
    _visualItems->setDirty(false);
1142 1143
}

1144
void MissionController::_deinitAllVisualItems(void)
1145
{
1146 1147
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1148 1149
    }

1150
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1151 1152
}

1153
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1154
{
1155 1156
    _visualItems->setDirty(false);

1157
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1158 1159
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
1160
    connect(visualItem, &VisualMissionItem::flightSpeedChanged,                         this, &MissionController::_recalcAltitudeRangeBearing);
1161

1162 1163 1164 1165 1166 1167 1168 1169
    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";
        }
1170 1171 1172 1173
    } 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);
1174
        connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcAltitudeRangeBearing);
1175
    }
1176 1177
}

1178
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1179
{
1180 1181
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1182 1183
}

1184
void MissionController::_itemCommandChanged(void)
1185
{
1186 1187
    _recalcChildItems();
    _recalcWaypointLines();
1188 1189
}

1190
void MissionController::_activeVehicleBeingRemoved(void)
1191
{
1192
    qCDebug(MissionControllerLog) << "MissionController::_activeVehicleBeingRemoved";
1193

1194
    MissionManager* missionManager = _activeVehicle->missionManager();
1195 1196 1197 1198

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

Don Gagne's avatar
Don Gagne committed
1202 1203
    // 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
1204 1205
    removeAll();
}
Don Gagne's avatar
Don Gagne committed
1206

1207 1208 1209 1210 1211
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();
1212

1213 1214 1215 1216 1217 1218 1219
    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);
1220 1221
    connect(_activeVehicle, &Vehicle::cruiseSpeedChanged,               this, &MissionController::_recalcAltitudeRangeBearing);
    connect(_activeVehicle, &Vehicle::hoverSpeedChanged,                this, &MissionController::_recalcAltitudeRangeBearing);
1222

1223
    if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
1224 1225 1226
        // 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();
1227
    }
1228

1229 1230
    _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
    _activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
1231 1232 1233 1234
}

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

1238 1239
        if (settingsItem) {
            settingsItem->setShowHomePosition(homePositionAvailable);
1240
            emit plannedHomePositionChanged(plannedHomePosition());
1241 1242
            _recalcWaypointLines();
        } else {
1243
            qWarning() << "First item is not MissionSettingsComplexItem";
1244
        }
1245
    }
1246 1247 1248 1249
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
1250
    if (!_editMode && _visualItems) {
1251 1252 1253 1254 1255
        MissionSettingsComplexItem* settingsItem = qobject_cast<MissionSettingsComplexItem*>(_visualItems->get(0));
        if (settingsItem) {
            if (settingsItem->coordinate() != homePosition) {
                settingsItem->setCoordinate(homePosition);
                settingsItem->setShowHomePosition(true);
1256 1257 1258 1259 1260
                qCDebug(MissionControllerLog) << "Home position update" << homePosition;
                emit plannedHomePositionChanged(plannedHomePosition());
                _recalcWaypointLines();
            }
        } else {
1261
            qWarning() << "First item is not MissionSettingsComplexItem";
1262
        }
1263
    }
1264 1265
}

1266 1267 1268 1269 1270 1271 1272 1273 1274
void MissionController::_setMissionMaxTelemetry(double missionMaxTelemetry)
{
    if (!qFuzzyCompare(_missionMaxTelemetry, missionMaxTelemetry)) {
        _missionMaxTelemetry = missionMaxTelemetry;
        emit missionMaxTelemetryChanged(_missionMaxTelemetry);
    }
}

void MissionController::_setMissionDistance(double missionDistance)
1275 1276 1277 1278 1279 1280 1281
{
    if (!qFuzzyCompare(_missionDistance, missionDistance)) {
        _missionDistance = missionDistance;
        emit missionDistanceChanged(_missionDistance);
    }
}

1282
void MissionController::_setMissionTime(double missionTime)
1283
{
1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294
    if (!qFuzzyCompare(_missionTime, missionTime)) {
        _missionTime = missionTime;
        emit missionTimeChanged();
    }
}

void MissionController::_setMissionHoverTime(double missionHoverTime)
{
    if (!qFuzzyCompare(_missionHoverTime, missionHoverTime)) {
        _missionHoverTime = missionHoverTime;
        emit missionHoverTimeChanged();
1295 1296 1297
    }
}

1298
void MissionController::_setMissionHoverDistance(double missionHoverDistance)
1299
{
1300 1301 1302
    if (!qFuzzyCompare(_missionHoverDistance, missionHoverDistance)) {
        _missionHoverDistance = missionHoverDistance;
        emit missionHoverDistanceChanged(_missionHoverDistance);
1303 1304 1305
    }
}

1306
void MissionController::_setMissionCruiseTime(double missionCruiseTime)
1307
{
1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318
    if (!qFuzzyCompare(_missionCruiseTime, missionCruiseTime)) {
        _missionCruiseTime = missionCruiseTime;
        emit missionCruiseTimeChanged();
    }
}

void MissionController::_setMissionCruiseDistance(double missionCruiseDistance)
{
    if (!qFuzzyCompare(_missionCruiseDistance, missionCruiseDistance)) {
        _missionCruiseDistance = missionCruiseDistance;
        emit missionCruiseDistanceChanged(_missionCruiseDistance);
1319 1320 1321
    }
}

1322
void MissionController::_inProgressChanged(bool inProgress)
1323
{
1324
    emit syncInProgressChanged(inProgress);
1325
}
1326

1327
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
1328
{
1329 1330 1331
    bool        found = false;
    double      foundAltitude;
    MAV_FRAME   foundFrame;
1332

1333 1334 1335 1336 1337 1338
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1341 1342 1343
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1344
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
1345 1346 1347
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1348
                    break;
1349 1350
                }
            }
1351 1352 1353
        }
    }

1354
    if (found) {
1355 1356
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1357 1358 1359
    }

    return found;
1360
}
1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373

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

1374 1375
/// Add the Mission Settings complex item to the front of the items
void MissionController::_addMissionSettings(Vehicle* vehicle, QmlObjectListModel* visualItems, bool addToCenter)
1376
{
1377 1378
    bool homePositionSet = false;

1379 1380
    MissionSettingsComplexItem* settingsItem = new MissionSettingsComplexItem(vehicle, visualItems);
    visualItems->insert(0, settingsItem);
1381

1382
    if (visualItems->count() > 1  && addToCenter) {
1383 1384 1385 1386
        double north = 0.0;
        double south = 0.0;
        double east  = 0.0;
        double west  = 0.0;
1387
        bool firstCoordSet = false;
1388

1389 1390 1391 1392 1393 1394 1395 1396
        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);
1397 1398
                    east  = fmax(east, lon);
                    west  = fmin(west, lon);
1399 1400 1401 1402
                } else {
                    firstCoordSet = true;
                    north = _normalizeLat(item->coordinate().latitude());
                    south = north;
1403 1404
                    east  = _normalizeLon(item->coordinate().longitude());
                    west  = east;
1405 1406 1407
                }
            }
        }
1408

1409 1410
        if (firstCoordSet) {
            homePositionSet = true;
1411
            settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
1412
        }
1413
    }
1414

1415
    if (!homePositionSet) {
1416
        settingsItem->setCoordinate(qgcApp()->lastKnownHomePosition());
1417 1418
    }
}
1419 1420 1421 1422 1423 1424 1425 1426

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

1427 1428
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1429 1430 1431 1432
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
    }
}
1433

1434
bool MissionController::syncInProgress(void) const
1435
{
1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448
    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);
1449
    }
1450
}
1451 1452 1453 1454

QGeoCoordinate MissionController::plannedHomePosition(void)
{
    if (_visualItems && _visualItems->count() > 0) {
1455 1456 1457
        MissionSettingsComplexItem* settingsItem = qobject_cast<MissionSettingsComplexItem*>(_visualItems->get(0));
        if (settingsItem && settingsItem->showHomePosition()) {
            return settingsItem->coordinate();
1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468
        }
    }

    return QGeoCoordinate();
}

void MissionController::_homeCoordinateChanged(void)
{
    emit plannedHomePositionChanged(plannedHomePosition());
    _recalcAltitudeRangeBearing();
}
1469 1470 1471 1472 1473

QString MissionController::fileExtension(void) const
{
    return QGCApplication::missionFileExtension;
}
1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491

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