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
        if (_editMode) {
129
            MissionController::_scanForAdditionalSettings(_visualItems, _activeVehicle);
130
        }
131

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

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

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

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

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

Don Gagne's avatar
Don Gagne committed
159 160
        for (int i=0; i<visualMissionItems->count(); i++) {
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(visualMissionItems->get(i));
161 162

            visualItem->appendMissionItems(missionItems, NULL);
163 164
        }

Don Gagne's avatar
Don Gagne committed
165
        vehicle->missionManager()->writeMissionItems(missionItems);
166 167

        for (int i=0; i<missionItems.count(); i++) {
Don Gagne's avatar
Don Gagne committed
168
            missionItems[i]->deleteLater();
169
        }
170 171
    }
}
172

173 174 175 176 177 178
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
179 180
        VisualMissionItem* lastItem = _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1);
        return lastItem->lastSequenceNumber() + 1;
181 182 183
    }
}

184
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
185
{
186
    int sequenceNumber = _nextSequenceNumber();
187
    SimpleMissionItem * newItem = new SimpleMissionItem(_activeVehicle, this);
188
    newItem->setSequenceNumber(sequenceNumber);
189
    newItem->setCoordinate(coordinate);
190 191 192
    newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
    _initVisualItem(newItem);
    if (_visualItems->count() == 1) {
193 194
        newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
    }
195
    newItem->setDefaultsForCommand();
Don Gagne's avatar
Don Gagne committed
196
    if ((MAV_CMD)newItem->command() == MAV_CMD_NAV_WAYPOINT) {
197 198
        double      prevAltitude;
        MAV_FRAME   prevFrame;
199

200 201 202
        if (_findPreviousAltitude(i, &prevAltitude, &prevFrame)) {
            newItem->missionItem().setFrame(prevFrame);
            newItem->missionItem().setParam7(prevAltitude);
203
        }
204
    }
205
    _visualItems->insert(i, newItem);
206 207 208

    _recalcAll();

209
    return newItem->sequenceNumber();
210 211
}

212
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
213
{
214 215
    ComplexMissionItem* newItem;

216
    int sequenceNumber = _nextSequenceNumber();
217 218
    if (itemName == _surveyMissionItemName) {
        newItem = new SurveyMissionItem(_activeVehicle, _visualItems);
219
        newItem->setCoordinate(mapCenterCoordinate);
220
    } else if (itemName == _fwLandingMissionItemName) {
221
        newItem = new FixedWingLandingComplexItem(_activeVehicle, _visualItems);
222 223 224 225
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }
226
    newItem->setSequenceNumber(sequenceNumber);
227
    _initVisualItem(newItem);
228

229
    _visualItems->insert(i, newItem);
230 231 232

    _recalcAll();

233
    return newItem->sequenceNumber();
234 235
}

236 237
void MissionController::removeMissionItem(int index)
{
238
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
239

240
    _deinitVisualItem(item);
241
    item->deleteLater();
242 243

    _recalcAll();
244
    _visualItems->setDirty(true);
245 246
}

247
void MissionController::removeAll(void)
248
{
249 250
    if (_visualItems) {
        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
251
        _visualItems->deleteLater();
252
        _visualItems = new QmlObjectListModel(this);
253
        _addMissionSettings(_activeVehicle, _visualItems, false /* addToCenter */);
254
        _initAllVisualItems();
Don Gagne's avatar
Don Gagne committed
255
        _visualItems->setDirty(true);
256
    }
257
}
258

259
bool MissionController::_loadJsonMissionFile(Vehicle* vehicle, const QByteArray& bytes, QmlObjectListModel* visualItems, QString& errorString)
260 261 262 263 264 265 266 267 268 269
{
    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
270 271 272
    // 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;
273 274
    }

Don Gagne's avatar
Don Gagne committed
275 276 277 278 279 280 281
    int fileVersion;
    if (!JsonHelper::validateQGCJsonFile(json,
                                         _jsonFileTypeValue,    // expected file type
                                         1,                     // minimum supported version
                                         2,                     // maximum supported version
                                         fileVersion,
                                         errorString)) {
282 283
        return false;
    }
284

