MissionController.cc 56.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 "JsonHelper.h"
20
#include "ParameterManager.h"
21
#include "QGroundControlQmlGlobal.h"
22

23
#ifndef __mobile__
24
#include "MainWindow.h"
25 26 27
#include "QGCFileDialog.h"
#endif

28 29
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

30

31
const char* MissionController::_settingsGroup =                 "MissionController";
Don Gagne's avatar
Don Gagne committed
32 33
const char* MissionController::_jsonFileTypeValue =             "Mission";
const char* MissionController::_jsonItemsKey =                  "items";
34
const char* MissionController::_jsonPlannedHomePositionKey =    "plannedHomePosition";
Don Gagne's avatar
Don Gagne committed
35
const char* MissionController::_jsonFirmwareTypeKey =           "firmwareType";
36 37 38
const char* MissionController::_jsonVehicleTypeKey =            "vehicleType";
const char* MissionController::_jsonCruiseSpeedKey =            "cruiseSpeed";
const char* MissionController::_jsonHoverSpeedKey =             "hoverSpeed";
Don Gagne's avatar
Don Gagne committed
39 40 41 42 43 44 45
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;
46 47

MissionController::MissionController(QObject *parent)
48
    : PlanElementController(parent)
49 50
    , _visualItems(NULL)
    , _complexItems(NULL)
51
    , _firstItemsFromVehicle(false)
52 53
    , _missionItemsRequested(false)
    , _queuedSend(false)
54
    , _missionDistance(0.0)
55 56 57 58 59
    , _missionTime(0.0)
    , _missionHoverDistance(0.0)
    , _missionHoverTime(0.0)
    , _missionCruiseDistance(0.0)
    , _missionCruiseTime(0.0)
60
    , _missionMaxTelemetry(0.0)
61
{
62 63 64 65 66

}

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

68 69 70 71
}

void MissionController::start(bool editMode)
{
72 73
    qCDebug(MissionControllerLog) << "start editMode" << editMode;

74
    PlanElementController::start(editMode);
75 76 77 78 79 80
    _init();
}

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

82 83 84 85 86 87
    PlanElementController::startStaticActiveVehicle(vehicle);
    _init();
}

void MissionController::_init(void)
{
88
    // We start with an empty mission
89 90 91
    _visualItems = new QmlObjectListModel(this);
    _addPlannedHomePosition(_visualItems, false /* addToCenter */);
    _initAllVisualItems();
92 93
}

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

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

106 107
        QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
        const QList<MissionItem*>& newMissionItems = _activeVehicle->missionManager()->missionItems();
108

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

        _deinitAllVisualItems();

        _visualItems->deleteListAndContents();
        _visualItems = newControllerMissionItems;

        if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
            _addPlannedHomePosition(_visualItems,true /* addToCenter */);
121 122
        }

123
        _missionItemsRequested = false;
124

125
        _initAllVisualItems();
126
        emit newItemsFromVehicle();
127 128 129
    }
}

130
void MissionController::loadFromVehicle(void)
131
{
132
    Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
133

134 135 136 137 138 139
    if (activeVehicle) {
        _missionItemsRequested = true;
        activeVehicle->missionManager()->requestMissionItems();
    }
}

140
void MissionController::sendToVehicle(void)
141
{
142 143 144 145 146 147 148
    if (_activeVehicle) {
        // Convert to MissionItems so we can send to vehicle
        QList<MissionItem*> missionItems;

        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
            if (visualItem->isSimpleItem()) {
149
                missionItems.append(new MissionItem(qobject_cast<SimpleMissionItem*>(visualItem)->missionItem()));
150
            } else {
151
                ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
152 153 154
                QmlObjectListModel* complexMissionItems = complexItem->getMissionItems();
                for (int j=0; j<complexMissionItems->count(); j++) {
                    missionItems.append(new MissionItem(*qobject_cast<MissionItem*>(complexMissionItems->get(j))));
155
                }
156
                delete complexMissionItems;
157 158 159 160 161
            }
        }

        _activeVehicle->missionManager()->writeMissionItems(missionItems);
        _visualItems->setDirty(false);
162 163 164 165

        for (int i=0; i<missionItems.count(); i++) {
            delete missionItems[i];
        }
166 167
    }
}
168

