MissionController.cc 56.8 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
    _visualItems = new QmlObjectListModel(this);
Don Gagne's avatar
Don Gagne committed
90
    _addPlannedHomePosition(_activeVehicle, _visualItems, false /* addToCenter */);
91
    _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
        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
116
        _visualItems->deleteLater();
117 118 119
        _visualItems = newControllerMissionItems;

        if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
Don Gagne's avatar
Don Gagne committed
120
            _addPlannedHomePosition(_activeVehicle, _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
{
Don Gagne's avatar
Don Gagne committed
142 143 144 145 146 147 148
    sendItemsToVehicle(_activeVehicle, _visualItems);
    _visualItems->setDirty(false);
}

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

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

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

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

174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189
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;
        }
    }
}

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

        if (_findLastAcceptanceRadius(&lastValue)) {
207
            newItem->missionItem().setParam2(lastValue);
208
        }
209 210
        if (_findLastAltitude(&lastValue, &lastFrame)) {
            newItem->missionItem().setFrame(lastFrame);
211
            newItem->missionItem().setParam7(lastValue);
212
        }
213
    }
214
    _visualItems->insert(i, newItem);
215 216 217

    _recalcAll();

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

221 222
int MissionController::insertComplexMissionItem(QGeoCoordinate coordinate, int i)
{
223
    int sequenceNumber = _nextSequenceNumber();
Don Gagne's avatar
Don Gagne committed
224
    SurveyMissionItem* newItem = new SurveyMissionItem(_activeVehicle, _visualItems);
225
    newItem->setSequenceNumber(sequenceNumber);
226
    newItem->setCoordinate(coordinate);
227
    _initVisualItem(newItem);
228

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

    _recalcAll();

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

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

241 242 243
    _deinitVisualItem(item);
    if (!item->isSimpleItem()) {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(_complexItems->removeOne(item));
244
        if (!complexItem) {
245 246 247
            qWarning() << "Complex item missing";
        }
    }
248
    item->deleteLater();
249 250 251 252 253

    _recalcAll();

    // Set the new current item

254
    if (index >= _visualItems->count()) {
255 256
        index--;
    }
257
    for (int i=0; i<_visualItems->count(); i++) {
Don Gagne's avatar
Don Gagne committed
258
        VisualMissionItem* item =  qobject_cast<VisualMissionItem*>(_visualItems->get(i));
259 260
        item->setIsCurrentItem(i == index);
    }
261
    _visualItems->setDirty(true);
262 263
}

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

Don Gagne's avatar
Don Gagne committed
276
bool MissionController::_loadJsonMissionFile(Vehicle* vehicle, const QByteArray& bytes, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString)
277 278 279 280 281 282 283 284 285 286
{
    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
287 288 289
    // 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;
290 291
    }

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

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

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

322 323 324 325 326
    // 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];
327

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

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

342 343 344 345 346
    // 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
347
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
348 349 350 351 352 353 354

    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()) {
355
            SurveyMissionItem* complexItem = qobject_cast<SurveyMissionItem*>(complexItems->get(nextComplexItemIndex));
356 357 358 359 360 361 362 363 364 365 366 367 368 369

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

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

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

            nextSequenceNumber++;
385
        }
Don Gagne's avatar
Don Gagne committed
386
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < complexItems->count());
387 388

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

Don Gagne's avatar
Don Gagne committed
391
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
392
            visualItems->insert(0, item);
393 394 395 396
        } else {
            return false;
        }
    } else {
Don Gagne's avatar
Don Gagne committed
397
        _addPlannedHomePosition(vehicle, visualItems, true /* addToCenter */);
398 399 400 401 402
    }

    return true;
}

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

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

420
    // Mission Settings
