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


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

27
#ifndef __mobile__
28
#include "MainWindow.h"
29
#include "QGCQFileDialog.h"
30 31
#endif

32 33
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

MissionController::MissionController(QObject *parent)
51
    : PlanElementController(parent)
52
    , _visualItems(NULL)
53
    , _settingsItem(NULL)
54
    , _firstItemsFromVehicle(false)
55 56
    , _missionItemsRequested(false)
    , _queuedSend(false)
57 58
    , _surveyMissionItemName(tr("Survey"))
    , _fwLandingMissionItemName(tr("Fixed Wing Landing"))
59
{
DonLakeFlyer's avatar
DonLakeFlyer committed
60 61 62 63 64 65 66 67 68 69
    _missionFlightStatus.maxTelemetryDistance = 0;
    _missionFlightStatus.totalDistance = 0;
    _missionFlightStatus.totalTime = 0;
    _missionFlightStatus.hoverDistance = 0;
    _missionFlightStatus.hoverTime = 0;
    _missionFlightStatus.cruiseDistance = 0;
    _missionFlightStatus.cruiseTime = 0;
    _missionFlightStatus.cruiseSpeed = 0;
    _missionFlightStatus.hoverSpeed = 0;
    _missionFlightStatus.gimbalYaw = 0;
70 71 72 73
}

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

75 76 77 78
}

void MissionController::start(bool editMode)
{
79 80
    qCDebug(MissionControllerLog) << "start editMode" << editMode;

81
    PlanElementController::start(editMode);
82 83 84 85 86 87
    _init();
}

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

89 90 91 92 93 94
    PlanElementController::startStaticActiveVehicle(vehicle);
    _init();
}

void MissionController::_init(void)
{
95
    // We start with an empty mission
96
    _visualItems = new QmlObjectListModel(this);
97
    _addMissionSettings(_activeVehicle, _visualItems, false /* addToCenter */);
98
    _initAllVisualItems();
99 100
}

101
// Called when new mission items have completed downloading from Vehicle
102
void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllRequested)
103
{
104 105
    qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle";

106 107
    if (!_editMode || removeAllRequested || _missionItemsRequested || _visualItems->count() == 1) {
        // Fly Mode (accept if):
Don Gagne's avatar
Don Gagne committed
108
        //      - Always accepts new items from the vehicle so Fly view is kept up to date
109
        // Edit Mode (accept if):
110
        //      - Either a load from vehicle was manually requested or
Don Gagne's avatar
Don Gagne committed
111
        //      - The initial automatic load from a vehicle completed and the current editor is empty
112
        //      - Remove all way requested from Fly view (clear mission on flight end)
113

114 115
        QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
        const QList<MissionItem*>& newMissionItems = _activeVehicle->missionManager()->missionItems();
116 117 118 119 120 121
        qCDebug(MissionControllerLog) << "loading from vehicle: count"<< newMissionItems.count();

        int i = 0;
        if (_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() && newMissionItems.count() != 0) {
            // First item is fake home position
            _addMissionSettings(_activeVehicle, newControllerMissionItems, false /* addToCenter */);
122
            MissionSettingsItem* settingsItem = newControllerMissionItems->value<MissionSettingsItem*>(0);
123 124 125 126 127 128 129
            if (!settingsItem) {
                qWarning() << "First item is not settings item";
                return;
            }
            settingsItem->setCoordinate(newMissionItems[0]->coordinate());
            i = 1;
        }
130

131 132
        for (; i<newMissionItems.count(); i++) {
            const MissionItem* missionItem = newMissionItems[i];
133 134 135 136
            newControllerMissionItems->append(new SimpleMissionItem(_activeVehicle, *missionItem, this));
        }

        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
137
        _visualItems->deleteLater();
138
        _settingsItem = NULL;
139 140 141
        _visualItems = newControllerMissionItems;

        if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
142
            _addMissionSettings(_activeVehicle, _visualItems, _visualItems->count() > 0 /* addToCenter */);
143 144
        }

145
        _missionItemsRequested = false;
146

147
        if (_editMode) {
148
            MissionController::_scanForAdditionalSettings(_visualItems, _activeVehicle);
149
        }
150

151
        _initAllVisualItems();
152
        emit newItemsFromVehicle();
153 154 155
    }
}

156
void MissionController::loadFromVehicle(void)
157
{
158
    Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
159

160 161 162 163 164 165
    if (activeVehicle) {
        _missionItemsRequested = true;
        activeVehicle->missionManager()->requestMissionItems();
    }
}

166
void MissionController::sendToVehicle(void)
167
{
Don Gagne's avatar
Don Gagne committed
168 169 170 171
    sendItemsToVehicle(_activeVehicle, _visualItems);
    _visualItems->setDirty(false);
}