169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184
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;
        }
    }
}

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

        if (_findLastAcceptanceRadius(&lastValue)) {
202
            newItem->missionItem().setParam2(lastValue);
203
        }
204 205
        if (_findLastAltitude(&lastValue, &lastFrame)) {
            newItem->missionItem().setFrame(lastFrame);
206
            newItem->missionItem().setParam7(lastValue);
207
        }
208
    }
209
    _visualItems->insert(i, newItem);
210 211 212

    _recalcAll();

213
    return newItem->sequenceNumber();
214 215
}

216 217
int MissionController::insertComplexMissionItem(QGeoCoordinate coordinate, int i)
{
218
    int sequenceNumber = _nextSequenceNumber();
219
    SurveyMissionItem* newItem = new SurveyMissionItem(_activeVehicle, this);
220
    newItem->setSequenceNumber(sequenceNumber);
221
    newItem->setCoordinate(coordinate);
222
    _initVisualItem(newItem);
223

224 225
    _visualItems->insert(i, newItem);
    _complexItems->append(newItem);
226 227 228

    _recalcAll();

229
    return newItem->sequenceNumber();
230 231
}

232 233
void MissionController::removeMissionItem(int index)
{
234
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
235

236 237 238
    _deinitVisualItem(item);
    if (!item->isSimpleItem()) {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(_complexItems->removeOne(item));
239
        if (!complexItem) {
240 241 242
            qWarning() << "Complex item missing";
        }
    }
243
    item->deleteLater();
244 245 246 247 248

    _recalcAll();

    // Set the new current item

249
    if (index >= _visualItems->count()) {
250 251
        index--;
    }
252
    for (int i=0; i<_visualItems->count(); i++) {
Don Gagne's avatar
Don Gagne committed
253
        VisualMissionItem* item =  qobject_cast<VisualMissionItem*>(_visualItems->get(i));
254 255
        item->setIsCurrentItem(i == index);
    }
256
    _visualItems->setDirty(true);
257 258
}

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

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

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

Don Gagne's avatar
Don Gagne committed
297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313
    if (fileVersion == 1) {
        return _loadJsonMissionFileV1(json, visualItems, complexItems, errorString);
    } else {
        return _loadJsonMissionFileV2(json, visualItems, complexItems, errorString);
    }
}

bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString)
{
    // 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)) {
314 315 316
        return false;
    }

317 318 319 320 321
    // Read complex items
    QJsonArray complexArray(json[_jsonComplexItemsKey].toArray());
    qCDebug(MissionControllerLog) << "Json load: complex item count" << complexArray.count();
    for (int i=0; i<complexArray.count(); i++) {
        const QJsonValue& itemValue = complexArray[i];
322

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

328
        SurveyMissionItem* item = new SurveyMissionItem(_activeVehicle, this);
Don Gagne's avatar
Don Gagne committed
329 330
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
331 332 333
            complexItems->append(item);
        } 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 345 346 347 348 349

    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << complexItems->count();
    do {
        qCDebug(MissionControllerLog) << "Json load: simple item loop nextSimpleItemIndex:nextComplexItemIndex:nextSequenceNumber" << nextSimpleItemIndex << nextComplexItemIndex << nextSequenceNumber;

        // If there is a complex item that should be next in sequence add it in
        if (nextComplexItemIndex < complexItems->count()) {
350
            SurveyMissionItem* complexItem = qobject_cast<SurveyMissionItem*>(complexItems->get(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();
371
            SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
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
        }
Don Gagne's avatar
Don Gagne committed
381
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < complexItems->count());
382 383

    if (json.contains(_jsonPlannedHomePositionKey)) {
384
        SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
385

Don Gagne's avatar
Don Gagne committed
386
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
387
            visualItems->insert(0, item);
388 389 390 391
        } else {
            return false;
        }
    } else {
392
        _addPlannedHomePosition(visualItems, true /* addToCenter */);
393 394 395 396 397
    }

    return true;
}

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

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

