MissionController.cc 63.7 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
    , _missionItemsRequested(false)
56 57
    , _surveyMissionItemName(tr("Survey"))
    , _fwLandingMissionItemName(tr("Fixed Wing Landing"))
58
    , _appSettings(qgcApp()->toolbox()->settingsManager()->appSettings())
59
{
60
    _resetMissionFlightStatus();
61 62 63 64
}

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

66 67
}

68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101
void MissionController::_resetMissionFlightStatus(void)
{
    _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 ? _activeVehicle->defaultCruiseSpeed() : std::numeric_limits<double>::quiet_NaN();
    _missionFlightStatus.hoverSpeed =           _activeVehicle ? _activeVehicle->defaultHoverSpeed() : std::numeric_limits<double>::quiet_NaN();
    _missionFlightStatus.vehicleSpeed =         _activeVehicle ? (_activeVehicle->multiRotor() || _activeVehicle->vtol() ? _missionFlightStatus.hoverSpeed : _missionFlightStatus.cruiseSpeed) : std::numeric_limits<double>::quiet_NaN();
    _missionFlightStatus.gimbalYaw =            std::numeric_limits<double>::quiet_NaN();

    // Battery information

    _missionFlightStatus.mAhBattery =           0;
    _missionFlightStatus.hoverAmps =            0;
    _missionFlightStatus.cruiseAmps =           0;
    _missionFlightStatus.ampMinutesAvailable =  0;
    _missionFlightStatus.hoverAmpsTotal =       0;
    _missionFlightStatus.cruiseAmpsTotal =      0;
    _missionFlightStatus.batteryChangePoint =   -1;
    _missionFlightStatus.batteriesRequired =    -1;

    if (_activeVehicle) {
        _activeVehicle->firmwarePlugin()->batteryConsumptionData(_activeVehicle, _missionFlightStatus.mAhBattery, _missionFlightStatus.hoverAmps, _missionFlightStatus.cruiseAmps);
        if (_missionFlightStatus.mAhBattery != 0) {
            double batteryPercentRemainingAnnounce = qgcApp()->toolbox()->settingsManager()->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toDouble();
            _missionFlightStatus.ampMinutesAvailable = (double)_missionFlightStatus.mAhBattery / 1000.0 * 60.0 * ((100.0 - batteryPercentRemainingAnnounce) / 100.0);
        }
    }
}

102 103
void MissionController::start(bool editMode)
{
104 105
    qCDebug(MissionControllerLog) << "start editMode" << editMode;

106
    PlanElementController::start(editMode);
107 108 109 110 111 112
    _init();
}

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

114 115 116 117 118 119
    PlanElementController::startStaticActiveVehicle(vehicle);
    _init();
}

void MissionController::_init(void)
{
120
    // We start with an empty mission
121
    _visualItems = new QmlObjectListModel(this);
122
    _addMissionSettings(_activeVehicle, _visualItems, false /* addToCenter */);
123
    _initAllVisualItems();
124 125
}

126
// Called when new mission items have completed downloading from Vehicle
127
void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllRequested)
128
{
129 130
    qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle";

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

139 140
        QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
        const QList<MissionItem*>& newMissionItems = _activeVehicle->missionManager()->missionItems();
141 142 143 144 145 146
        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 */);
147
            MissionSettingsItem* settingsItem = newControllerMissionItems->value<MissionSettingsItem*>(0);
148 149 150 151 152 153 154
            if (!settingsItem) {
                qWarning() << "First item is not settings item";
                return;
            }
            settingsItem->setCoordinate(newMissionItems[0]->coordinate());
            i = 1;
        }
155

156 157
        for (; i<newMissionItems.count(); i++) {
            const MissionItem* missionItem = newMissionItems[i];
158 159 160 161
            newControllerMissionItems->append(new SimpleMissionItem(_activeVehicle, *missionItem, this));
        }

        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
162
        _visualItems->deleteLater();
163
        _settingsItem = NULL;
164 165 166
        _visualItems = newControllerMissionItems;

        if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
167
            _addMissionSettings(_activeVehicle, _visualItems, _editMode && _visualItems->count() > 0 /* addToCenter */);