Don Gagne's avatar
Don Gagne committed
285
    if (fileVersion == 1) {
286
        return _loadJsonMissionFileV1(vehicle, json, visualItems, errorString);
Don Gagne's avatar
Don Gagne committed
287
    } else {
288
        return _loadJsonMissionFileV2(vehicle, json, visualItems, errorString);
Don Gagne's avatar
Don Gagne committed
289 290 291
    }
}

292
bool MissionController::_loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
293 294 295 296 297 298 299 300 301
{
    // 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)) {
302 303 304
        return false;
    }

305
    // Read complex items
306
    QList<SurveyMissionItem*> surveyItems;
307 308 309 310
    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];
311

312 313 314 315 316
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

Don Gagne's avatar
Don Gagne committed
317
        SurveyMissionItem* item = new SurveyMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
318 319
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
320
            surveyItems.append(item);
321 322
        } else {
            return false;
323
        }
324
    }
325

326 327 328 329 330
    // 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
331
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
332

333
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
334 335 336 337
    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
338 339
        if (nextComplexItemIndex < surveyItems.count()) {
            SurveyMissionItem* complexItem = surveyItems[nextComplexItemIndex];
340 341 342 343 344 345 346 347 348 349 350 351 352 353

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

354 355 356 357 358
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
359
            const QJsonObject itemObject = itemValue.toObject();
Don Gagne's avatar
Don Gagne committed
360
            SimpleMissionItem* item = new SimpleMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
361
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
362
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
363
                nextSequenceNumber = item->lastSequenceNumber() + 1;
364
                visualItems->append(item);
365 366 367 368
            } else {
                return false;
            }
        }
369
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
370 371

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

Don Gagne's avatar
Don Gagne committed
374
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
375 376 377 378
            MissionSettingsComplexItem* settingsItem = new MissionSettingsComplexItem(vehicle, visualItems);
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
379 380 381 382
        } else {
            return false;
        }
    } else {
383
        _addMissionSettings(vehicle, visualItems, true /* addToCenter */);
384 385 386 387 388
    }

    return true;
}

389
bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
390 391 392 393 394 395
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
396 397 398
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
399 400 401 402 403 404 405
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

406
    // Mission Settings
Don Gagne's avatar
Don Gagne committed
407
    QGeoCoordinate homeCoordinate;
408
    SettingsManager* settingsManager = qgcApp()->toolbox()->settingsManager();
Don Gagne's avatar
Don Gagne committed
409 410 411
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
Don Gagne's avatar
Don Gagne committed
412
    if (json.contains(_jsonVehicleTypeKey) && vehicle->isOfflineEditingVehicle()) {
413
        settingsManager->appSettings()->offlineEditingVehicleType()->setRawValue(json[_jsonVehicleTypeKey].toDouble());
414 415
    }
    if (json.contains(_jsonCruiseSpeedKey)) {
416
        settingsManager->appSettings()->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
417 418
    }
    if (json.contains(_jsonHoverSpeedKey)) {
419
        settingsManager->appSettings()->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
420 421
    }

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

            if (item->load(stream)) {
556
                visualItems->append(item);
557 558 559 560 561 562 563 564 565 566
            } 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;
    }

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

570 571 572 573 574
        // 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
575 576
            }
        }
577 578 579
    }

    return true;
580 581
}

582
void MissionController::loadFromFile(const QString& filename)
583
{
Don Gagne's avatar
Don Gagne committed
584 585
    QmlObjectListModel* newVisualItems = NULL;

586
    if (!loadItemsFromFile(_activeVehicle, filename, &newVisualItems)) {
Don Gagne's avatar
Don Gagne committed
587 588 589 590 591 592 593 594 595 596 597
        return;
    }

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

    _visualItems = newVisualItems;

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

601
    MissionController::_scanForAdditionalSettings(_visualItems, _activeVehicle);
602

Don Gagne's avatar
Don Gagne committed
603 604 605
    _initAllVisualItems();
}