415
    // Mission Settings
Don Gagne's avatar
Don Gagne committed
416 417 418 419
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
420 421 422 423 424 425 426 427 428 429
    if (json.contains(_jsonVehicleTypeKey) && _activeVehicle->isOfflineEditingVehicle()) {
        QGroundControlQmlGlobal::offlineEditingVehicleType()->setRawValue(json[_jsonVehicleTypeKey].toDouble());
    }
    if (json.contains(_jsonCruiseSpeedKey)) {
        QGroundControlQmlGlobal::offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
    }
    if (json.contains(_jsonHoverSpeedKey)) {
        QGroundControlQmlGlobal::offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
    }

Don Gagne's avatar
Don Gagne committed
430 431 432 433 434 435 436 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 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497
    SimpleMissionItem* homeItem = new SimpleMissionItem(_activeVehicle, this);
    homeItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, homeItem);
    qCDebug(MissionControllerLog) << "plannedHomePosition" << homeCoordinate;

    // Read mission items

    int nextSequenceNumber = 1; // Start with 1 since home is in 0
    const QJsonArray rgMissionItems(json[_jsonItemsKey].toArray());
    for (int i=0; i<rgMissionItems.count(); i++) {
        // Convert to QJsonObject
        const QJsonValue& itemValue = rgMissionItems[i];
        if (!itemValue.isObject()) {
            errorString = tr("Mission item %1 is not an object").arg(i);
            return false;
        }
        const QJsonObject itemObject = itemValue.toObject();

        // Load item based on type

        QList<JsonHelper::KeyValidateInfo> itemKeyInfoList = {
            { VisualMissionItem::jsonTypeKey,  QJsonValue::String, true },
        };
        if (!JsonHelper::validateKeys(itemObject, itemKeyInfoList, errorString)) {
            return false;
        }
        QString itemType = itemObject[VisualMissionItem::jsonTypeKey].toString();

        if (itemType == VisualMissionItem::jsonTypeSimpleItemValue) {
            qCDebug(MissionControllerLog) << "Loading MISSION_ITEM: nextSequenceNumber" << nextSequenceNumber;
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_activeVehicle, this);
            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;
                SurveyMissionItem* surveyItem = new SurveyMissionItem(_activeVehicle, this);
                if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(surveyItem);
                complexItems->append(surveyItem);
            } else {
                errorString = tr("Unsupported complex item type: %1").arg(complexItemType);
            }
        } else {
            errorString = tr("Unknown item type: %1").arg(itemType);
            return false;
        }
    }

    // Fix up the DO_JUMP commands jump sequence number by finding the item with the matching doJumpId
    for (int i=0; i<visualItems->count(); i++) {
        if (visualItems->value<VisualMissionItem*>(i)->isSimpleItem()) {
            SimpleMissionItem* doJumpItem = visualItems->value<SimpleMissionItem*>(i);
Don Gagne's avatar
Don Gagne committed
498
            if ((MAV_CMD)doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521
                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;
}

522
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542
{
    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()) {
543
            SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
544 545

            if (item->load(stream)) {
546
                visualItems->append(item);
547 548 549 550 551 552 553 554 555 556
            } 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;
    }

557 558
    if (addPlannedHomePosition || visualItems->count() == 0) {
        _addPlannedHomePosition(visualItems, true /* addToCenter */);
Don Gagne's avatar
Don Gagne committed
559

560 561 562 563 564
        // 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
565 566
            }
        }
567 568 569
    }

    return true;
570 571
}

572
void MissionController::loadFromFile(const QString& filename)
573 574 575 576 577 578 579
{
    QString errorString;

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

580 581
    QmlObjectListModel* newVisualItems = new QmlObjectListModel(this);
    QmlObjectListModel* newComplexItems = new QmlObjectListModel(this);
582 583 584 585 586 587

    QFile file(filename);

    if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
        errorString = file.errorString();
    } else {
588 589
        QByteArray  bytes = file.readAll();
        QTextStream stream(&bytes);
590

591 592 593
        QString firstLine = stream.readLine();
        if (firstLine.contains(QRegExp("QGC.*WPL"))) {
            stream.seek(0);
594
            _loadTextMissionFile(stream, newVisualItems, errorString);
595
        } else {
596
            _loadJsonMissionFile(bytes, newVisualItems, newComplexItems, errorString);
597 598
        }
    }