172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192
/// Converts from visual items to MissionItems
///     @param missionItemParent QObject parent for newly allocated MissionItems
/// @return true: Mission end action was added to end of list
bool MissionController::_convertToMissionItems(QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent)
{
    bool endActionSet = false;
    int lastSeqNum = 0;

    for (int i=0; i<visualMissionItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(visualMissionItems->get(i));

        lastSeqNum = visualItem->lastSequenceNumber();
        visualItem->appendMissionItems(rgMissionItems, missionItemParent);

        qCDebug(MissionControllerLog) << "_convertToMissionItems seqNum:lastSeqNum:command"
                                      << visualItem->sequenceNumber()
                                      << lastSeqNum
                                      << visualItem->commandName();
    }

    // Mission settings has a special case for end mission action
193
    MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
194 195 196 197 198 199 200
    if (settingsItem) {
        endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
    }

    return endActionSet;
}

Don Gagne's avatar
Don Gagne committed
201 202 203
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
204
        QList<MissionItem*> rgMissionItems;
205

206
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
207

208
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
209

210 211
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
212
        }
213 214
    }
}
215

216 217 218 219 220 221
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
222 223
        VisualMissionItem* lastItem = _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1);
        return lastItem->lastSequenceNumber() + 1;
224 225 226
    }
}

227
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
228
{
229
    int sequenceNumber = _nextSequenceNumber();
230
    SimpleMissionItem * newItem = new SimpleMissionItem(_activeVehicle, this);
231
    newItem->setSequenceNumber(sequenceNumber);
232
    newItem->setCoordinate(coordinate);
233 234 235
    newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
    _initVisualItem(newItem);
    if (_visualItems->count() == 1) {
236 237
        newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
    }
238
    newItem->setDefaultsForCommand();
Don Gagne's avatar
Don Gagne committed
239
    if ((MAV_CMD)newItem->command() == MAV_CMD_NAV_WAYPOINT) {
240 241
        double      prevAltitude;
        MAV_FRAME   prevFrame;
242

243 244 245
        if (_findPreviousAltitude(i, &prevAltitude, &prevFrame)) {
            newItem->missionItem().setFrame(prevFrame);
            newItem->missionItem().setParam7(prevAltitude);
246
        }
247
    }
248
    _visualItems->insert(i, newItem);
249 250 251

    _recalcAll();

252
    return newItem->sequenceNumber();
253 254
}

255
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
256
{
257 258
    ComplexMissionItem* newItem;

259
    int sequenceNumber = _nextSequenceNumber();
260 261
    if (itemName == _surveyMissionItemName) {
        newItem = new SurveyMissionItem(_activeVehicle, _visualItems);
262
        newItem->setCoordinate(mapCenterCoordinate);
263
    } else if (itemName == _fwLandingMissionItemName) {
264
        newItem = new FixedWingLandingComplexItem(_activeVehicle, _visualItems);
265 266 267 268
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }
269
    newItem->setSequenceNumber(sequenceNumber);
270
    _initVisualItem(newItem);
271

272
    _visualItems->insert(i, newItem);
273 274 275

    _recalcAll();

276
    return newItem->sequenceNumber();
277 278
}

279 280
void MissionController::removeMissionItem(int index)
{
281
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
282

283
    _deinitVisualItem(item);
284
    item->deleteLater();
285 286

    _recalcAll();
287
    _visualItems->setDirty(true);
288 289
}

290
void MissionController::removeAll(void)
291
{
292 293
    if (_visualItems) {
        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
294
        _visualItems->deleteLater();
295
        _settingsItem = NULL;
296
        _visualItems = new QmlObjectListModel(this);
297
        _addMissionSettings(_activeVehicle, _visualItems, false /* addToCenter */);
298
        _initAllVisualItems();
Don Gagne's avatar
Don Gagne committed
299
        _visualItems->setDirty(true);
300
    }
301
}
302

303
bool MissionController::_loadJsonMissionFile(Vehicle* vehicle, const QByteArray& bytes, QmlObjectListModel* visualItems, QString& errorString)
304 305 306 307 308 309 310 311 312 313
{
    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
314 315 316
    // 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;
317 318
    }

Don Gagne's avatar
Don Gagne committed
319 320 321 322 323 324 325
    int fileVersion;
    if (!JsonHelper::validateQGCJsonFile(json,
                                         _jsonFileTypeValue,    // expected file type
                                         1,                     // minimum supported version
                                         2,                     // maximum supported version
                                         fileVersion,
                                         errorString)) {
326 327
        return false;
    }
328

Don Gagne's avatar
Don Gagne committed
329
    if (fileVersion == 1) {
330
        return _loadJsonMissionFileV1(vehicle, json, visualItems, errorString);
Don Gagne's avatar
Don Gagne committed
331
    } else {
332
        return _loadJsonMissionFileV2(vehicle, json, visualItems, errorString);
Don Gagne's avatar
Don Gagne committed
333 334 335
    }
}

336
bool MissionController::_loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
337 338 339 340 341 342 343 344 345
{
    // 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)) {
346 347 348
        return false;
    }

349
    // Read complex items
350
    QList<SurveyMissionItem*> surveyItems;
351 352 353 354
    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];
355

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

Don Gagne's avatar
Don Gagne committed
361
        SurveyMissionItem* item = new SurveyMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
362 363
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
364
            surveyItems.append(item);
365 366
        } else {
            return false;
367
        }
368
    }
369

370 371 372 373 374
    // 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
375
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
376

377
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
378 379 380 381
    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