168 169
        }

170
        _missionItemsRequested = false;
171

172
        if (_editMode) {
173
            MissionController::_scanForAdditionalSettings(_visualItems, _activeVehicle);
174
        }
175

176
        _initAllVisualItems();
177
        emit newItemsFromVehicle();
178 179 180
    }
}

181
void MissionController::loadFromVehicle(void)
182
{
183
    Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
184

185 186 187 188 189 190
    if (activeVehicle) {
        _missionItemsRequested = true;
        activeVehicle->missionManager()->requestMissionItems();
    }
}

191
void MissionController::sendToVehicle(void)
192
{
Don Gagne's avatar
Don Gagne committed
193 194 195 196
    sendItemsToVehicle(_activeVehicle, _visualItems);
    _visualItems->setDirty(false);
}

197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217
/// 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
218
    MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
219 220 221 222 223 224 225
    if (settingsItem) {
        endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
    }

    return endActionSet;
}

Don Gagne's avatar
Don Gagne committed
226 227 228
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
229
        QList<MissionItem*> rgMissionItems;
230

231
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
232

233
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
234

235 236
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
237
        }
238 239
    }
}
240

241 242 243 244 245 246
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
247 248
        VisualMissionItem* lastItem = _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1);
        return lastItem->lastSequenceNumber() + 1;
249 250 251
    }
}

252
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
253
{
254
    int sequenceNumber = _nextSequenceNumber();
255
    SimpleMissionItem * newItem = new SimpleMissionItem(_activeVehicle, this);
256
    newItem->setSequenceNumber(sequenceNumber);
257
    newItem->setCoordinate(coordinate);
258 259 260
    newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
    _initVisualItem(newItem);
    if (_visualItems->count() == 1) {
261 262
        newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
    }
263
    newItem->setDefaultsForCommand();
Don Gagne's avatar
Don Gagne committed
264
    if ((MAV_CMD)newItem->command() == MAV_CMD_NAV_WAYPOINT) {
265 266
        double      prevAltitude;
        MAV_FRAME   prevFrame;
267

268 269 270
        if (_findPreviousAltitude(i, &prevAltitude, &prevFrame)) {
            newItem->missionItem().setFrame(prevFrame);
            newItem->missionItem().setParam7(prevAltitude);
271
        }
272
    }
273
    _visualItems->insert(i, newItem);
274 275 276

    _recalcAll();

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

280
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
281
{
282 283
    ComplexMissionItem* newItem;

284
    int sequenceNumber = _nextSequenceNumber();
285 286
    if (itemName == _surveyMissionItemName) {
        newItem = new SurveyMissionItem(_activeVehicle, _visualItems);
287
        newItem->setCoordinate(mapCenterCoordinate);
288
    } else if (itemName == _fwLandingMissionItemName) {
289
        newItem = new FixedWingLandingComplexItem(_activeVehicle, _visualItems);
290 291 292 293
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }
294
    newItem->setSequenceNumber(sequenceNumber);
295
    _initVisualItem(newItem);
296

297
    _visualItems->insert(i, newItem);
298 299 300

    _recalcAll();

301
    return newItem->sequenceNumber();
302 303
}

304 305
void MissionController::removeMissionItem(int index)
{
306
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
307

308
    _deinitVisualItem(item);
309
    item->deleteLater();
310 311

    _recalcAll();
312
    _visualItems->setDirty(true);
313 314
}

315
void MissionController::removeAll(void)
316
{
317 318
    if (_visualItems) {
        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
319
        _visualItems->deleteLater();
320
        _settingsItem = NULL;
321
        _visualItems = new QmlObjectListModel(this);
322
        _addMissionSettings(_activeVehicle, _visualItems, false /* addToCenter */);
323
        _initAllVisualItems();
Don Gagne's avatar
Don Gagne committed
324
        _visualItems->setDirty(true);
325
    }
326
}
327

328
bool MissionController::_loadJsonMissionFile(Vehicle* vehicle, const QByteArray& bytes, QmlObjectListModel* visualItems, QString& errorString)
329 330 331 332 333 334 335 336 337 338
{
    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
339 340 341
    // 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;
342 343
    }

Don Gagne's avatar
Don Gagne committed
344 345 346 347 348 349 350
    int fileVersion;
    if (!JsonHelper::validateQGCJsonFile(json,
                                         _jsonFileTypeValue,    // expected file type
                                         1,                     // minimum supported version
                                         2,                     // maximum supported version
                                         fileVersion,
                                         errorString)) {
351 352
        return false;
    }
353

Don Gagne's avatar
Don Gagne committed
354
    if (fileVersion == 1) {
355
        return _loadJsonMissionFileV1(vehicle, json, visualItems, errorString);
Don Gagne's avatar
Don Gagne committed
356
    } else {
357
        return _loadJsonMissionFileV2(vehicle, json, visualItems, errorString);
Don Gagne's avatar
Don Gagne committed
358 359 360
    }
}