606
bool MissionController::loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems)
Don Gagne's avatar
Don Gagne committed
607 608 609
{
    *visualItems = NULL;

610 611 612
    QString errorString;

    if (filename.isEmpty()) {
Don Gagne's avatar
Don Gagne committed
613
        return false;
614 615
    }

Don Gagne's avatar
Don Gagne committed
616
    *visualItems = new QmlObjectListModel();
617 618 619 620

    QFile file(filename);

    if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
Don Gagne's avatar
Don Gagne committed
621
        errorString = file.errorString() + QStringLiteral(" ") + filename;
622
    } else {
623 624
        QByteArray  bytes = file.readAll();
        QTextStream stream(&bytes);
625

626 627 628
        QString firstLine = stream.readLine();
        if (firstLine.contains(QRegExp("QGC.*WPL"))) {
            stream.seek(0);
Don Gagne's avatar
Don Gagne committed
629
            _loadTextMissionFile(vehicle, stream, *visualItems, errorString);
630
        } else {
631
            _loadJsonMissionFile(vehicle, bytes, *visualItems, errorString);
632 633
        }
    }
634

635
    if (!errorString.isEmpty()) {
Don Gagne's avatar
Don Gagne committed
636
        (*visualItems)->deleteLater();
637

638
        qgcApp()->showMessage(errorString);
Don Gagne's avatar
Don Gagne committed
639
        return false;
640 641
    }

Don Gagne's avatar
Don Gagne committed
642
    return true;
643 644
}

645
void MissionController::loadFromFilePicker(void)
646
{
647
#ifndef __mobile__
648
    QString filename = QGCFileDialog::getOpenFileName(MainWindow::instance(), "Select Mission File to load", QString(), "Mission file (*.mission);;All Files (*.*)");
649 650 651 652

    if (filename.isEmpty()) {
        return;
    }
653
    loadFromFile(filename);
654 655 656
#endif
}

657
void MissionController::saveToFile(const QString& filename)
658 659
{
    qDebug() << filename;
660 661 662 663

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

665
    QString missionFilename = filename;
666
    if (!QFileInfo(filename).fileName().contains(".")) {
Don Gagne's avatar
Don Gagne committed
667
        missionFilename += QString(".%1").arg(QGCApplication::missionFileExtension);
668 669
    }

670
    QFile file(missionFilename);
671

672
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
673
        qgcApp()->showMessage(file.errorString());
674
    } else {
675
        QJsonObject missionFileObject;      // top level json object
676

Don Gagne's avatar
Don Gagne committed
677
        missionFileObject[JsonHelper::jsonVersionKey] =         _missionFileVersion;
678
        missionFileObject[JsonHelper::jsonGroundStationKey] =   JsonHelper::jsonGroundStationValue;
679

680
        // Mission settings
681

682 683 684
        MissionSettingsComplexItem* settingsItem = _visualItems->value<MissionSettingsComplexItem*>(0);
        if (!settingsItem) {
            qWarning() << "First item is not MissionSettingsComplexItem";
685 686
            return;
        }
Don Gagne's avatar
Don Gagne committed
687
        QJsonValue coordinateValue;
688
        JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
Don Gagne's avatar
Don Gagne committed
689
        missionFileObject[_jsonPlannedHomePositionKey] = coordinateValue;
690 691 692 693
        missionFileObject[_jsonFirmwareTypeKey] = _activeVehicle->firmwareType();
        missionFileObject[_jsonVehicleTypeKey] = _activeVehicle->vehicleType();
        missionFileObject[_jsonCruiseSpeedKey] = _activeVehicle->cruiseSpeed();
        missionFileObject[_jsonHoverSpeedKey] = _activeVehicle->hoverSpeed();
694

695
        // Save the visual items
Don Gagne's avatar
Don Gagne committed
696
        QJsonArray  rgMissionItems;
697
        for (int i=0; i<_visualItems->count(); i++) {
698
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
699
            visualItem->save(rgMissionItems);
700
        }
Don Gagne's avatar
Don Gagne committed
701
        missionFileObject[_jsonItemsKey] = rgMissionItems;
702 703

        QJsonDocument saveDoc(missionFileObject);
704
        file.write(saveDoc.toJson());
705 706
    }

707
    _visualItems->setDirty(false);
708 709
}

710
void MissionController::saveToFilePicker(void)
711 712
{
#ifndef __mobile__
713
    QString filename = QGCFileDialog::getSaveFileName(MainWindow::instance(), "Select file to save mission to", QString(), "Mission file (*.mission);;All Files (*.*)");
714 715 716 717

    if (filename.isEmpty()) {
        return;
    }
718
    saveToFile(filename);
719
#endif
720 721
}