382 383
        if (nextComplexItemIndex < surveyItems.count()) {
            SurveyMissionItem* complexItem = surveyItems[nextComplexItemIndex];
384 385 386 387 388 389 390 391 392 393 394 395 396 397

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

398 399 400 401 402
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
403
            const QJsonObject itemObject = itemValue.toObject();
Don Gagne's avatar
Don Gagne committed
404
            SimpleMissionItem* item = new SimpleMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
405
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
406
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
407
                nextSequenceNumber = item->lastSequenceNumber() + 1;
408
                visualItems->append(item);
409 410 411 412
            } else {
                return false;
            }
        }
413
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
414 415

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

Don Gagne's avatar
Don Gagne committed
418
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
419
            MissionSettingsItem* settingsItem = new MissionSettingsItem(vehicle, visualItems);
420 421 422
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
423 424 425 426
        } else {
            return false;
        }
    } else {
427
        _addMissionSettings(vehicle, visualItems, true /* addToCenter */);
428 429 430 431 432
    }

    return true;
}

433
bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
434 435 436 437 438 439
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
440 441 442
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
443 444 445 446 447 448 449
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

450
    // Mission Settings
Don Gagne's avatar
Don Gagne committed
451
    QGeoCoordinate homeCoordinate;
452
    SettingsManager* settingsManager = qgcApp()->toolbox()->settingsManager();
Don Gagne's avatar
Don Gagne committed
453 454 455
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
Don Gagne's avatar
Don Gagne committed
456
    if (json.contains(_jsonVehicleTypeKey) && vehicle->isOfflineEditingVehicle()) {
457
        settingsManager->appSettings()->offlineEditingVehicleType()->setRawValue(json[_jsonVehicleTypeKey].toDouble());
458 459
    }
    if (json.contains(_jsonCruiseSpeedKey)) {
460
        settingsManager->appSettings()->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
461 462
    }
    if (json.contains(_jsonHoverSpeedKey)) {
463
        settingsManager->appSettings()->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
464 465
    }

466
    MissionSettingsItem* settingsItem = new MissionSettingsItem(vehicle, visualItems);
467 468
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
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
    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) {
Don Gagne's avatar
Don Gagne committed
495
            SimpleMissionItem* simpleItem = new SimpleMissionItem(vehicle, visualItems);
496
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
497
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
498
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
499 500 501 502 503 504 505 506 507 508 509 510 511 512 513
                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
514
                SurveyMissionItem* surveyItem = new SurveyMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
515 516 517 518 519 520
                if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(surveyItem);
521
            } else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
522 523 524 525 526 527 528 529
                qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
                FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(vehicle, visualItems);
                if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(landingItem);
530
            } else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
531
                qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
532
                MissionSettingsItem* settingsItem = new MissionSettingsItem(vehicle, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
533 534 535 536 537 538
                if (!settingsItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = settingsItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Mission Settings load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(settingsItem);
Don Gagne's avatar
Don Gagne committed
539 540 541 542 543 544 545 546 547 548 549 550 551
            } 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
552
            if ((MAV_CMD)doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575
                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
576
bool MissionController::_loadTextMissionFile(Vehicle* vehicle, QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596
{
    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
597
            SimpleMissionItem* item = new SimpleMissionItem(vehicle, visualItems);
598 599

            if (item->load(stream)) {
600
                visualItems->append(item);
601 602 603 604 605 606
            } else {
                errorString = QStringLiteral("The mission file is corrupted.");
                return false;
            }
        }
    } else {
607
        errorString = QStringLiteral("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
608 609 610
        return false;
    }

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

614 615 616 617 618
        // 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
619 620
            }
        }
621 622 623
    }

    return true;
624 625
}

626
void MissionController::loadFromFile(const QString& filename)
627
{
Don Gagne's avatar
Don Gagne committed
628 629
    QmlObjectListModel* newVisualItems = NULL;

630
    if (!loadItemsFromFile(_activeVehicle, filename, &newVisualItems)) {
Don Gagne's avatar
Don Gagne committed
631 632 633 634 635 636
        return;
    }

    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
637
        _settingsItem = NULL;
Don Gagne's avatar
Don Gagne committed
638 639 640 641 642
    }

    _visualItems = newVisualItems;

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

646
    MissionController::_scanForAdditionalSettings(_visualItems, _activeVehicle);
647

Don Gagne's avatar
Don Gagne committed
648
    _initAllVisualItems();
DonLakeFlyer's avatar
DonLakeFlyer committed
649 650 651 652 653 654 655 656 657 658 659 660 661 662 663

    QString filenameOnly = filename;
    int lastSepIndex = filename.lastIndexOf(QStringLiteral("/"));
    if (lastSepIndex != -1) {
        filenameOnly = filename.right(filename.length() - lastSepIndex - 1);
    }
    QString extension = AppSettings::missionFileExtension;
    if (filenameOnly.endsWith("." + extension)) {
        filenameOnly = filenameOnly.left(filenameOnly.length() - extension.length() - 1);
    }

    _settingsItem->missionName()->setRawValue(filenameOnly);
    _settingsItem->setExistingMission(true);

    sendToVehicle();
Don Gagne's avatar
Don Gagne committed
664 665
}