599

600
    if (!errorString.isEmpty()) {
601 602 603 604 605 606 607 608 609
        for (int i=0; i<newVisualItems->count(); i++) {
            newVisualItems->get(i)->deleteLater();
        }
        for (int i=0; i<newComplexItems->count(); i++) {
            newComplexItems->get(i)->deleteLater();
        }
        delete newVisualItems;
        delete newComplexItems;

610
        qgcApp()->showMessage(errorString);
611
        return;
612 613
    }

614 615 616
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteListAndContents();
617
    }
618 619 620 621 622 623 624
    if (_complexItems) {
        _complexItems->deleteLater();
    }

    _visualItems = newVisualItems;
    _complexItems = newComplexItems;

625 626
    if (_visualItems->count() == 0) {
        _addPlannedHomePosition(_visualItems, true /* addToCenter */);
627 628
    }

629
    _initAllVisualItems();
630 631
}

632
void MissionController::loadFromFilePicker(void)
633
{
634
#ifndef __mobile__
635
    QString filename = QGCFileDialog::getOpenFileName(MainWindow::instance(), "Select Mission File to load", QString(), "Mission file (*.mission);;All Files (*.*)");
636 637 638 639

    if (filename.isEmpty()) {
        return;
    }
640
    loadFromFile(filename);
641 642 643
#endif
}

644
void MissionController::saveToFile(const QString& filename)
645 646
{
    qDebug() << filename;
647 648 649 650

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

652
    QString missionFilename = filename;
653
    if (!QFileInfo(filename).fileName().contains(".")) {
Don Gagne's avatar
Don Gagne committed
654
        missionFilename += QString(".%1").arg(QGCApplication::missionFileExtension);
655 656
    }

657
    QFile file(missionFilename);
658

659
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
660
        qgcApp()->showMessage(file.errorString());
661
    } else {
662
        QJsonObject missionFileObject;      // top level json object
663

Don Gagne's avatar
Don Gagne committed
664
        missionFileObject[JsonHelper::jsonVersionKey] =         _missionFileVersion;
665
        missionFileObject[JsonHelper::jsonGroundStationKey] =   JsonHelper::jsonGroundStationValue;
666

667
        // Mission settings
668

669
        SimpleMissionItem* homeItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(0));
Don Gagne's avatar
Don Gagne committed
670
        if (!homeItem) {
671 672 673
            qgcApp()->showMessage(QStringLiteral("Internal error: VisualMissionItem at index 0 not SimpleMissionItem"));
            return;
        }
Don Gagne's avatar
Don Gagne committed
674 675 676
        QJsonValue coordinateValue;
        JsonHelper::saveGeoCoordinate(homeItem->coordinate(), true /* writeAltitude */, coordinateValue);
        missionFileObject[_jsonPlannedHomePositionKey] = coordinateValue;
677 678 679 680
        missionFileObject[_jsonFirmwareTypeKey] = _activeVehicle->firmwareType();
        missionFileObject[_jsonVehicleTypeKey] = _activeVehicle->vehicleType();
        missionFileObject[_jsonCruiseSpeedKey] = _activeVehicle->cruiseSpeed();
        missionFileObject[_jsonHoverSpeedKey] = _activeVehicle->hoverSpeed();
681

682
        // Save the visual items
Don Gagne's avatar
Don Gagne committed
683
        QJsonArray  rgMissionItems;
684
        for (int i=1; i<_visualItems->count(); i++) {
685 686
            QJsonObject itemObject;

687
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
688
            visualItem->save(itemObject);
Don Gagne's avatar
Don Gagne committed
689
            rgMissionItems.append(itemObject);
690
        }
Don Gagne's avatar
Don Gagne committed
691
        missionFileObject[_jsonItemsKey] = rgMissionItems;