722
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
723
{
Don Gagne's avatar
Don Gagne committed
724
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
725
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
726 727 728 729
    bool            distanceOk =    false;

    // Convert to fixed altitudes

730
    qCDebug(MissionControllerLog) << homeAlt
731 732
                                  << currentItem->coordinateHasRelativeAltitude() << currentItem->coordinate().altitude()
                                  << prevItem->exitCoordinateHasRelativeAltitude() << prevItem->exitCoordinate().altitude();
733

734
    distanceOk = true;
735
    if (currentItem->coordinateHasRelativeAltitude()) {
736 737
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
738
    if (prevItem->exitCoordinateHasRelativeAltitude()) {
739
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
740 741 742 743 744
    }

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

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
745 746 747
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
748
    } else {
Don Gagne's avatar
Don Gagne committed
749
        *altDifference = 0.0;
750
        *azimuth = 0.0;
751
        *distance = 0.0;
752 753 754
    }
}

755
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
756 757 758 759 760 761 762 763 764
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

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

765
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
766 767
}

768 769
void MissionController::_recalcWaypointLines(void)
{
770 771 772
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

773
    MissionSettingsComplexItem*  settingsItem = qobject_cast<MissionSettingsComplexItem*>(lastCoordinateItem);
774

775 776
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsComplexItem";
777 778
    }

779
    bool    showHomePosition =  false; // FIXME: settingsItem->showHomePosition();
780 781 782

    qCDebug(MissionControllerLog) << "_recalcWaypointLines";

Nate Weibley's avatar
Nate Weibley committed
783 784
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
785 786 787 788 789 790 791
    _waypointLines.clear();

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


792
        // If we still haven't found the first coordinate item and we hit a takeoff command, link back to home
793 794
        if (firstCoordinateItem &&
                item->isSimpleItem() &&
795 796
                (qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF ||
                 qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) {
797 798 799 800 801 802 803
            linkBackToHome = true;
        }

        if (item->specifiesCoordinate()) {
            if (!item->isStandaloneCoordinate()) {
                firstCoordinateItem = false;
                VisualItemPair pair(lastCoordinateItem, item);
804
                if (lastCoordinateItem != settingsItem || (showHomePosition && linkBackToHome)) {
805 806
                    if (old_table.contains(pair)) {
                        // Do nothing, this segment already exists and is wired up
Nate Weibley's avatar
Nate Weibley committed
807
                        _linesTable[pair] = old_table.take(pair);
808 809 810 811
                    } 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
812
                                endNotifier    = &VisualMissionItem::coordinateChanged;
813 814 815 816 817 818 819
                        // 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
820
                        _linesTable[pair] = linevect;
821 822 823 824 825 826 827 828 829 830
                    }
                }
                lastCoordinateItem = item;
            }
        }
    }

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
831 832
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849
            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()
{
850
    if (!_visualItems->count()) {
851
        return;
852
    }
853 854 855

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

858 859
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsComplexItem";
860 861
    }

862
    bool showHomePosition = settingsItem->showHomePosition();
863 864 865

    qCDebug(MissionControllerLog) << "_recalcAltitudeRangeBearing";

866 867 868
    // 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.
869

870
    // No values for first item
871
    lastCoordinateItem->setAltDifference(0.0);
872
    lastCoordinateItem->setAzimuth(0.0);
873
    lastCoordinateItem->setDistance(0.0);
874

875 876
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
877 878
    const double homePositionAltitude = settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = settingsItem->coordinate().altitude();
879

880 881
    double missionDistance = 0.0;
    double missionMaxTelemetry = 0.0;
882 883 884 885 886 887 888
    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();
889

890 891
    bool vtolVehicle = _activeVehicle->vtol();
    bool vtolInHover = true;
892

Don Gagne's avatar
Don Gagne committed
893
    bool linkBackToHome = false;
894

895 896
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
897 898 899
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

900 901
        // Assume the worst
        item->setAzimuth(0.0);
902
        item->setDistance(0.0);
903

904 905 906 907 908 909 910 911 912 913
        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;
                }
            }
914 915
        }

916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938
        // 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;
939 940
                }
            }
941 942 943
                break;
            default:
                break;
944
            }
Don Gagne's avatar
Don Gagne committed
945 946
        }

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

950
            double absoluteAltitude = item->coordinate().altitude();