361
bool MissionController::_loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
362 363 364 365 366 367 368 369 370
{
    // 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)) {
371 372 373
        return false;
    }

374
    // Read complex items
375
    QList<SurveyMissionItem*> surveyItems;
376 377 378 379
    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];
380

381 382 383 384 385
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

Don Gagne's avatar
Don Gagne committed
386
        SurveyMissionItem* item = new SurveyMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
387 388
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
389
            surveyItems.append(item);
390 391
        } else {
            return false;
392
        }
393
    }
394

395 396 397 398 399
    // 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
400
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
401

402
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
403 404 405 406
    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
407 408
        if (nextComplexItemIndex < surveyItems.count()) {
            SurveyMissionItem* complexItem = surveyItems[nextComplexItemIndex];
409 410 411 412 413 414 415 416 417 418 419 420 421 422

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

423 424 425 426 427
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
428
            const QJsonObject itemObject = itemValue.toObject();
Don Gagne's avatar
Don Gagne committed
429
            SimpleMissionItem* item = new SimpleMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
430
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
431
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
432
                nextSequenceNumber = item->lastSequenceNumber() + 1;
433
                visualItems->append(item);
434 435 436 437
            } else {
                return false;
            }
        }
438
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
439 440

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

Don Gagne's avatar
Don Gagne committed
443
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
444
            MissionSettingsItem* settingsItem = new MissionSettingsItem(vehicle, visualItems);
445 446 447
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
448 449 450 451
        } else {
            return false;
        }
    } else {
452
        _addMissionSettings(vehicle, visualItems, true /* addToCenter */);
453 454 455 456 457
    }

    return true;
}

458
bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
459 460 461 462 463 464
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
465 466 467
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
468 469 470 471 472 473 474
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

475
    // Mission Settings
Don Gagne's avatar
Don Gagne committed
476
    QGeoCoordinate homeCoordinate;
477
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
Don Gagne's avatar
Don Gagne committed
478 479 480
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
Don Gagne's avatar
Don Gagne committed
481
    if (json.contains(_jsonVehicleTypeKey) && vehicle->isOfflineEditingVehicle()) {
482
        appSettings->offlineEditingVehicleType()->setRawValue(json[_jsonVehicleTypeKey].toDouble());
483 484
    }
    if (json.contains(_jsonCruiseSpeedKey)) {
485
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
486 487
    }
    if (json.contains(_jsonHoverSpeedKey)) {
488
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
489 490
    }

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

            if (item->load(stream)) {
625
                visualItems->append(item);
626 627 628 629 630 631
            } else {
                errorString = QStringLiteral("The mission file is corrupted.");
                return false;
            }
        }
    } else {
632
        errorString = QStringLiteral("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
633 634 635
        return false;
    }

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

639 640 641 642 643
        // 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
644 645
            }
        }
646 647 648
    }

    return true;
649 650
}

651
void MissionController::loadFromFile(const QString& filename)
652
{
Don Gagne's avatar
Don Gagne committed
653 654
    QmlObjectListModel* newVisualItems = NULL;

655
    if (!loadItemsFromFile(_activeVehicle, filename, &newVisualItems)) {
Don Gagne's avatar
Don Gagne committed
656 657 658 659 660 661
        return;
    }

    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
662
        _settingsItem = NULL;
Don Gagne's avatar
Don Gagne committed
663 664 665 666 667
    }

    _visualItems = newVisualItems;

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