666
bool MissionController::loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems)
Don Gagne's avatar
Don Gagne committed
667 668 669
{
    *visualItems = NULL;

670 671 672
    QString errorString;

    if (filename.isEmpty()) {
Don Gagne's avatar
Don Gagne committed
673
        return false;
674 675
    }

Don Gagne's avatar
Don Gagne committed
676
    *visualItems = new QmlObjectListModel();
677 678 679 680

    QFile file(filename);

    if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
Don Gagne's avatar
Don Gagne committed
681
        errorString = file.errorString() + QStringLiteral(" ") + filename;
682
    } else {
683 684
        QByteArray  bytes = file.readAll();
        QTextStream stream(&bytes);
685

686 687 688
        QString firstLine = stream.readLine();
        if (firstLine.contains(QRegExp("QGC.*WPL"))) {
            stream.seek(0);
Don Gagne's avatar
Don Gagne committed
689
            _loadTextMissionFile(vehicle, stream, *visualItems, errorString);
690
        } else {
691
            _loadJsonMissionFile(vehicle, bytes, *visualItems, errorString);
692 693
        }
    }
694

695
    if (!errorString.isEmpty()) {
Don Gagne's avatar
Don Gagne committed
696
        (*visualItems)->deleteLater();
697

698
        qgcApp()->showMessage(errorString);
Don Gagne's avatar
Don Gagne committed
699
        return false;
700 701
    }

Don Gagne's avatar
Don Gagne committed
702
    return true;
703 704
}

705
void MissionController::saveToFile(const QString& filename)
706 707
{
    qDebug() << filename;
708 709 710 711

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

713
    QString missionFilename = filename;
714
    if (!QFileInfo(filename).fileName().contains(".")) {
715
        missionFilename += QString(".%1").arg(AppSettings::missionFileExtension);
716 717
    }

718
    QFile file(missionFilename);
719

720
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
721
        qgcApp()->showMessage(file.errorString());
722
    } else {
723
        QJsonObject missionFileObject;      // top level json object
724

Don Gagne's avatar
Don Gagne committed
725
        missionFileObject[JsonHelper::jsonVersionKey] =         _missionFileVersion;
726
        missionFileObject[JsonHelper::jsonGroundStationKey] =   JsonHelper::jsonGroundStationValue;
727

728
        // Mission settings
729

730
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
731
        if (!settingsItem) {
732
            qWarning() << "First item is not MissionSettingsItem";
733 734
            return;
        }
Don Gagne's avatar
Don Gagne committed
735
        QJsonValue coordinateValue;
736
        JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
Don Gagne's avatar
Don Gagne committed
737
        missionFileObject[_jsonPlannedHomePositionKey] = coordinateValue;
738 739
        missionFileObject[_jsonFirmwareTypeKey] = _activeVehicle->firmwareType();
        missionFileObject[_jsonVehicleTypeKey] = _activeVehicle->vehicleType();
DonLakeFlyer's avatar
DonLakeFlyer committed
740 741
        missionFileObject[_jsonCruiseSpeedKey] = _activeVehicle->defaultCruiseSpeed();
        missionFileObject[_jsonHoverSpeedKey] = _activeVehicle->defaultHoverSpeed();
742

743
        // Save the visual items
744

DonLakeFlyer's avatar
DonLakeFlyer committed
745
        QJsonArray rgJsonMissionItems;
746
        for (int i=0; i<_visualItems->count(); i++) {
747
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764

            visualItem->save(rgJsonMissionItems);
        }

        // Mission settings has a special case for end mission action
        if (settingsItem) {
            QList<MissionItem*> rgMissionItems;

            if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
                QJsonObject saveObject;
                MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
                missionItem->save(saveObject);
                rgJsonMissionItems.append(saveObject);
            }
            for (int i=0; i<rgMissionItems.count(); i++) {
                rgMissionItems[i]->deleteLater();
            }
765
        }
766 767

        missionFileObject[_jsonItemsKey] = rgJsonMissionItems;
768 769

        QJsonDocument saveDoc(missionFileObject);
770
        file.write(saveDoc.toJson());
771 772
    }

773
    _visualItems->setDirty(false);
774 775
}

776
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
777
{
Don Gagne's avatar
Don Gagne committed
778
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
779
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
780 781 782 783
    bool            distanceOk =    false;

    // Convert to fixed altitudes

784
    qCDebug(MissionControllerLog) << homeAlt
785 786
                                  << currentItem->coordinateHasRelativeAltitude() << currentItem->coordinate().altitude()
                                  << prevItem->exitCoordinateHasRelativeAltitude() << prevItem->exitCoordinate().altitude();
787

788
    distanceOk = true;
789
    if (currentItem->coordinateHasRelativeAltitude()) {
790 791
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
792
    if (prevItem->exitCoordinateHasRelativeAltitude()) {
793
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
794 795 796 797 798
    }

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

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
799 800 801
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
802
    } else {
Don Gagne's avatar
Don Gagne committed
803
        *altDifference = 0.0;
804
        *azimuth = 0.0;
805
        *distance = 0.0;
806 807 808
    }
}

809
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
810 811 812 813 814 815 816 817 818
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

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

819
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
820 821
}