692 693

        QJsonDocument saveDoc(missionFileObject);
694
        file.write(saveDoc.toJson());
695 696
    }

697
    _visualItems->setDirty(false);
698 699
}

700
void MissionController::saveToFilePicker(void)
701 702
{
#ifndef __mobile__
703
    QString filename = QGCFileDialog::getSaveFileName(MainWindow::instance(), "Select file to save mission to", QString(), "Mission file (*.mission);;All Files (*.*)");
704 705 706 707

    if (filename.isEmpty()) {
        return;
    }
708
    saveToFile(filename);
709
#endif
710 711
}

712
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
713
{
Don Gagne's avatar
Don Gagne committed
714
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
715
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
716 717 718 719
    bool            distanceOk =    false;

    // Convert to fixed altitudes

720
    qCDebug(MissionControllerLog) << homeAlt
721 722
                                  << currentItem->coordinateHasRelativeAltitude() << currentItem->coordinate().altitude()
                                  << prevItem->exitCoordinateHasRelativeAltitude() << prevItem->exitCoordinate().altitude();
723

724
    distanceOk = true;
725
    if (currentItem->coordinateHasRelativeAltitude()) {
726 727
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
728
    if (prevItem->exitCoordinateHasRelativeAltitude()) {
729
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
730 731 732 733 734
    }

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

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
735 736 737
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
738
    } else {
Don Gagne's avatar
Don Gagne committed
739
        *altDifference = 0.0;
740
        *azimuth = 0.0;
741
        *distance = 0.0;
742 743 744
    }
}

745
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
746 747 748 749 750 751 752 753 754
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

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

755
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
756 757
}

758 759
void MissionController::_recalcWaypointLines(void)
{
760 761 762 763 764 765 766 767 768 769
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

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

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

    bool    showHomePosition =  homeItem->showHomePosition();
770 771 772

    qCDebug(MissionControllerLog) << "_recalcWaypointLines";

Nate Weibley's avatar
Nate Weibley committed
773 774
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
775 776 777 778 779 780 781
    _waypointLines.clear();

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


782
        // If we still haven't found the first coordinate item and we hit a takeoff command, link back to home
783 784
        if (firstCoordinateItem &&
                item->isSimpleItem() &&
785 786
                (qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF ||
                 qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) {
787 788 789 790 791 792 793 794 795 796
            linkBackToHome = true;
        }

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


    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
822 823
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852
            objs.append(vect);
        }

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


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

    _recalcAltitudeRangeBearing();

    emit waypointLinesChanged();
}

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

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

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

853
    bool showHomePosition =  homeItem->showHomePosition();
854 855 856

    qCDebug(MissionControllerLog) << "_recalcAltitudeRangeBearing";

857 858 859
    // 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.
860

861
    // No values for first item
862
    lastCoordinateItem->setAltDifference(0.0);
863
    lastCoordinateItem->setAzimuth(0.0);
864
    lastCoordinateItem->setDistance(0.0);
865

866 867
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
868
    const double homePositionAltitude = homeItem->coordinate().altitude();
869 870
    minAltSeen = maxAltSeen = homeItem->coordinate().altitude();

871 872
    double missionDistance = 0.0;
    double missionMaxTelemetry = 0.0;
873 874 875 876 877 878 879
    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();
880

881 882
    bool vtolVehicle = _activeVehicle->vtol();
    bool vtolInHover = true;
883

Don Gagne's avatar
Don Gagne committed
884
    bool linkBackToHome = false;
885

886 887
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
888 889 890
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

891 892
        // Assume the worst
        item->setAzimuth(0.0);
893
        item->setDistance(0.0);
894

895 896 897 898 899 900 901 902 903 904
        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;
                }
            }
905 906
        }

907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929
        // 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;
930 931
                }
            }
932 933 934
                break;
            default:
                break;
935
            }
Don Gagne's avatar
Don Gagne committed
936 937
        }

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

941
            double absoluteAltitude = item->coordinate().altitude();