671
    MissionController::_scanForAdditionalSettings(_visualItems, _activeVehicle);
672

Don Gagne's avatar
Don Gagne committed
673 674 675
    _initAllVisualItems();
}

676
bool MissionController::loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems)
Don Gagne's avatar
Don Gagne committed
677 678 679
{
    *visualItems = NULL;

680 681 682
    QString errorString;

    if (filename.isEmpty()) {
Don Gagne's avatar
Don Gagne committed
683
        return false;
684 685
    }

Don Gagne's avatar
Don Gagne committed
686
    *visualItems = new QmlObjectListModel();
687 688 689 690

    QFile file(filename);

    if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
Don Gagne's avatar
Don Gagne committed
691
        errorString = file.errorString() + QStringLiteral(" ") + filename;
692
    } else {
693 694
        QByteArray  bytes = file.readAll();
        QTextStream stream(&bytes);
695

696 697 698
        QString firstLine = stream.readLine();
        if (firstLine.contains(QRegExp("QGC.*WPL"))) {
            stream.seek(0);
Don Gagne's avatar
Don Gagne committed
699
            _loadTextMissionFile(vehicle, stream, *visualItems, errorString);
700
        } else {
701
            _loadJsonMissionFile(vehicle, bytes, *visualItems, errorString);
702 703
        }
    }
704

705
    if (!errorString.isEmpty()) {
Don Gagne's avatar
Don Gagne committed
706
        (*visualItems)->deleteLater();
707

708
        qgcApp()->showMessage(errorString);
Don Gagne's avatar
Don Gagne committed
709
        return false;
710 711
    }

Don Gagne's avatar
Don Gagne committed
712
    return true;
713 714
}

715
void MissionController::saveToFile(const QString& filename)
716
{
717 718 719
    if (filename.isEmpty()) {
        return;
    }
720

721
    QString missionFilename = filename;
722
    if (!QFileInfo(filename).fileName().contains(".")) {
723
        missionFilename += QString(".%1").arg(AppSettings::missionFileExtension);
724 725
    }

726
    QFile file(missionFilename);
727

728
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
729
        qgcApp()->showMessage(tr("Mission save %1 : %2").arg(filename).arg(file.errorString()));
730
    } else {
731
        QJsonObject missionFileObject;      // top level json object
732

Don Gagne's avatar
Don Gagne committed
733
        missionFileObject[JsonHelper::jsonVersionKey] =         _missionFileVersion;
734
        missionFileObject[JsonHelper::jsonGroundStationKey] =   JsonHelper::jsonGroundStationValue;
735

736
        // Mission settings
737

738
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
739
        if (!settingsItem) {
740
            qWarning() << "First item is not MissionSettingsItem";
741 742
            return;
        }
Don Gagne's avatar
Don Gagne committed
743
        QJsonValue coordinateValue;
744
        JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
Don Gagne's avatar
Don Gagne committed
745
        missionFileObject[_jsonPlannedHomePositionKey] = coordinateValue;
746 747
        missionFileObject[_jsonFirmwareTypeKey] = _activeVehicle->firmwareType();
        missionFileObject[_jsonVehicleTypeKey] = _activeVehicle->vehicleType();
DonLakeFlyer's avatar
DonLakeFlyer committed
748 749
        missionFileObject[_jsonCruiseSpeedKey] = _activeVehicle->defaultCruiseSpeed();
        missionFileObject[_jsonHoverSpeedKey] = _activeVehicle->defaultHoverSpeed();
750

751
        // Save the visual items
752

DonLakeFlyer's avatar
DonLakeFlyer committed
753
        QJsonArray rgJsonMissionItems;
754
        for (int i=0; i<_visualItems->count(); i++) {
755
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772

            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();
            }
773
        }
774 775

        missionFileObject[_jsonItemsKey] = rgJsonMissionItems;
776 777

        QJsonDocument saveDoc(missionFileObject);
778
        file.write(saveDoc.toJson());
779 780
    }