951
            if (item->coordinateHasRelativeAltitude()) {
952 953 954 955 956
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

957 958 959 960 961 962 963 964 965 966
            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
967
                firstCoordinateItem = false;
968
                if (lastCoordinateItem != settingsItem || linkBackToHome) {
969 970
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
971

972
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
973 974 975
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
976 977

                    missionDistance += distance;
978
                    missionMaxTelemetry = qMax(missionMaxTelemetry, _calcDistanceToHome(item, settingsItem));
979 980 981 982 983 984 985 986 987 988 989 990 991

                    // 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;
992 993
                        }
                    } else {
994
                        missionTime += distance / (_activeVehicle->multiRotor() ? currentHoverSpeed : currentCruiseSpeed);
995
                    }
996
                }
997 998 999 1000 1001 1002 1003
                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;
1004
                    missionMaxTelemetry = qMax(missionMaxTelemetry, complexItem->greatestDistanceTo(settingsItem->exitCoordinate()));
1005 1006 1007

                    // Let the complex item know the current cruise speed
                    complexItem->setCruiseSpeed(cruiseSpeed);
1008
                }
1009
            }
1010 1011

            lastCoordinateItem = item;
1012 1013 1014
        }
    }

1015 1016 1017 1018 1019 1020 1021
    _setMissionMaxTelemetry(missionMaxTelemetry);
    _setMissionDistance(missionDistance);
    _setMissionTime(missionTime);
    _setMissionHoverDistance(vtolHoverDistance);
    _setMissionHoverTime(vtolHoverTime);
    _setMissionCruiseDistance(vtolCruiseDistance);
    _setMissionCruiseTime(vtolCruiseTime);
1022

1023 1024
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1025 1026
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1027 1028 1029

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1030
            if (item->coordinateHasRelativeAltitude()) {
1031 1032 1033 1034 1035 1036
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1037
            }
1038 1039 1040 1041
        }
    }
}

1042 1043 1044
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1045 1046 1047 1048 1049 1050
    // 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));

1051 1052
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1053 1054 1055
    }
}

1056 1057 1058
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1059
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1060 1061 1062

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

1063 1064
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1065 1066 1067 1068 1069

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1070
        } else if (item->isSimpleItem()) {
1071 1072 1073 1074 1075
            currentParentItem->childItems()->append(item);
        }
    }
}

1076 1077
void MissionController::_recalcAll(void)
{
1078
    _recalcSequence();
1079 1080 1081 1082
    _recalcChildItems();
    _recalcWaypointLines();
}

1083
/// Initializes a new set of mission items
1084
void MissionController::_initAllVisualItems(void)
1085
{
1086
    MissionSettingsComplexItem* settingsItem = NULL;
1087 1088 1089

    // Setup home position at index 0

1090 1091 1092
    settingsItem = qobject_cast<MissionSettingsComplexItem*>(_visualItems->get(0));
    if (!settingsItem) {
        qWarning() << "First item not MissionSettingsComplexItem";
1093 1094
        return;
    }
1095

1096 1097
    settingsItem->setShowHomePosition(_editMode);
    settingsItem->setIsCurrentItem(true);
1098 1099

    if (!_editMode && _activeVehicle && _activeVehicle->homePositionAvailable()) {
1100 1101
        settingsItem->setCoordinate(_activeVehicle->homePosition());
        settingsItem->setShowHomePosition(true);
1102
    }
1103

1104 1105
    emit plannedHomePositionChanged(plannedHomePosition());

1106
    connect(settingsItem, &VisualMissionItem::coordinateChanged, this, &MissionController::_homeCoordinateChanged);
1107

1108 1109 1110 1111
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1112

1113
    _recalcAll();
1114

1115
    emit visualItemsChanged();
1116

1117
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1118

1119
    _visualItems->setDirty(false);
1120 1121
}

1122
void MissionController::_deinitAllVisualItems(void)
1123
{
1124 1125
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1126 1127
    }

1128
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1129 1130
}

1131
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1132
{
1133 1134
    _visualItems->setDirty(false);

1135
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1136 1137
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
1138
    connect(visualItem, &VisualMissionItem::flightSpeedChanged,                         this, &MissionController::_recalcAltitudeRangeBearing);
1139
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1140

1141 1142 1143 1144 1145 1146 1147 1148
    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";
        }
1149 1150
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1151 1152 1153 1154 1155
        if (complexItem) {
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcAltitudeRangeBearing);
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1156
    }
1157 1158
}