Don Gagne's avatar
Don Gagne committed
421 422 423 424
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
Don Gagne's avatar
Don Gagne committed
425
    if (json.contains(_jsonVehicleTypeKey) && vehicle->isOfflineEditingVehicle()) {
426 427 428 429 430 431 432 433 434
        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
435
    SimpleMissionItem* homeItem = new SimpleMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
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
    homeItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, homeItem);
    qCDebug(MissionControllerLog) << "plannedHomePosition" << homeCoordinate;

    // Read mission items

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

        // Load item based on type

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

        if (itemType == VisualMissionItem::jsonTypeSimpleItemValue) {
            qCDebug(MissionControllerLog) << "Loading MISSION_ITEM: nextSequenceNumber" << nextSequenceNumber;
Don Gagne's avatar
Don Gagne committed
465
            SimpleMissionItem* simpleItem = new SimpleMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481
            if (simpleItem->load(itemObject, nextSequenceNumber++, errorString)) {
                visualItems->append(simpleItem);
            } else {
                return false;
            }
        } else if (itemType == VisualMissionItem::jsonTypeComplexItemValue) {
            QList<JsonHelper::KeyValidateInfo> complexItemKeyInfoList = {
                { ComplexMissionItem::jsonComplexItemTypeKey,  QJsonValue::String, true },
            };
            if (!JsonHelper::validateKeys(itemObject, complexItemKeyInfoList, errorString)) {
                return false;
            }
            QString complexItemType = itemObject[ComplexMissionItem::jsonComplexItemTypeKey].toString();

            if (complexItemType == SurveyMissionItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Survey: nextSequenceNumber" << nextSequenceNumber;
Don Gagne's avatar
Don Gagne committed
482
                SurveyMissionItem* surveyItem = new SurveyMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502
                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
503
            if ((MAV_CMD)doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526
                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
527
bool MissionController::_loadTextMissionFile(Vehicle* vehicle, QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547
{
    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
548
            SimpleMissionItem* item = new SimpleMissionItem(vehicle, visualItems);
549 550

            if (item->load(stream)) {
551
                visualItems->append(item);
552 553 554 555 556 557 558 559 560 561
            } 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;
    }

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

565 566 567 568 569
        // 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
570 571
            }
        }
572 573 574
    }

    return true;
575 576
}

577
void MissionController::loadFromFile(const QString& filename)
578
{
Don Gagne's avatar
Don Gagne committed
579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608
    QmlObjectListModel* newVisualItems = NULL;
    QmlObjectListModel* newComplexItems = NULL;

    if (!loadItemsFromFile(_activeVehicle, filename, &newVisualItems, &newComplexItems)) {
        return;
    }

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

    _visualItems = newVisualItems;
    _complexItems = newComplexItems;

    if (_visualItems->count() == 0) {
        _addPlannedHomePosition(_activeVehicle, _visualItems, true /* addToCenter */);
    }

    _initAllVisualItems();
}

bool MissionController::loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems, QmlObjectListModel** complexItems)
{
    *visualItems = NULL;
    *complexItems = NULL;

609 610 611
    QString errorString;

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

Don Gagne's avatar
Don Gagne committed
615 616
    *visualItems = new QmlObjectListModel();
    *complexItems = 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 {
Don Gagne's avatar
Don Gagne committed
631
            _loadJsonMissionFile(vehicle, bytes, *visualItems, *complexItems, errorString);
632 633
        }
    }
634

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

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

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

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

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

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

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

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

671
    QFile file(missionFilename);
672

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

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

681
        // Mission settings
682

683
        SimpleMissionItem* homeItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(0));
Don Gagne's avatar
Don Gagne committed
684
        if (!homeItem) {
685 686 687
            qgcApp()->showMessage(QStringLiteral("Internal error: VisualMissionItem at index 0 not SimpleMissionItem"));
            return;
        }
Don Gagne's avatar
Don Gagne committed
688 689 690
        QJsonValue coordinateValue;
        JsonHelper::saveGeoCoordinate(homeItem->coordinate(), true /* writeAltitude */, coordinateValue);
        missionFileObject[_jsonPlannedHomePositionKey] = coordinateValue;
691 692 693 694
        missionFileObject[_jsonFirmwareTypeKey] = _activeVehicle->firmwareType();
        missionFileObject[_jsonVehicleTypeKey] = _activeVehicle->vehicleType();
        missionFileObject[_jsonCruiseSpeedKey] = _activeVehicle->cruiseSpeed();
        missionFileObject[_jsonHoverSpeedKey] = _activeVehicle->hoverSpeed();
695

696
        // Save the visual items
Don Gagne's avatar
Don Gagne committed
697
        QJsonArray  rgMissionItems;
698
        for (int i=1; i<_visualItems->count(); i++) {
699 700
            QJsonObject itemObject;

701
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
702
            visualItem->save(itemObject);
Don Gagne's avatar
Don Gagne committed
703
            rgMissionItems.append(itemObject);
704
        }
Don Gagne's avatar
Don Gagne committed
705
        missionFileObject[_jsonItemsKey] = rgMissionItems;
706 707

        QJsonDocument saveDoc(missionFileObject);
708
        file.write(saveDoc.toJson());
709 710
    }

711
    _visualItems->setDirty(false);
712 713
}

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

    if (filename.isEmpty()) {
        return;
    }
722
    saveToFile(filename);