822 823
void MissionController::_recalcWaypointLines(void)
{
824 825 826
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

827
    bool showHomePosition = _settingsItem->coordinate().isValid();
828 829 830

    qCDebug(MissionControllerLog) << "_recalcWaypointLines";

Nate Weibley's avatar
Nate Weibley committed
831 832
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
833 834 835 836 837 838 839
    _waypointLines.clear();

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


840
        // If we still haven't found the first coordinate item and we hit a takeoff command, link back to home
841 842
        if (firstCoordinateItem &&
                item->isSimpleItem() &&
843 844
                (qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF ||
                 qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) {
845 846 847 848 849 850 851
            linkBackToHome = true;
        }

        if (item->specifiesCoordinate()) {
            if (!item->isStandaloneCoordinate()) {
                firstCoordinateItem = false;
                VisualItemPair pair(lastCoordinateItem, item);
852
                if (lastCoordinateItem != _settingsItem || (showHomePosition && linkBackToHome)) {
853 854
                    if (old_table.contains(pair)) {
                        // Do nothing, this segment already exists and is wired up
Nate Weibley's avatar
Nate Weibley committed
855
                        _linesTable[pair] = old_table.take(pair);
856 857 858 859
                    } 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
860
                                endNotifier    = &VisualMissionItem::coordinateChanged;
861 862 863 864 865 866
                        // 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
DonLakeFlyer's avatar
DonLakeFlyer committed
867
                        connect(item, &VisualMissionItem::coordinateChanged, this, &MissionController::_recalcMissionFlightStatus);
Nate Weibley's avatar
Nate Weibley committed
868
                        _linesTable[pair] = linevect;
869 870 871 872 873 874 875 876 877 878
                    }
                }
                lastCoordinateItem = item;
            }
        }
    }

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
879 880
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
881 882 883 884 885 886 887 888 889 890
            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);

DonLakeFlyer's avatar
DonLakeFlyer committed
891
    _recalcMissionFlightStatus();
892 893 894 895

    emit waypointLinesChanged();
}