1159
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1160
{
1161 1162
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1163 1164
}

1165
void MissionController::_itemCommandChanged(void)
1166
{
1167 1168
    _recalcChildItems();
    _recalcWaypointLines();
1169 1170
}

1171
void MissionController::_activeVehicleBeingRemoved(void)
1172
{
1173
    qCDebug(MissionControllerLog) << "MissionController::_activeVehicleBeingRemoved";
1174

1175
    MissionManager* missionManager = _activeVehicle->missionManager();
1176 1177 1178 1179

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

Don Gagne's avatar
Don Gagne committed
1183 1184
    // 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
1185 1186
    removeAll();
}
Don Gagne's avatar
Don Gagne committed
1187

1188 1189 1190 1191 1192
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();
1193

1194 1195 1196 1197 1198 1199 1200
    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);
1201 1202
    connect(_activeVehicle, &Vehicle::cruiseSpeedChanged,               this, &MissionController::_recalcAltitudeRangeBearing);
    connect(_activeVehicle, &Vehicle::hoverSpeedChanged,                this, &MissionController::_recalcAltitudeRangeBearing);
1203

1204
    if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
1205 1206 1207
        // 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();
1208
    }
1209

1210 1211
    _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
    _activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
1212 1213 1214 1215
}

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

1219 1220
        if (settingsItem) {
            settingsItem->setShowHomePosition(homePositionAvailable);
1221
            emit plannedHomePositionChanged(plannedHomePosition());
1222 1223
            _recalcWaypointLines();
        } else {
1224
            qWarning() << "First item is not MissionSettingsComplexItem";
1225
        }
1226
    }
1227 1228 1229 1230
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
1231
    if (!_editMode && _visualItems) {
1232 1233 1234 1235 1236
        MissionSettingsComplexItem* settingsItem = qobject_cast<MissionSettingsComplexItem*>(_visualItems->get(0));
        if (settingsItem) {
            if (settingsItem->coordinate() != homePosition) {
                settingsItem->setCoordinate(homePosition);
                settingsItem->setShowHomePosition(true);
1237 1238 1239 1240 1241
                qCDebug(MissionControllerLog) << "Home position update" << homePosition;
                emit plannedHomePositionChanged(plannedHomePosition());
                _recalcWaypointLines();
            }
        } else {
1242
            qWarning() << "First item is not MissionSettingsComplexItem";
1243
        }
1244
    }
1245 1246
}

1247 1248 1249 1250 1251 1252 1253 1254 1255
void MissionController::_setMissionMaxTelemetry(double missionMaxTelemetry)
{
    if (!qFuzzyCompare(_missionMaxTelemetry, missionMaxTelemetry)) {
        _missionMaxTelemetry = missionMaxTelemetry;
        emit missionMaxTelemetryChanged(_missionMaxTelemetry);
    }
}

void MissionController::_setMissionDistance(double missionDistance)
1256 1257 1258 1259 1260 1261 1262
{
    if (!qFuzzyCompare(_missionDistance, missionDistance)) {
        _missionDistance = missionDistance;
        emit missionDistanceChanged(_missionDistance);
    }
}

1263
void MissionController::_setMissionTime(double missionTime)
1264
{
1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275
    if (!qFuzzyCompare(_missionTime, missionTime)) {
        _missionTime = missionTime;
        emit missionTimeChanged();
    }
}

void MissionController::_setMissionHoverTime(double missionHoverTime)
{
    if (!qFuzzyCompare(_missionHoverTime, missionHoverTime)) {
        _missionHoverTime = missionHoverTime;
        emit missionHoverTimeChanged();
1276 1277 1278
    }
}

1279
void MissionController::_setMissionHoverDistance(double missionHoverDistance)
1280
{
1281 1282 1283
    if (!qFuzzyCompare(_missionHoverDistance, missionHoverDistance)) {
        _missionHoverDistance = missionHoverDistance;
        emit missionHoverDistanceChanged(_missionHoverDistance);
1284 1285 1286
    }
}

1287
void MissionController::_setMissionCruiseTime(double missionCruiseTime)
1288
{
1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299
    if (!qFuzzyCompare(_missionCruiseTime, missionCruiseTime)) {
        _missionCruiseTime = missionCruiseTime;
        emit missionCruiseTimeChanged();
    }
}