781 782 783 784
    // If we are connected to a real vehicle, don't clear dirty bit on saving to file since vehicle is still out of date
    if (_activeVehicle->isOfflineEditingVehicle()) {
        _visualItems->setDirty(false);
    }
785 786
}

787
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
788
{
Don Gagne's avatar
Don Gagne committed
789
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
790
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
791 792 793 794
    bool            distanceOk =    false;

    // Convert to fixed altitudes

795
    distanceOk = true;
796
    if (currentItem->coordinateHasRelativeAltitude()) {
797 798
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
799
    if (prevItem->exitCoordinateHasRelativeAltitude()) {
800
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
801 802 803
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
804 805 806
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
807
    } else {
Don Gagne's avatar
Don Gagne committed
808
        *altDifference = 0.0;
809
        *azimuth = 0.0;
810
        *distance = 0.0;
811 812 813
    }
}

814
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
815 816 817 818 819 820 821
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

822
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
823 824
}

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

830
    bool showHomePosition = _settingsItem->coordinate().isValid();
831

832
    qCDebug(MissionControllerLog) << "_recalcWaypointLines showHomePosition" << showHomePosition;
833

Nate Weibley's avatar
Nate Weibley committed
834 835
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
836 837 838 839 840 841 842
    _waypointLines.clear();

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


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

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

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

    emit waypointLinesChanged();
}

899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928
void MissionController::_updateBatteryInfo(int waypointIndex)
{
    if (_missionFlightStatus.mAhBattery != 0) {
        _missionFlightStatus.hoverAmpsTotal = (_missionFlightStatus.hoverTime / 60.0) * _missionFlightStatus.hoverAmps;
        _missionFlightStatus.cruiseAmpsTotal = (_missionFlightStatus.cruiseTime / 60.0) * _missionFlightStatus.cruiseAmps;
        _missionFlightStatus.batteriesRequired = ceil((_missionFlightStatus.hoverAmpsTotal + _missionFlightStatus.cruiseAmpsTotal) / _missionFlightStatus.ampMinutesAvailable);
        if (_missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
            _missionFlightStatus.batteryChangePoint = waypointIndex - 1;
        }
    }
}

void MissionController::_addHoverTime(double hoverTime, double hoverDistance, int waypointIndex)
{
    _missionFlightStatus.totalTime += hoverTime;
    _missionFlightStatus.hoverTime += hoverTime;
    _missionFlightStatus.hoverDistance += hoverDistance;
    _missionFlightStatus.totalDistance += hoverDistance;
    _updateBatteryInfo(waypointIndex);
}

void MissionController::_addCruiseTime(double cruiseTime, double cruiseDistance, int waypointIndex)
{
    _missionFlightStatus.totalTime += cruiseTime;
    _missionFlightStatus.cruiseTime += cruiseTime;
    _missionFlightStatus.cruiseDistance += cruiseDistance;
    _missionFlightStatus.totalDistance += cruiseDistance;
    _updateBatteryInfo(waypointIndex);
}

DonLakeFlyer's avatar
DonLakeFlyer committed
929
void MissionController::_recalcMissionFlightStatus()
930
{
931
    if (!_visualItems->count()) {
932
        return;
933
    }
934 935 936 937

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

938
    bool showHomePosition = _settingsItem->coordinate().isValid();
939

DonLakeFlyer's avatar
DonLakeFlyer committed
940
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
941

942 943 944
    // 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.
945

946
    // No values for first item
947
    lastCoordinateItem->setAltDifference(0.0);
948
    lastCoordinateItem->setAzimuth(0.0);
949
    lastCoordinateItem->setDistance(0.0);
950

951 952
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
953 954
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
955

DonLakeFlyer's avatar
DonLakeFlyer committed
956 957
    double lastVehicleYaw = 0;

958
    _resetMissionFlightStatus();
959

DonLakeFlyer's avatar
DonLakeFlyer committed
960
    bool vtolInHover = true;
Don Gagne's avatar
Don Gagne committed
961
    bool linkBackToHome = false;
962

DonLakeFlyer's avatar
DonLakeFlyer committed
963
    for (int i=0; i<_visualItems->count(); i++) {
964
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
965 966 967
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

968 969
        // Assume the worst
        item->setAzimuth(0.0);
970
        item->setDistance(0.0);
971

DonLakeFlyer's avatar
DonLakeFlyer committed
972 973 974 975 976 977 978 979
        // 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;
980
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
981
                    _missionFlightStatus.cruiseSpeed = newSpeed;
982
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
983 984
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
985
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
986 987 988 989
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
990 991 992 993 994 995
        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
996 997 998 999 1000
        }

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

1003 1004 1005 1006 1007 1008 1009 1010
        // 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
1011
        if (simpleItem && _activeVehicle->vtol()) {
1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025
            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;
1026 1027
                }
            }