DonLakeFlyer's avatar
DonLakeFlyer committed
896
void MissionController::_recalcMissionFlightStatus()
897
{
898
    if (!_visualItems->count()) {
899
        return;
900
    }
901 902 903 904

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

905
    bool showHomePosition = _settingsItem->coordinate().isValid();
906

DonLakeFlyer's avatar
DonLakeFlyer committed
907
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
908

909 910 911
    // 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.
912

913
    // No values for first item
914
    lastCoordinateItem->setAltDifference(0.0);
915
    lastCoordinateItem->setAzimuth(0.0);
916
    lastCoordinateItem->setDistance(0.0);
917

918 919
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
920 921
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
922

DonLakeFlyer's avatar
DonLakeFlyer committed
923 924 925 926 927 928 929 930 931 932 933 934 935
    double lastVehicleYaw = 0;

    _missionFlightStatus.totalDistance =        0.0;
    _missionFlightStatus.maxTelemetryDistance = 0.0;
    _missionFlightStatus.totalTime =            0.0;
    _missionFlightStatus.hoverTime =            0.0;
    _missionFlightStatus.cruiseTime =           0.0;
    _missionFlightStatus.hoverDistance =        0.0;
    _missionFlightStatus.cruiseDistance =       0.0;
    _missionFlightStatus.cruiseSpeed =          _activeVehicle->defaultCruiseSpeed();
    _missionFlightStatus.hoverSpeed =           _activeVehicle->defaultHoverSpeed();
    _missionFlightStatus.vehicleSpeed =         _activeVehicle->multiRotor() || _activeVehicle->vtol() ? _missionFlightStatus.hoverSpeed : _missionFlightStatus.cruiseSpeed;
    _missionFlightStatus.gimbalYaw =            std::numeric_limits<double>::quiet_NaN();
936

DonLakeFlyer's avatar
DonLakeFlyer committed
937
    bool vtolInHover = true;
Don Gagne's avatar
Don Gagne committed
938
    bool linkBackToHome = false;
939

DonLakeFlyer's avatar
DonLakeFlyer committed
940
    for (int i=0; i<_visualItems->count(); i++) {
941
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
942 943 944
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

945 946
        // Assume the worst
        item->setAzimuth(0.0);
947
        item->setDistance(0.0);
948

DonLakeFlyer's avatar
DonLakeFlyer committed
949 950 951 952 953 954 955 956
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
            if (_activeVehicle->multiRotor()) {
                _missionFlightStatus.hoverSpeed = newSpeed;
            } else if (_activeVehicle->vtol()) {
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
957
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
958
                    _missionFlightStatus.cruiseSpeed = newSpeed;
959
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
960 961
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
962
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
963 964 965 966
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
967 968 969 970 971 972
        if (_activeVehicle->vehicleYawsToNextWaypointInMission()) {
            // We current only support gimbal display in this mode
            double gimbalYaw = item->specifiedGimbalYaw();
            if (!qIsNaN(gimbalYaw)) {
                _missionFlightStatus.gimbalYaw = gimbalYaw;
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
973 974 975 976 977
        }

        if (i == 0) {
            // We only process speed and gimbal from Mission Settings item
            continue;
978 979
        }

980 981 982 983 984 985 986 987
        // 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
DonLakeFlyer's avatar
DonLakeFlyer committed
988
        if (simpleItem && _activeVehicle->vtol()) {
989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002
            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;
1003 1004
                }
            }
1005 1006 1007
                break;
            default:
                break;
1008
            }
Don Gagne's avatar
Don Gagne committed
1009 1010
        }

1011
        if (item->specifiesCoordinate()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1012 1013 1014 1015 1016 1017
            // Update vehicle yaw assuming direction to next waypoint
            if (item != lastCoordinateItem) {
                lastVehicleYaw = lastCoordinateItem->exitCoordinate().azimuthTo(item->coordinate());
                lastCoordinateItem->setMissionVehicleYaw(lastVehicleYaw);
            }

1018 1019
            // Keep track of the min/max altitude for all waypoints so we can show altitudes as a percentage

1020
            double absoluteAltitude = item->coordinate().altitude();
1021
            if (item->coordinateHasRelativeAltitude()) {
1022 1023 1024 1025 1026
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1027 1028 1029 1030 1031 1032 1033 1034 1035 1036
            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
1037
                firstCoordinateItem = false;
1038
                if (lastCoordinateItem != _settingsItem || linkBackToHome) {
1039 1040
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1041

1042
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1043 1044 1045
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1046

DonLakeFlyer's avatar
DonLakeFlyer committed
1047
                    _missionFlightStatus.totalDistance += distance;
1048
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1049

DonLakeFlyer's avatar
DonLakeFlyer committed
1050 1051 1052 1053
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
                    if (_activeVehicle->vtol()) {
1054
                        if (vtolInHover) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1055 1056 1057
                            _missionFlightStatus.totalTime += hoverTime;
                            _missionFlightStatus.hoverTime += hoverTime;
                            _missionFlightStatus.hoverDistance += distance;
1058
                        } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1059 1060 1061
                            _missionFlightStatus.totalTime += cruiseTime;
                            _missionFlightStatus.cruiseTime += cruiseTime;
                            _missionFlightStatus.cruiseDistance += distance;
1062 1063
                        }
                    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1064 1065 1066 1067 1068 1069 1070 1071 1072 1073
                        if (_activeVehicle->multiRotor()) {
                            _missionFlightStatus.totalTime += hoverTime;
                            _missionFlightStatus.hoverTime += hoverTime;
                            _missionFlightStatus.hoverDistance += distance;
                        } else {
                            _missionFlightStatus.totalTime += cruiseTime;
                            _missionFlightStatus.cruiseTime += cruiseTime;
                            _missionFlightStatus.cruiseDistance += distance;

                        }
1074
                    }
1075
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1076

1077
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1078 1079 1080
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
                    _missionFlightStatus.totalDistance += distance;
1081
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106

                    double hoverTime = _missionFlightStatus.totalDistance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = _missionFlightStatus.totalDistance / _missionFlightStatus.cruiseSpeed;
                    if (_activeVehicle->vtol()) {
                        if (vtolInHover) {
                            _missionFlightStatus.totalTime += hoverTime;
                            _missionFlightStatus.hoverTime += hoverTime;
                            _missionFlightStatus.hoverDistance += distance;
                        } else {
                            _missionFlightStatus.totalTime += cruiseTime;
                            _missionFlightStatus.cruiseTime += cruiseTime;
                            _missionFlightStatus.cruiseDistance += distance;
                        }
                    } else {
                        if (_activeVehicle->multiRotor()) {
                            _missionFlightStatus.totalTime += hoverTime;
                            _missionFlightStatus.hoverTime += hoverTime;
                            _missionFlightStatus.hoverDistance += distance;
                        } else {
                            _missionFlightStatus.totalTime += cruiseTime;
                            _missionFlightStatus.cruiseTime += cruiseTime;
                            _missionFlightStatus.cruiseDistance += distance;

                        }
                    }
1107
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1108 1109

                item->setMissionFlightStatus(_missionFlightStatus);
1110
            }
1111 1112

            lastCoordinateItem = item;
1113 1114
        }
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1115
    lastCoordinateItem->setMissionVehicleYaw(lastVehicleYaw);
1116 1117


DonLakeFlyer's avatar
DonLakeFlyer committed
1118 1119 1120 1121 1122 1123 1124
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1125

1126 1127
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1128 1129
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1130 1131 1132

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1133
            if (item->coordinateHasRelativeAltitude()) {
1134 1135 1136 1137 1138 1139
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1140
            }
1141 1142 1143 1144
        }
    }
}

1145 1146 1147
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1148 1149 1150 1151 1152 1153
    // 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));

1154 1155
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1156 1157 1158
    }
}

1159 1160 1161
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1162
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1163 1164 1165

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

1166 1167
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1168 1169 1170 1171 1172

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1173
        } else if (item->isSimpleItem()) {
1174 1175 1176 1177 1178
            currentParentItem->childItems()->append(item);
        }
    }
}

1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195
void MissionController::_setPlannedHomePositionFromFirstCoordinate(void)
{
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

    // Set the planned home position to be a deltae from first coordinate
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

        if (item->specifiesCoordinate()) {
            _settingsItem->setCoordinate(item->coordinate().atDistanceAndAzimuth(30, 0));
        }
    }
}


