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
        MissionSettingsComplexItem::scanForMissionSettings(_visualItems, _activeVehicle);

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

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

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

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

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

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

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

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

179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194
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;
        }
    }
}

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

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

    _recalcAll();

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

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

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

240
    _visualItems->insert(i, 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
    _deinitVisualItem(item);
252
    item->deleteLater();
253 254

    _recalcAll();
255
    _visualItems->setDirty(true);
256 257
}

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

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

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

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

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

316
    // Read complex items
317
    QList<SurveyMissionItem*> surveyItems;
318 319 320 321
    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];
322

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

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

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

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

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

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

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

            nextSequenceNumber++;
380
        }
381
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
382 383

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

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

    return true;
}

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

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

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

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

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

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

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

    return true;
591 592
}

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

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

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

    _visualItems = newVisualItems;

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

612 613
    MissionSettingsComplexItem::scanForMissionSettings(_visualItems, _activeVehicle);

Don Gagne's avatar
Don Gagne committed
614 615 616
    _initAllVisualItems();
}

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

621 622 623
    QString errorString;

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

Don Gagne's avatar
Don Gagne committed
627
    *visualItems = 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 {
642
            _loadJsonMissionFile(vehicle, bytes, *visualItems, errorString);
643 644
        }
    }
645

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

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

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

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

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

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

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

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

681
    QFile file(missionFilename);
682

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

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

691
        // Mission settings
692

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

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

        QJsonDocument saveDoc(missionFileObject);
715
        file.write(saveDoc.toJson());
716 717
    }

718
    _visualItems->setDirty(false);
719 720
}

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

    if (filename.isEmpty()) {
        return;
    }
729
    saveToFile(filename);
730
#endif
731 732
}

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

    // Convert to fixed altitudes

741
    qCDebug(MissionControllerLog) << homeAlt
742 743
                                  << currentItem->coordinateHasRelativeAltitude() << currentItem->coordinate().altitude()
                                  << prevItem->exitCoordinateHasRelativeAltitude() << prevItem->exitCoordinate().altitude();
744

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

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

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

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

    distanceOk = true;

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

776
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
777 778
}

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

784
    MissionSettingsComplexItem*  settingsItem = qobject_cast<MissionSettingsComplexItem*>(lastCoordinateItem);
785

786 787
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsComplexItem";
788 789
    }

790
    bool    showHomePosition =  false; // FIXME: settingsItem->showHomePosition();
791 792 793

    qCDebug(MissionControllerLog) << "_recalcWaypointLines";

Nate Weibley's avatar
Nate Weibley committed
794 795
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
796 797 798 799 800 801 802
    _waypointLines.clear();

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


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

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

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
842 843
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860
            objs.append(vect);
        }

        // We don't delete here because many links may still be valid
        _waypointLines.swapObjectList(objs);
    }

    // Anything left in the old table is an obsolete line object that can go
    qDeleteAll(old_table);

    _recalcAltitudeRangeBearing();

    emit waypointLinesChanged();
}

void MissionController::_recalcAltitudeRangeBearing()
{
861
    if (!_visualItems->count()) {
862
        return;
863
    }
864 865 866

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

869 870
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsComplexItem";
871 872
    }

873
    bool showHomePosition = settingsItem->showHomePosition();
874 875 876

    qCDebug(MissionControllerLog) << "_recalcAltitudeRangeBearing";

877 878 879
    // 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.
880

881
    // No values for first item
882
    lastCoordinateItem->setAltDifference(0.0);
883
    lastCoordinateItem->setAzimuth(0.0);
884
    lastCoordinateItem->setDistance(0.0);
885

886 887
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
888 889
    const double homePositionAltitude = settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = settingsItem->coordinate().altitude();
890

891 892
    double missionDistance = 0.0;
    double missionMaxTelemetry = 0.0;
893 894 895 896 897 898 899
    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();
900

901 902
    bool vtolVehicle = _activeVehicle->vtol();
    bool vtolInHover = true;
903

Don Gagne's avatar
Don Gagne committed
904
    bool linkBackToHome = false;
905

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

911 912
        // Assume the worst
        item->setAzimuth(0.0);
913
        item->setDistance(0.0);
914

915 916 917 918 919 920 921 922 923 924
        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;
                }
            }
925 926
        }

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

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

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

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

983
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
984 985 986
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
987 988

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

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

                    // Let the complex item know the current cruise speed
                    complexItem->setCruiseSpeed(cruiseSpeed);
1019
                }
1020
            }
1021 1022

            lastCoordinateItem = item;
1023 1024 1025
        }
    }