1028 1029 1030
                break;
            default:
                break;
1031
            }
Don Gagne's avatar
Don Gagne committed
1032 1033
        }

1034
        if (item->specifiesCoordinate()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1035 1036 1037 1038 1039 1040
            // Update vehicle yaw assuming direction to next waypoint
            if (item != lastCoordinateItem) {
                lastVehicleYaw = lastCoordinateItem->exitCoordinate().azimuthTo(item->coordinate());
                lastCoordinateItem->setMissionVehicleYaw(lastVehicleYaw);
            }

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

1043
            double absoluteAltitude = item->coordinate().altitude();
1044
            if (item->coordinateHasRelativeAltitude()) {
1045 1046 1047 1048 1049
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1050 1051 1052 1053 1054 1055 1056 1057 1058 1059
            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
1060
                firstCoordinateItem = false;
1061
                if (lastCoordinateItem != _settingsItem || linkBackToHome) {
1062 1063
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1064

1065
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1066 1067 1068
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1069

1070
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1071

DonLakeFlyer's avatar
DonLakeFlyer committed
1072 1073 1074 1075
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
                    if (_activeVehicle->vtol()) {
1076
                        if (vtolInHover) {
1077
                            _addHoverTime(hoverTime, distance, item->sequenceNumber());
1078
                        } else {
1079
                            _addCruiseTime(cruiseTime, distance, item->sequenceNumber());
1080 1081
                        }
                    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1082
                        if (_activeVehicle->multiRotor()) {
1083
                            _addHoverTime(hoverTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1084
                        } else {
1085
                            _addCruiseTime(cruiseTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1086
                        }
1087
                    }
1088
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1089

1090
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1091 1092
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1093
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1094

1095 1096
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
DonLakeFlyer's avatar
DonLakeFlyer committed
1097 1098
                    if (_activeVehicle->vtol()) {
                        if (vtolInHover) {
1099
                            _addHoverTime(hoverTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1100
                        } else {
1101
                            _addCruiseTime(cruiseTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1102 1103 1104
                        }
                    } else {
                        if (_activeVehicle->multiRotor()) {
1105
                            _addHoverTime(hoverTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1106
                        } else {
1107
                            _addCruiseTime(cruiseTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1108 1109
                        }
                    }
1110
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1111 1112

                item->setMissionFlightStatus(_missionFlightStatus);
1113
            }
1114 1115

            lastCoordinateItem = item;
1116 1117
        }
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1118
    lastCoordinateItem->setMissionVehicleYaw(lastVehicleYaw);
1119

1120 1121 1122
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1123

DonLakeFlyer's avatar
DonLakeFlyer committed
1124 1125 1126 1127 1128 1129 1130
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1131 1132
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1133

1134 1135
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1136 1137
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1138 1139 1140

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1141
            if (item->coordinateHasRelativeAltitude()) {
1142 1143 1144 1145 1146 1147
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1148
            }
1149 1150 1151 1152
        }
    }
}

1153 1154 1155
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1156 1157 1158 1159 1160 1161
    // 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));

1162 1163
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1164 1165 1166
    }
}

1167 1168 1169
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1170
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1171 1172 1173

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

1174 1175
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1176 1177 1178 1179 1180

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1181
        } else if (item->isSimpleItem()) {
1182 1183 1184 1185 1186
            currentParentItem->childItems()->append(item);
        }
    }
}

1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203
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));
        }
    }
}