723
#endif
724 725
}

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

    // Convert to fixed altitudes

734
    qCDebug(MissionControllerLog) << homeAlt
735 736
                                  << currentItem->coordinateHasRelativeAltitude() << currentItem->coordinate().altitude()
                                  << prevItem->exitCoordinateHasRelativeAltitude() << prevItem->exitCoordinate().altitude();
737

738
    distanceOk = true;
739
    if (currentItem->coordinateHasRelativeAltitude()) {
740 741
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
742
    if (prevItem->exitCoordinateHasRelativeAltitude()) {
743
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
744 745 746 747 748
    }

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

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

759
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
760 761 762 763 764 765 766 767 768
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

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

769
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
770 771
}

772 773
void MissionController::_recalcWaypointLines(void)
{
774 775 776 777 778 779 780 781 782 783
    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();
784 785 786

    qCDebug(MissionControllerLog) << "_recalcWaypointLines";

Nate Weibley's avatar
Nate Weibley committed
787 788
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
789 790 791 792 793 794 795
    _waypointLines.clear();

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


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


    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
836 837
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866
            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";
    }

867
    bool showHomePosition =  homeItem->showHomePosition();
868 869 870

    qCDebug(MissionControllerLog) << "_recalcAltitudeRangeBearing";

871 872 873
    // 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.
874

875
    // No values for first item
876
    lastCoordinateItem->setAltDifference(0.0);
877
    lastCoordinateItem->setAzimuth(0.0);
878
    lastCoordinateItem->setDistance(0.0);
879

880 881
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
882
    const double homePositionAltitude = homeItem->coordinate().altitude();
883 884
    minAltSeen = maxAltSeen = homeItem->coordinate().altitude();

885 886
    double missionDistance = 0.0;
    double missionMaxTelemetry = 0.0;
887 888 889 890 891 892 893
    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();
894

895 896
    bool vtolVehicle = _activeVehicle->vtol();
    bool vtolInHover = true;
897

Don Gagne's avatar
Don Gagne committed
898
    bool linkBackToHome = false;
899

900 901
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
902 903 904
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

905 906
        // Assume the worst
        item->setAzimuth(0.0);
907
        item->setDistance(0.0);
908

909 910 911 912 913 914 915 916 917 918
        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;
                }
            }
919 920
        }

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

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

955
            double absoluteAltitude = item->coordinate().altitude();
956
            if (item->coordinateHasRelativeAltitude()) {
957 958 959 960 961
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

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

977
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
978 979 980
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
981 982

                    missionDistance += distance;
983 984 985 986 987 988 989 990 991 992 993 994 995 996
                    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;
997 998
                        }
                    } else {
999
                        missionTime += distance / (_activeVehicle->multiRotor() ? currentHoverSpeed : currentCruiseSpeed);
1000
                    }
1001
                }
1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012
                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);
1013
                }
1014
            }
1015 1016

            lastCoordinateItem = item;
1017 1018 1019
        }
    }

1020 1021 1022 1023 1024 1025 1026
    _setMissionMaxTelemetry(missionMaxTelemetry);
    _setMissionDistance(missionDistance);
    _setMissionTime(missionTime);
    _setMissionHoverDistance(vtolHoverDistance);
    _setMissionHoverTime(vtolHoverTime);
    _setMissionCruiseDistance(vtolCruiseDistance);
    _setMissionCruiseTime(vtolCruiseTime);
1027

1028 1029
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1030 1031
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1032 1033 1034

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1035
            if (item->coordinateHasRelativeAltitude()) {
1036 1037 1038 1039 1040 1041
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1042
            }
1043 1044 1045 1046
        }
    }
}

1047 1048 1049
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1050 1051 1052 1053 1054 1055 1056 1057 1058
    // 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);
1059

1060
            if (complexItem) {
Don Gagne's avatar
Don Gagne committed
1061
                sequenceNumber = complexItem->lastSequenceNumber() + 1;
1062 1063 1064 1065
            } else {
                qWarning() << "isSimpleItem == false, yet not ComplexMissionItem";
            }
        }
1066 1067 1068
    }
}

1069 1070 1071
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1072
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1073 1074 1075

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

1076 1077
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1078 1079 1080 1081 1082

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1083
        } else if (item->isSimpleItem()) {
1084 1085 1086 1087 1088
            currentParentItem->childItems()->append(item);
        }
    }
}

1089 1090
void MissionController::_recalcAll(void)
{
1091
    _recalcSequence();
1092 1093 1094 1095
    _recalcChildItems();
    _recalcWaypointLines();
}