1196 1197
void MissionController::_recalcAll(void)
{
1198
    _setPlannedHomePositionFromFirstCoordinate();
1199
    _recalcSequence();
1200 1201 1202 1203
    _recalcChildItems();
    _recalcWaypointLines();
}

1204
/// Initializes a new set of mission items
1205
void MissionController::_initAllVisualItems(void)
1206
{
1207 1208
    // Setup home position at index 0

1209 1210 1211
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1212 1213
        return;
    }
1214
    _settingsItem->setIsCurrentItem(true);
1215

1216 1217
    if (!_editMode && _activeVehicle) {
        _settingsItem->setCoordinate(_activeVehicle->homePosition());
1218
    }
1219

1220
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
1221

1222 1223 1224 1225
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1226

1227
    _recalcAll();
1228

1229
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1230 1231 1232
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1233
    emit containsItemsChanged(containsItems());
1234

1235
    _visualItems->setDirty(false);
1236 1237
}

1238
void MissionController::_deinitAllVisualItems(void)
1239
{
1240 1241
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1242 1243
    }

1244
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1245
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1246 1247
}

1248
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1249
{
1250 1251
    _visualItems->setDirty(false);

1252
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1253 1254
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1255 1256
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1257
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1258

1259 1260 1261 1262 1263 1264 1265 1266
    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";
        }
1267 1268
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1269
        if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1270
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcMissionFlightStatus);
1271 1272 1273
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1274
    }
1275 1276
}

1277
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1278
{
1279 1280
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1281 1282
}

1283
void MissionController::_itemCommandChanged(void)
1284
{
1285 1286
    _recalcChildItems();
    _recalcWaypointLines();
1287 1288
}

1289
void MissionController::_activeVehicleBeingRemoved(void)
1290
{
1291
    qCDebug(MissionControllerLog) << "MissionController::_activeVehicleBeingRemoved";
1292

1293
    MissionManager* missionManager = _activeVehicle->missionManager();
1294 1295 1296 1297

    disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailableFromVehicle);
    disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
    disconnect(missionManager, &MissionManager::currentItemChanged,         this, &MissionController::_currentMissionItemChanged);
1298
    disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
Don Gagne's avatar
Don Gagne committed
1299

Don Gagne's avatar
Don Gagne committed
1300 1301
    // 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
1302 1303
    removeAll();
}
Don Gagne's avatar
Don Gagne committed
1304

1305 1306 1307 1308 1309
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();
1310

1311 1312 1313 1314 1315 1316
    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::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);
DonLakeFlyer's avatar
DonLakeFlyer committed
1317 1318
    connect(_activeVehicle, &Vehicle::defaultCruiseSpeedChanged,        this, &MissionController::_recalcMissionFlightStatus);
    connect(_activeVehicle, &Vehicle::defaultHoverSpeedChanged,         this, &MissionController::_recalcMissionFlightStatus);
1319
    connect(_activeVehicle, &Vehicle::vehicleTypeChanged,               this, &MissionController::complexMissionItemNamesChanged);
1320

1321
    if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
1322 1323 1324
        // 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();
1325
    }
1326

1327
    _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
1328 1329

    emit complexMissionItemNamesChanged();
1330 1331 1332 1333
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
1334 1335
    if (_visualItems) {
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1336
        if (settingsItem) {
1337
            settingsItem->setCoordinate(homePosition);
1338
        } else {
1339
            qWarning() << "First item is not MissionSettingsItem";
1340
        }
1341
    }
1342 1343
}

1344 1345
void MissionController::_setMissionMaxTelemetry(double missionMaxTelemetry)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1346 1347 1348
    if (!qFuzzyCompare(_missionFlightStatus.maxTelemetryDistance, missionMaxTelemetry)) {
        _missionFlightStatus.maxTelemetryDistance = missionMaxTelemetry;
        emit missionMaxTelemetryChanged(missionMaxTelemetry);
1349 1350 1351 1352
    }
}

void MissionController::_setMissionDistance(double missionDistance)
1353
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1354 1355 1356
    if (!qFuzzyCompare(_missionFlightStatus.totalDistance, missionDistance)) {
        _missionFlightStatus.totalDistance = missionDistance;
        emit missionDistanceChanged(missionDistance);
1357 1358 1359
    }
}

1360
void MissionController::_setMissionTime(double missionTime)
1361
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1362 1363
    if (!qFuzzyCompare(_missionFlightStatus.totalTime, missionTime)) {
        _missionFlightStatus.totalTime = missionTime;
1364 1365 1366 1367 1368 1369
        emit missionTimeChanged();
    }
}

void MissionController::_setMissionHoverTime(double missionHoverTime)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1370 1371
    if (!qFuzzyCompare(_missionFlightStatus.hoverTime, missionHoverTime)) {
        _missionFlightStatus.hoverTime = missionHoverTime;
1372
        emit missionHoverTimeChanged();
1373 1374 1375
    }
}