1204 1205
void MissionController::_recalcAll(void)
{
1206 1207 1208
    if (_editMode) {
        _setPlannedHomePositionFromFirstCoordinate();
    }
1209
    _recalcSequence();
1210 1211 1212 1213
    _recalcChildItems();
    _recalcWaypointLines();
}

1214
/// Initializes a new set of mission items
1215
void MissionController::_initAllVisualItems(void)
1216
{
1217 1218
    // Setup home position at index 0

1219 1220 1221
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1222 1223
        return;
    }
1224
    _settingsItem->setIsCurrentItem(true);
1225

1226 1227
    if (!_editMode && _activeVehicle) {
        _settingsItem->setCoordinate(_activeVehicle->homePosition());
1228
    }
1229

1230
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
1231
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);
1232

1233 1234 1235 1236
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1237

1238
    _recalcAll();
1239

1240
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1241 1242 1243
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1244
    emit containsItemsChanged(containsItems());
1245
    emit plannedHomePositionChanged(plannedHomePosition());
1246

1247
    _visualItems->setDirty(false);
1248 1249
}

1250
void MissionController::_deinitAllVisualItems(void)
1251
{
1252 1253 1254
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1255 1256
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1257 1258
    }

1259
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1260
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1261 1262
}

1263
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1264
{
1265 1266
    _visualItems->setDirty(false);

1267
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1268 1269
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1270 1271
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1272
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1273

1274 1275 1276 1277 1278 1279 1280 1281
    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";
        }
1282 1283
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1284
        if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1285
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcMissionFlightStatus);
1286 1287 1288
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1289
    }
1290 1291
}

1292
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1293
{
1294 1295
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1296 1297
}

1298
void MissionController::_itemCommandChanged(void)
1299
{
1300 1301
    _recalcChildItems();
    _recalcWaypointLines();
1302 1303
}

1304
void MissionController::_activeVehicleBeingRemoved(void)
1305
{
1306
    qCDebug(MissionControllerLog) << "MissionController::_activeVehicleBeingRemoved";
1307

1308
    MissionManager* missionManager = _activeVehicle->missionManager();
1309 1310 1311 1312

    disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailableFromVehicle);
    disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
    disconnect(missionManager, &MissionManager::currentItemChanged,         this, &MissionController::_currentMissionItemChanged);
1313 1314
    disconnect(missionManager, &MissionManager::lastCurrentItemChanged,     this, &MissionController::resumeMissionItemChanged);
    disconnect(missionManager, &MissionManager::resumeMissionReady,         this, &MissionController::resumeMissionReady);
1315
    disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
Don Gagne's avatar
Don Gagne committed
1316

Don Gagne's avatar
Don Gagne committed
1317 1318
    // 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
1319 1320
    removeAll();
}
Don Gagne's avatar
Don Gagne committed
1321

1322 1323 1324 1325 1326
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();
1327

1328 1329 1330 1331 1332
    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);
1333 1334
    connect(missionManager, &MissionManager::lastCurrentItemChanged,    this, &MissionController::resumeMissionItemChanged);
    connect(missionManager, &MissionManager::resumeMissionReady,        this, &MissionController::resumeMissionReady);
1335
    connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);
DonLakeFlyer's avatar
DonLakeFlyer committed
1336 1337
    connect(_activeVehicle, &Vehicle::defaultCruiseSpeedChanged,        this, &MissionController::_recalcMissionFlightStatus);
    connect(_activeVehicle, &Vehicle::defaultHoverSpeedChanged,         this, &MissionController::_recalcMissionFlightStatus);
1338
    connect(_activeVehicle, &Vehicle::vehicleTypeChanged,               this, &MissionController::complexMissionItemNamesChanged);
1339

1340
    if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
1341 1342 1343
        // 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();
1344
    }
1345

1346
    _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
1347 1348

    emit complexMissionItemNamesChanged();
1349
    emit resumeMissionItemChanged();
1350 1351 1352 1353
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
1354 1355
    if (_visualItems) {
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1356
        if (settingsItem) {
1357
            settingsItem->setCoordinate(homePosition);
1358
        } else {
1359
            qWarning() << "First item is not MissionSettingsItem";
1360
        }
1361
    }