1096
/// Initializes a new set of mission items
1097
void MissionController::_initAllVisualItems(void)
1098
{
1099 1100 1101 1102 1103 1104 1105 1106 1107
    SimpleMissionItem* homeItem = NULL;

    // Setup home position at index 0

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

Don Gagne's avatar
Don Gagne committed
1109
    homeItem->setHomePositionSpecialCase(true);
1110
    homeItem->setShowHomePosition(_editMode);
1111 1112
    homeItem->missionItem().setCommand(MAV_CMD_NAV_WAYPOINT);
    homeItem->missionItem().setFrame(MAV_FRAME_GLOBAL);
1113 1114 1115 1116 1117
    homeItem->setIsCurrentItem(true);

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

1120 1121 1122 1123
    emit plannedHomePositionChanged(plannedHomePosition());

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

1124
    QmlObjectListModel* newComplexItems = new QmlObjectListModel(this);
1125 1126 1127
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
1128

1129 1130 1131
        // Set up complex item list
        if (!item->isSimpleItem()) {
            ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);
1132

1133 1134 1135 1136 1137
            if (complexItem) {
                newComplexItems->append(item);
            } else {
                qWarning() << "isSimpleItem == false, but not ComplexMissionItem";
            }
1138
        }
1139 1140
    }

1141 1142 1143 1144
    if (_complexItems) {
        _complexItems->deleteLater();
    }
    _complexItems = newComplexItems;
1145

1146
    _recalcAll();
1147

1148 1149
    emit visualItemsChanged();
    emit complexVisualItemsChanged();
1150

1151
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1152

1153
    _visualItems->setDirty(false);
1154 1155
}

1156
void MissionController::_deinitAllVisualItems(void)
1157
{
1158 1159
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1160 1161
    }

1162
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1163 1164
}

1165
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1166
{
1167 1168
    _visualItems->setDirty(false);

1169
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1170 1171
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
1172
    connect(visualItem, &VisualMissionItem::flightSpeedChanged,                         this, &MissionController::_recalcAltitudeRangeBearing);
1173

1174 1175 1176 1177 1178 1179 1180 1181
    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";
        }
1182 1183 1184 1185
    } 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);
1186
        connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcAltitudeRangeBearing);
1187
    }
1188 1189
}

1190
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1191
{
1192 1193
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1194 1195
}

1196
void MissionController::_itemCommandChanged(void)
1197
{
1198 1199
    _recalcChildItems();
    _recalcWaypointLines();
1200 1201
}

1202
void MissionController::_activeVehicleBeingRemoved(void)
1203
{
1204
    qCDebug(MissionControllerLog) << "MissionController::_activeVehicleBeingRemoved";
1205

1206
    MissionManager* missionManager = _activeVehicle->missionManager();
1207 1208 1209 1210

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

Don Gagne's avatar
Don Gagne committed
1214 1215
    // 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
1216 1217
    removeAll();
}
Don Gagne's avatar
Don Gagne committed
1218

1219 1220 1221 1222 1223
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();
1224

1225 1226 1227 1228 1229 1230 1231
    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);
1232 1233
    connect(_activeVehicle, &Vehicle::cruiseSpeedChanged,               this, &MissionController::_recalcAltitudeRangeBearing);
    connect(_activeVehicle, &Vehicle::hoverSpeedChanged,                this, &MissionController::_recalcAltitudeRangeBearing);
1234

1235
    if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
1236 1237 1238
        // 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();
1239
    }
1240

1241 1242
    _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
    _activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
1243 1244 1245 1246
}

void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
1247 1248 1249 1250 1251
    if (!_editMode && _visualItems) {
        SimpleMissionItem* homeItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(0));

        if (homeItem) {
            homeItem->setShowHomePosition(homePositionAvailable);
1252
            emit plannedHomePositionChanged(plannedHomePosition());
1253 1254 1255 1256
            _recalcWaypointLines();
        } else {
            qWarning() << "Unabled to cast home item to SimpleMissionItem";
        }
1257
    }
1258 1259 1260 1261
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
1262
    if (!_editMode && _visualItems) {
1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273
        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";
        }
1274
    }
1275 1276
}

1277 1278 1279 1280 1281 1282 1283 1284 1285
void MissionController::_setMissionMaxTelemetry(double missionMaxTelemetry)
{
    if (!qFuzzyCompare(_missionMaxTelemetry, missionMaxTelemetry)) {
        _missionMaxTelemetry = missionMaxTelemetry;
        emit missionMaxTelemetryChanged(_missionMaxTelemetry);
    }
}