1026 1027 1028 1029 1030 1031 1032
    _setMissionMaxTelemetry(missionMaxTelemetry);
    _setMissionDistance(missionDistance);
    _setMissionTime(missionTime);
    _setMissionHoverDistance(vtolHoverDistance);
    _setMissionHoverTime(vtolHoverTime);
    _setMissionCruiseDistance(vtolCruiseDistance);
    _setMissionCruiseTime(vtolCruiseTime);
1033

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

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

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

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

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

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

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

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

1095 1096
void MissionController::_recalcAll(void)
{
1097
    _recalcSequence();
1098 1099 1100 1101
    _recalcChildItems();
    _recalcWaypointLines();
}

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

    // Setup home position at index 0

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

1115 1116
    settingsItem->setShowHomePosition(_editMode);
    settingsItem->setIsCurrentItem(true);
1117 1118

    if (!_editMode && _activeVehicle && _activeVehicle->homePositionAvailable()) {
1119 1120
        settingsItem->setCoordinate(_activeVehicle->homePosition());
        settingsItem->setShowHomePosition(true);
1121
    }
1122

1123 1124
    emit plannedHomePositionChanged(plannedHomePosition());

1125
    connect(settingsItem, &VisualMissionItem::coordinateChanged, this, &MissionController::_homeCoordinateChanged);
1126

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

1132
    _recalcAll();
1133

1134
    emit visualItemsChanged();
1135

1136
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1137

1138
    _visualItems->setDirty(false);
1139 1140
}

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

1147
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1148 1149
}

1150
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1151
{
1152 1153
    _visualItems->setDirty(false);

1154
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1155 1156
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
1157
    connect(visualItem, &VisualMissionItem::flightSpeedChanged,                         this, &MissionController::_recalcAltitudeRangeBearing);
1158

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

1175
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1176
{
1177 1178
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1179 1180
}

1181
void MissionController::_itemCommandChanged(void)
1182
{
1183 1184
    _recalcChildItems();
    _recalcWaypointLines();
1185 1186
}

1187
void MissionController::_activeVehicleBeingRemoved(void)
1188
{
1189
    qCDebug(MissionControllerLog) << "MissionController::_activeVehicleBeingRemoved";
1190

1191
    MissionManager* missionManager = _activeVehicle->missionManager();
1192 1193 1194 1195

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

Don Gagne's avatar
Don Gagne committed
1199 1200
    // 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
1201 1202
    removeAll();
}
Don Gagne's avatar
Don Gagne committed
1203

1204 1205 1206 1207 1208
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();
1209

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

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

1226 1227
    _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
    _activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
1228 1229 1230 1231
}

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

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

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

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

void MissionController::_setMissionDistance(double missionDistance)
1272 1273 1274 1275 1276 1277 1278
{
    if (!qFuzzyCompare(_missionDistance, missionDistance)) {
        _missionDistance = missionDistance;
        emit missionDistanceChanged(_missionDistance);
    }
}

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

void MissionController::_setMissionHoverTime(double missionHoverTime)
{
    if (!qFuzzyCompare(_missionHoverTime, missionHoverTime)) {
        _missionHoverTime = missionHoverTime;
        emit missionHoverTimeChanged();
1292 1293 1294
    }
}

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

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

void MissionController::_setMissionCruiseDistance(double missionCruiseDistance)
{
    if (!qFuzzyCompare(_missionCruiseDistance, missionCruiseDistance)) {
        _missionCruiseDistance = missionCruiseDistance;
        emit missionCruiseDistanceChanged(_missionCruiseDistance);
1316 1317 1318
    }
}

1319
void MissionController::_inProgressChanged(bool inProgress)
1320
{
1321
    emit syncInProgressChanged(inProgress);
1322
}
1323

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

1330 1331 1332 1333 1334 1335
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

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

1351
    if (found) {
1352 1353
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1354 1355 1356
    }

    return found;
1357
}
1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370

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

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

1376 1377
    MissionSettingsComplexItem* settingsItem = new MissionSettingsComplexItem(vehicle, visualItems);
    visualItems->insert(0, settingsItem);
1378

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

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

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

1412
    if (!homePositionSet) {
1413
        settingsItem->setCoordinate(qgcApp()->lastKnownHomePosition());
1414 1415
    }
}
1416 1417 1418 1419 1420 1421 1422 1423

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

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

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

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

    return QGeoCoordinate();
}

void MissionController::_homeCoordinateChanged(void)
{
    emit plannedHomePositionChanged(plannedHomePosition());
    _recalcAltitudeRangeBearing();
}
1466 1467 1468 1469 1470

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

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