1362 1363 1364
}

void MissionController::_inProgressChanged(bool inProgress)
1365
{
1366
    emit syncInProgressChanged(inProgress);
1367
}
1368

1369
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
1370
{
1371 1372 1373
    bool        found = false;
    double      foundAltitude;
    MAV_FRAME   foundFrame;
1374

1375 1376 1377 1378 1379 1380
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1383 1384 1385
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1386
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
1387 1388 1389
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1390
                    break;
1391 1392
                }
            }
1393 1394 1395
        }
    }

1396
    if (found) {
1397 1398
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1399 1400 1401
    }

    return found;
1402
}
1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415

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

1416 1417
/// Add the Mission Settings complex item to the front of the items
void MissionController::_addMissionSettings(Vehicle* vehicle, QmlObjectListModel* visualItems, bool addToCenter)
1418
{
1419
    MissionSettingsItem* settingsItem = new MissionSettingsItem(vehicle, visualItems);
1420

1421
    visualItems->insert(0, settingsItem);
1422

1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447
    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;
                    }
1448 1449
                }
            }
1450

1451 1452 1453
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1454
        }
1455 1456
    } else {
        settingsItem->setCoordinate(vehicle->homePosition());
1457 1458
    }
}
1459

1460
int MissionController::resumeMissionItem(void) const
1461
{
1462 1463 1464

    int resumeIndex = -1;

1465
    if (!_editMode) {
1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478
        int firstTrueItemIndex = _activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 1 : 0;
        resumeIndex = _activeVehicle->missionManager()->lastCurrentItem();
        if (resumeIndex > firstTrueItemIndex) {
            if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
                resumeIndex++;
            }
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
        }
    }

    return resumeIndex;
}
1479

1480 1481 1482
void MissionController::_currentMissionItemChanged(int sequenceNumber)
{
    if (!_editMode) {
1483 1484 1485 1486
        if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            sequenceNumber++;
        }

1487 1488
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1489 1490 1491 1492
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
    }
}
1493

1494
bool MissionController::syncInProgress(void) const
1495
{
1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508
    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);
1509
    }
1510
}
1511

1512 1513
QString MissionController::fileExtension(void) const
{
1514
    return AppSettings::missionFileExtension;
1515
}
1516

1517 1518
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1519 1520 1521
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, vehicle);

1522 1523 1524 1525 1526 1527
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1528
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
1529 1530 1531 1532 1533
        if (settingsItem && settingsItem->scanForMissionSettings(visualItems, scanIndex, vehicle)) {
            continue;
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1534 1535
        if (simpleItem) {
            simpleItem->scanForSections(visualItems, scanIndex + 1, vehicle);
1536 1537 1538 1539 1540
        }

        scanIndex++;
    }
}
1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554 1555 1556

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();
}
1557 1558 1559 1560 1561 1562 1563 1564 1565 1566 1567 1568

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

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

    return complexItems;
}
1569

1570
void MissionController::_visualItemsDirtyChanged(bool dirty)
1571
{
1572 1573 1574 1575 1576 1577 1578 1579 1580
    if (dirty) {
        if (_visualItems->count() > 1) {
            emit dirtyChanged(true);
        } else {
            // This was a change to mission settings with no other mission items added
            _visualItems->setDirty(false);
        }
    } else {
        emit dirtyChanged(false);
DonLakeFlyer's avatar
DonLakeFlyer committed
1581 1582
    }
}
1583 1584 1585 1586 1587 1588 1589 1590

void MissionController::resumeMission(int resumeIndex)
{
    if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
        resumeIndex--;
    }
    _activeVehicle->missionManager()->generateResumeMission(resumeIndex);
}
1591 1592 1593 1594 1595 1596 1597 1598 1599

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1600 1601 1602 1603 1604 1605 1606 1607 1608 1609

void MissionController::applyDefaultMissionAltitude(void)
{
    double defaultAltitude = _appSettings->defaultMissionItemAltitude()->rawValue().toDouble();

    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);
        item->applyNewAltitude(defaultAltitude);
    }
}