942
            if (item->coordinateHasRelativeAltitude()) {
943 944 945 946 947
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

948 949 950 951 952 953 954 955 956 957
            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
958
                firstCoordinateItem = false;
959 960 961
                if (lastCoordinateItem != homeItem || linkBackToHome) {
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
962

963
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
964 965 966
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
967 968

                    missionDistance += distance;
969 970 971 972 973 974 975 976 977 978 979 980 981 982
                    missionMaxTelemetry = qMax(missionMaxTelemetry, _calcDistanceToHome(item, homeItem));

                    // Calculate mission time
                    if (vtolVehicle) {
                        if (vtolInHover) {
                            double hoverTime = distance / _activeVehicle->hoverSpeed();
                            missionTime += hoverTime;
                            vtolHoverTime += hoverTime;
                            vtolHoverDistance += distance;
                        } else {
                            double cruiseTime = distance / currentCruiseSpeed;
                            missionTime += cruiseTime;
                            vtolCruiseTime += cruiseTime;
                            vtolCruiseDistance += distance;
983 984
                        }
                    } else {
985
                        missionTime += distance / (_activeVehicle->multiRotor() ? currentHoverSpeed : currentCruiseSpeed);
986
                    }
987
                }
988 989 990 991 992 993 994 995 996 997 998
                if (complexItem) {
                    // Add in distance/time inside survey as well
                    // This code assumes all surveys are done cruise not hover
                    double complexDistance = complexItem->complexDistance();
                    double cruiseSpeed = _activeVehicle->multiRotor() ? currentHoverSpeed : currentCruiseSpeed;
                    missionDistance += complexDistance;
                    missionTime += complexDistance / cruiseSpeed;
                    missionMaxTelemetry = qMax(missionMaxTelemetry, complexItem->greatestDistanceTo(homeItem->exitCoordinate()));

                    // Let the complex item know the current cruise speed
                    complexItem->setCruiseSpeed(cruiseSpeed);
999
                }
1000
            }
1001 1002

            lastCoordinateItem = item;
1003 1004 1005
        }
    }

1006 1007 1008 1009 1010 1011 1012
    _setMissionMaxTelemetry(missionMaxTelemetry);
    _setMissionDistance(missionDistance);
    _setMissionTime(missionTime);
    _setMissionHoverDistance(vtolHoverDistance);
    _setMissionHoverTime(vtolHoverTime);
    _setMissionCruiseDistance(vtolCruiseDistance);
    _setMissionCruiseTime(vtolCruiseTime);
1013

1014 1015
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1016 1017
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1018 1019 1020

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1021
            if (item->coordinateHasRelativeAltitude()) {
1022 1023 1024 1025 1026 1027
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1028
            }
1029 1030 1031 1032
        }
    }
}

1033 1034 1035
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1036 1037 1038 1039 1040 1041 1042 1043 1044
    // 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);
1045

1046
            if (complexItem) {
Don Gagne's avatar
Don Gagne committed
1047
                sequenceNumber = complexItem->lastSequenceNumber() + 1;
1048 1049 1050 1051
            } else {
                qWarning() << "isSimpleItem == false, yet not ComplexMissionItem";
            }
        }
1052 1053 1054
    }
}

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

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

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

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

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

1082
/// Initializes a new set of mission items
1083
void MissionController::_initAllVisualItems(void)
1084
{
1085 1086 1087 1088 1089 1090 1091 1092 1093
    SimpleMissionItem* homeItem = NULL;

    // Setup home position at index 0

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

Don Gagne's avatar
Don Gagne committed
1095
    homeItem->setHomePositionSpecialCase(true);
1096
    homeItem->setShowHomePosition(_editMode);
1097 1098
    homeItem->missionItem().setCommand(MAV_CMD_NAV_WAYPOINT);
    homeItem->missionItem().setFrame(MAV_FRAME_GLOBAL);
1099 1100 1101 1102 1103
    homeItem->setIsCurrentItem(true);

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

1106 1107 1108 1109
    emit plannedHomePositionChanged(plannedHomePosition());

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

1110
    QmlObjectListModel* newComplexItems = new QmlObjectListModel(this);
1111 1112 1113
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
1114

1115 1116 1117
        // Set up complex item list
        if (!item->isSimpleItem()) {
            ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);
1118

1119 1120 1121 1122 1123
            if (complexItem) {
                newComplexItems->append(item);
            } else {
                qWarning() << "isSimpleItem == false, but not ComplexMissionItem";
            }
1124
        }