void MissionController::_setMissionDistance(double missionDistance)
1286 1287 1288 1289 1290 1291 1292
{
    if (!qFuzzyCompare(_missionDistance, missionDistance)) {
        _missionDistance = missionDistance;
        emit missionDistanceChanged(_missionDistance);
    }
}

1293
void MissionController::_setMissionTime(double missionTime)
1294
{
1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305
    if (!qFuzzyCompare(_missionTime, missionTime)) {
        _missionTime = missionTime;
        emit missionTimeChanged();
    }
}

void MissionController::_setMissionHoverTime(double missionHoverTime)
{
    if (!qFuzzyCompare(_missionHoverTime, missionHoverTime)) {
        _missionHoverTime = missionHoverTime;
        emit missionHoverTimeChanged();
1306 1307 1308
    }
}

1309
void MissionController::_setMissionHoverDistance(double missionHoverDistance)
1310
{
1311 1312 1313
    if (!qFuzzyCompare(_missionHoverDistance, missionHoverDistance)) {
        _missionHoverDistance = missionHoverDistance;
        emit missionHoverDistanceChanged(_missionHoverDistance);
1314 1315 1316
    }
}

1317
void MissionController::_setMissionCruiseTime(double missionCruiseTime)
1318
{
1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329
    if (!qFuzzyCompare(_missionCruiseTime, missionCruiseTime)) {
        _missionCruiseTime = missionCruiseTime;
        emit missionCruiseTimeChanged();
    }
}

void MissionController::_setMissionCruiseDistance(double missionCruiseDistance)
{
    if (!qFuzzyCompare(_missionCruiseDistance, missionCruiseDistance)) {
        _missionCruiseDistance = missionCruiseDistance;
        emit missionCruiseDistanceChanged(_missionCruiseDistance);
1330 1331 1332
    }
}

1333
void MissionController::_inProgressChanged(bool inProgress)
1334
{
1335
    emit syncInProgressChanged(inProgress);
1336
}
1337

1338
bool MissionController::_findLastAltitude(double* lastAltitude, MAV_FRAME* frame)
1339
{
1340
    bool found = false;
1341
    double foundAltitude;
1342
    MAV_FRAME foundFrame;
1343

1344
    // Don't use home position
1345
    for (int i=1; i<_visualItems->count(); i++) {
1346
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1347

1348 1349 1350 1351
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {

            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1352 1353 1354 1355
                if ((MAV_CMD)simpleItem->command() != MAV_CMD_NAV_TAKEOFF) {
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1356 1357
                }
            }
1358 1359 1360
        }
    }

1361 1362
    if (found) {
        *lastAltitude = foundAltitude;
1363
        *frame = foundFrame;
1364 1365 1366 1367 1368 1369 1370 1371 1372 1373
    }

    return found;
}

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

1374 1375
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1376

1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387
        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";
            }
1388 1389 1390 1391 1392 1393 1394 1395
        }
    }

    if (found) {
        *lastAcceptanceRadius = foundAcceptanceRadius;
    }

    return found;
1396
}
1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410

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

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

/// Add the home position item to the front of the list
Don Gagne's avatar
Don Gagne committed
1411
void MissionController::_addPlannedHomePosition(Vehicle* vehicle, QmlObjectListModel* visualItems, bool addToCenter)
1412
{
1413 1414
    bool homePositionSet = false;

Don Gagne's avatar
Don Gagne committed
1415
    SimpleMissionItem* homeItem = new SimpleMissionItem(vehicle, visualItems);
1416
    visualItems->insert(0, homeItem);
1417

1418
    if (visualItems->count() > 1  && addToCenter) {
1419 1420
        double north, south, east, west;
        bool firstCoordSet = false;
1421

1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441
        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;
                }
            }
        }
1442

1443 1444 1445
        if (firstCoordSet) {
            homePositionSet = true;
            homeItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
1446
        }
1447
    }
1448

1449
    if (!homePositionSet) {
1450 1451 1452
        homeItem->setCoordinate(qgcApp()->lastKnownHomePosition());
    }
}
1453 1454 1455 1456 1457 1458 1459 1460

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

1461 1462
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1463 1464 1465 1466
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
    }
}
1467

1468
bool MissionController::syncInProgress(void) const
1469
{
1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482
    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);
1483
    }
1484
}
1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502

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();
}
1503 1504 1505 1506 1507

QString MissionController::fileExtension(void) const
{
    return QGCApplication::missionFileExtension;
}
1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523 1524 1525

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