1376
void MissionController::_setMissionHoverDistance(double missionHoverDistance)
1377
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1378 1379 1380
    if (!qFuzzyCompare(_missionFlightStatus.hoverDistance, missionHoverDistance)) {
        _missionFlightStatus.hoverDistance = missionHoverDistance;
        emit missionHoverDistanceChanged(missionHoverDistance);
1381 1382 1383
    }
}

1384
void MissionController::_setMissionCruiseTime(double missionCruiseTime)
1385
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1386 1387
    if (!qFuzzyCompare(_missionFlightStatus.cruiseTime, missionCruiseTime)) {
        _missionFlightStatus.cruiseTime = missionCruiseTime;
1388 1389 1390 1391 1392 1393
        emit missionCruiseTimeChanged();
    }
}

void MissionController::_setMissionCruiseDistance(double missionCruiseDistance)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1394 1395 1396
    if (!qFuzzyCompare(_missionFlightStatus.cruiseDistance, missionCruiseDistance)) {
        _missionFlightStatus.cruiseDistance = missionCruiseDistance;
        emit missionCruiseDistanceChanged(missionCruiseDistance);
1397 1398 1399
    }
}

1400
void MissionController::_inProgressChanged(bool inProgress)
1401
{
1402
    emit syncInProgressChanged(inProgress);
1403
}
1404

1405
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
1406
{
1407 1408 1409
    bool        found = false;
    double      foundAltitude;
    MAV_FRAME   foundFrame;
1410

1411 1412 1413 1414 1415 1416
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1419 1420 1421
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1422
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
1423 1424 1425
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1426
                    break;
1427 1428
                }
            }
1429 1430 1431
        }
    }

1432
    if (found) {
1433 1434
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1435 1436 1437
    }

    return found;
1438
}
1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451

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

1452 1453
/// Add the Mission Settings complex item to the front of the items
void MissionController::_addMissionSettings(Vehicle* vehicle, QmlObjectListModel* visualItems, bool addToCenter)
1454
{
1455
    MissionSettingsItem* settingsItem = new MissionSettingsItem(vehicle, visualItems);
1456

1457
    visualItems->insert(0, settingsItem);
1458

1459 1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483
    if (addToCenter) {
        if (visualItems->count() > 1) {
            double north = 0.0;
            double south = 0.0;
            double east  = 0.0;
            double west  = 0.0;
            bool firstCoordSet = false;

            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;
                    }
1484 1485
                }
            }
1486

1487 1488 1489
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1490
        }
1491 1492
    } else {
        settingsItem->setCoordinate(vehicle->homePosition());
1493 1494
    }
}
1495 1496 1497 1498

void MissionController::_currentMissionItemChanged(int sequenceNumber)
{
    if (!_editMode) {
1499 1500
        bool prevMissionInProgress = missionInProgress();

1501 1502 1503 1504
        if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            sequenceNumber++;
        }

1505 1506
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1507 1508
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1509 1510 1511 1512

        if (prevMissionInProgress != missionInProgress()) {
            emit missionInProgressChanged();
        }
1513 1514
    }
}
1515

1516
bool MissionController::syncInProgress(void) const
1517
{
1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530
    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);
1531
    }
1532
}
1533

1534 1535
QString MissionController::fileExtension(void) const
{
1536
    return AppSettings::missionFileExtension;
1537
}
1538

1539 1540 1541 1542 1543 1544 1545 1546
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1547
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559 1560 1561
        if (settingsItem && settingsItem->scanForMissionSettings(visualItems, scanIndex, vehicle)) {
            continue;
        }

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

        scanIndex++;
    }
}
1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577

void MissionController::_updateContainsItems(void)
{
    emit containsItemsChanged(containsItems());
}

bool MissionController::containsItems(void) const
{
    return _visualItems ? _visualItems->count() > 1 : false;
}

void MissionController::removeAllFromVehicle(void)
{
    _missionItemsRequested = true;
    _activeVehicle->missionManager()->removeAll();
}
1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589

QStringList MissionController::complexMissionItemNames(void) const
{
    QStringList complexItems;

    complexItems.append(_surveyMissionItemName);
    if (_activeVehicle->fixedWing()) {
        complexItems.append(_fwLandingMissionItemName);
    }

    return complexItems;
}
1590 1591 1592 1593 1594

bool MissionController::missionInProgress(void) const
{
    return _visualItems && _visualItems->count() > 1 && (!_visualItems->value<VisualMissionItem*>(0)->isCurrentItem() && !_visualItems->value<VisualMissionItem*>(1)->isCurrentItem());
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1595 1596 1597 1598 1599 1600 1601 1602 1603 1604 1605 1606 1607 1608 1609 1610 1611 1612 1613 1614 1615 1616

void MissionController::save(void)
{
    // Save to file if the mission is named
    QString missionFullPath = _settingsItem->missionFullPath()->rawValue().toString();
    if (!missionFullPath.isEmpty()) {
        saveToFile(missionFullPath);
    }

    // Send to vehicle if we are connected
    if (!_activeVehicle->isOfflineEditingVehicle()) {
        sendToVehicle();
    }

    _settingsItem->setExistingMission(_visualItems->count() > 1 && !missionFullPath.isEmpty());
}

void MissionController::clearMission(void)
{
    removeAll();
    save();
}