1125 1126
    }

1127 1128 1129 1130
    if (_complexItems) {
        _complexItems->deleteLater();
    }
    _complexItems = newComplexItems;
1131

1132
    _recalcAll();
1133

1134 1135
    emit visualItemsChanged();
    emit complexVisualItemsChanged();
1136

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

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

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

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

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

1155
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1156 1157
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
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 1233 1234 1235 1236
    if (!_editMode && _visualItems) {
        SimpleMissionItem* homeItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(0));

        if (homeItem) {
            homeItem->setShowHomePosition(homePositionAvailable);
1237
            emit plannedHomePositionChanged(plannedHomePosition());
1238 1239 1240 1241
            _recalcWaypointLines();
        } else {
            qWarning() << "Unabled to cast home item to SimpleMissionItem";
        }
1242
    }
1243 1244 1245 1246
}

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

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

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

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

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

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

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

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

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

1323
bool MissionController::_findLastAltitude(double* lastAltitude, MAV_FRAME* frame)
1324
{
1325
    bool found = false;
1326
    double foundAltitude;
1327
    MAV_FRAME foundFrame;
1328

1329
    // Don't use home position
1330
    for (int i=1; i<_visualItems->count(); i++) {
1331
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1332

1333 1334 1335 1336
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {

            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1337 1338 1339 1340
                if ((MAV_CMD)simpleItem->command() != MAV_CMD_NAV_TAKEOFF) {
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1341 1342
                }
            }
1343 1344 1345
        }
    }

1346 1347
    if (found) {
        *lastAltitude = foundAltitude;
1348
        *frame = foundFrame;
1349 1350 1351 1352 1353 1354 1355 1356 1357 1358
    }

    return found;
}

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

1359 1360
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1361

1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372
        if (visualItem->isSimpleItem()) {
            SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);

            if (simpleItem) {
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
                    foundAcceptanceRadius = simpleItem->missionItem().param2();
                    found = true;
                }
            } else {
                qWarning() << "isSimpleItem == true, yet not SimpleMissionItem";
            }
1373 1374 1375 1376 1377 1378 1379 1380
        }
    }

    if (found) {
        *lastAcceptanceRadius = foundAcceptanceRadius;
    }

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

double MissionController::_normalizeLat(double lat)
{
    // Normalize latitude to range: 0 to 180, S to N
    return lat + 90.0;
}

double MissionController::_normalizeLon(double lon)
{
    // Normalize longitude to range: 0 to 360, W to E
    return lon  + 180.0;
}

/// Add the home position item to the front of the list
1396
void MissionController::_addPlannedHomePosition(QmlObjectListModel* visualItems, bool addToCenter)
1397
{
1398 1399
    bool homePositionSet = false;

1400 1401
    SimpleMissionItem* homeItem = new SimpleMissionItem(_activeVehicle, this);
    visualItems->insert(0, homeItem);
1402

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

1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426
        for (int i=1; i<visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(visualItems->get(i));

            if (item->specifiesCoordinate()) {
                if (firstCoordSet) {
                    double lat = _normalizeLat(item->coordinate().latitude());
                    double lon = _normalizeLon(item->coordinate().longitude());
                    north = fmax(north, lat);
                    south = fmin(south, lat);
                    east = fmax(east, lon);
                    west = fmin(west, lon);
                } else {
                    firstCoordSet = true;
                    north = _normalizeLat(item->coordinate().latitude());
                    south = north;
                    east = _normalizeLon(item->coordinate().longitude());
                    west = east;
                }
            }
        }
1427

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

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

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

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

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

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

    return QGeoCoordinate();
}

void MissionController::_homeCoordinateChanged(void)
{
    emit plannedHomePositionChanged(plannedHomePosition());
    _recalcAltitudeRangeBearing();
}
1488 1489 1490 1491 1492

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

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