void MissionController::_setMissionCruiseDistance(double missionCruiseDistance)
{
    if (!qFuzzyCompare(_missionCruiseDistance, missionCruiseDistance)) {
        _missionCruiseDistance = missionCruiseDistance;
        emit missionCruiseDistanceChanged(_missionCruiseDistance);
1300 1301 1302
    }
}

1303
void MissionController::_inProgressChanged(bool inProgress)
1304
{
1305
    emit syncInProgressChanged(inProgress);
1306
}
1307

1308
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
1309
{
1310 1311 1312
    bool        found = false;
    double      foundAltitude;
    MAV_FRAME   foundFrame;
1313

1314 1315 1316 1317 1318 1319
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1322 1323 1324
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1325
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
1326 1327 1328
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1329
                    break;
1330 1331
                }
            }
1332 1333 1334
        }
    }

1335
    if (found) {
1336 1337
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1338 1339 1340
    }

    return found;
1341
}
1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354

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

1355 1356
/// Add the Mission Settings complex item to the front of the items
void MissionController::_addMissionSettings(Vehicle* vehicle, QmlObjectListModel* visualItems, bool addToCenter)
1357
{
1358 1359
    bool homePositionSet = false;

1360 1361
    MissionSettingsComplexItem* settingsItem = new MissionSettingsComplexItem(vehicle, visualItems);
    visualItems->insert(0, settingsItem);
1362

1363
    if (visualItems->count() > 1  && addToCenter) {
1364 1365 1366 1367
        double north = 0.0;
        double south = 0.0;
        double east  = 0.0;
        double west  = 0.0;
1368
        bool firstCoordSet = false;
1369

1370 1371 1372 1373 1374 1375 1376 1377
        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);
1378 1379
                    east  = fmax(east, lon);
                    west  = fmin(west, lon);
1380 1381 1382 1383
                } else {
                    firstCoordSet = true;
                    north = _normalizeLat(item->coordinate().latitude());
                    south = north;
1384 1385
                    east  = _normalizeLon(item->coordinate().longitude());
                    west  = east;
1386 1387 1388
                }
            }
        }
1389

1390 1391
        if (firstCoordSet) {
            homePositionSet = true;
1392
            settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
1393
        }
1394
    }
1395

1396
    if (!homePositionSet) {
1397
        settingsItem->setCoordinate(qgcApp()->lastKnownHomePosition());
1398 1399
    }
}
1400 1401 1402 1403 1404 1405 1406 1407

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

1408 1409
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1410 1411 1412 1413
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
    }
}
1414

1415
bool MissionController::syncInProgress(void) const
1416
{
1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429
    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);
1430
    }
1431
}
1432 1433 1434 1435

QGeoCoordinate MissionController::plannedHomePosition(void)
{
    if (_visualItems && _visualItems->count() > 0) {
1436 1437 1438
        MissionSettingsComplexItem* settingsItem = qobject_cast<MissionSettingsComplexItem*>(_visualItems->get(0));
        if (settingsItem && settingsItem->showHomePosition()) {
            return settingsItem->coordinate();
1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449
        }
    }

    return QGeoCoordinate();
}

void MissionController::_homeCoordinateChanged(void)
{
    emit plannedHomePositionChanged(plannedHomePosition());
    _recalcAltitudeRangeBearing();
}
1450 1451 1452 1453 1454

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

1456
double MissionController::cruiseSpeed(void) const
1457 1458 1459 1460 1461 1462 1463 1464
{
    if (_activeVehicle) {
        return _activeVehicle->cruiseSpeed();
    } else {
        return 0.0f;
    }
}

1465
double MissionController::hoverSpeed(void) const
1466 1467 1468 1469 1470 1471 1472
{
    if (_activeVehicle) {
        return _activeVehicle->hoverSpeed();
    } else {
        return 0.0f;
    }
}
1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496

void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

        qCDebug(MissionControllerLog) << "MissionController::_scanForAdditionalSettings count:scanIndex" << visualItems->count() << scanIndex;

        MissionSettingsComplexItem* settingsItem = qobject_cast<MissionSettingsComplexItem*>(visualItem);
        if (settingsItem && settingsItem->scanForMissionSettings(visualItems, scanIndex, vehicle)) {
            continue;
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
        if (simpleItem && simpleItem->cameraSection()->available()) {
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
            continue;
        }

        scanIndex++;
    }
}