MissionController.cc 64.5 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
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();
80
    _missionFlightStatus.vehicleYaw =           0.0;
81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100
    _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);
        }
    }
101 102 103 104 105 106 107 108 109 110 111

    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionTimeChanged();
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);

112 113
}

114 115
void MissionController::start(bool editMode)
{
116 117
    qCDebug(MissionControllerLog) << "start editMode" << editMode;

118
    PlanElementController::start(editMode);
119 120 121 122 123 124
    _init();
}

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

126 127 128 129 130 131
    PlanElementController::startStaticActiveVehicle(vehicle);
    _init();
}

void MissionController::_init(void)
{
132
    // We start with an empty mission
133
    _visualItems = new QmlObjectListModel(this);
134
    _addMissionSettings(_activeVehicle, _visualItems, false /* addToCenter */);
135
    _initAllVisualItems();
136 137
}

138
// Called when new mission items have completed downloading from Vehicle
139
void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllRequested)
140
{
141 142
    qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle";

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

151 152
        QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
        const QList<MissionItem*>& newMissionItems = _activeVehicle->missionManager()->missionItems();
153 154 155 156 157 158
        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 */);
159
            MissionSettingsItem* settingsItem = newControllerMissionItems->value<MissionSettingsItem*>(0);
160 161 162 163 164 165 166
            if (!settingsItem) {
                qWarning() << "First item is not settings item";
                return;
            }
            settingsItem->setCoordinate(newMissionItems[0]->coordinate());
            i = 1;
        }
167

168 169
        for (; i<newMissionItems.count(); i++) {
            const MissionItem* missionItem = newMissionItems[i];
170 171 172 173
            newControllerMissionItems->append(new SimpleMissionItem(_activeVehicle, *missionItem, this));
        }

        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
174
        _visualItems->deleteLater();
175
        _settingsItem = NULL;
176 177 178
        _visualItems = newControllerMissionItems;

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

182
        _missionItemsRequested = false;
183

184
        if (_editMode) {
185
            MissionController::_scanForAdditionalSettings(_visualItems, _activeVehicle);
186
        }
187

188
        _initAllVisualItems();
189
        emit newItemsFromVehicle();
190 191 192
    }
}

193
void MissionController::loadFromVehicle(void)
194
{
195
    Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
196

197 198 199 200 201 202
    if (activeVehicle) {
        _missionItemsRequested = true;
        activeVehicle->missionManager()->requestMissionItems();
    }
}

203
void MissionController::sendToVehicle(void)
204
{
Don Gagne's avatar
Don Gagne committed
205 206 207 208
    sendItemsToVehicle(_activeVehicle, _visualItems);
    _visualItems->setDirty(false);
}

209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229
/// 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
230
    MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
231 232 233 234 235 236 237
    if (settingsItem) {
        endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
    }

    return endActionSet;
}

Don Gagne's avatar
Don Gagne committed
238 239 240
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
241
        QList<MissionItem*> rgMissionItems;
242

243
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
244

245
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
246

247 248
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
249
        }
250 251
    }
}
252

253 254 255 256 257 258
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
259 260
        VisualMissionItem* lastItem = _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1);
        return lastItem->lastSequenceNumber() + 1;
261 262 263
    }
}

264
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
265
{
266
    int sequenceNumber = _nextSequenceNumber();
267
    SimpleMissionItem * newItem = new SimpleMissionItem(_activeVehicle, this);
268
    newItem->setSequenceNumber(sequenceNumber);
269
    newItem->setCoordinate(coordinate);
270 271 272
    newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
    _initVisualItem(newItem);
    if (_visualItems->count() == 1) {
273 274
        newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
    }
275
    newItem->setDefaultsForCommand();
Don Gagne's avatar
Don Gagne committed
276
    if ((MAV_CMD)newItem->command() == MAV_CMD_NAV_WAYPOINT) {
277 278
        double      prevAltitude;
        MAV_FRAME   prevFrame;
279

280 281 282
        if (_findPreviousAltitude(i, &prevAltitude, &prevFrame)) {
            newItem->missionItem().setFrame(prevFrame);
            newItem->missionItem().setParam7(prevAltitude);
283
        }
284
    }
285
    _visualItems->insert(i, newItem);
286 287 288

    _recalcAll();

289
    return newItem->sequenceNumber();
290 291
}

292
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
293
{
294 295
    ComplexMissionItem* newItem;

296
    int sequenceNumber = _nextSequenceNumber();
297 298
    if (itemName == _surveyMissionItemName) {
        newItem = new SurveyMissionItem(_activeVehicle, _visualItems);
299
        newItem->setCoordinate(mapCenterCoordinate);
300
    } else if (itemName == _fwLandingMissionItemName) {
301
        newItem = new FixedWingLandingComplexItem(_activeVehicle, _visualItems);
302 303 304 305
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }
306
    newItem->setSequenceNumber(sequenceNumber);
307
    _initVisualItem(newItem);
308

309
    _visualItems->insert(i, newItem);
310 311 312

    _recalcAll();

313
    return newItem->sequenceNumber();
314 315
}

316 317
void MissionController::removeMissionItem(int index)
{
318
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
319

320
    _deinitVisualItem(item);
321
    item->deleteLater();
322 323

    _recalcAll();
324
    _visualItems->setDirty(true);
325 326
}

327
void MissionController::removeAll(void)
328
{
329 330
    if (_visualItems) {
        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
331
        _visualItems->deleteLater();
332
        _settingsItem = NULL;
333
        _visualItems = new QmlObjectListModel(this);
334
        _addMissionSettings(_activeVehicle, _visualItems, false /* addToCenter */);
335
        _initAllVisualItems();
Don Gagne's avatar
Don Gagne committed
336
        _visualItems->setDirty(true);
337
       _resetMissionFlightStatus();
338
    }
339
}
340

341
bool MissionController::_loadJsonMissionFile(Vehicle* vehicle, const QByteArray& bytes, QmlObjectListModel* visualItems, QString& errorString)
342 343 344 345 346 347 348 349 350 351
{
    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
352 353 354
    // 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;
355 356
    }

Don Gagne's avatar
Don Gagne committed
357 358 359 360 361 362 363
    int fileVersion;
    if (!JsonHelper::validateQGCJsonFile(json,
                                         _jsonFileTypeValue,    // expected file type
                                         1,                     // minimum supported version
                                         2,                     // maximum supported version
                                         fileVersion,
                                         errorString)) {
364 365
        return false;
    }
366

Don Gagne's avatar
Don Gagne committed
367
    if (fileVersion == 1) {
368
        return _loadJsonMissionFileV1(vehicle, json, visualItems, errorString);
Don Gagne's avatar
Don Gagne committed
369
    } else {
370
        return _loadJsonMissionFileV2(vehicle, json, visualItems, errorString);
Don Gagne's avatar
Don Gagne committed
371 372 373
    }
}

374
bool MissionController::_loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
375 376 377 378 379 380 381 382 383
{
    // 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)) {
384 385 386
        return false;
    }

387
    // Read complex items
388
    QList<SurveyMissionItem*> surveyItems;
389 390 391 392
    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];
393

394 395 396 397 398
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

Don Gagne's avatar
Don Gagne committed
399
        SurveyMissionItem* item = new SurveyMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
400 401
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
402
            surveyItems.append(item);
403 404
        } else {
            return false;
405
        }
406
    }
407

408 409 410 411 412
    // 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
413
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
414

415
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
416 417 418 419
    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
420 421
        if (nextComplexItemIndex < surveyItems.count()) {
            SurveyMissionItem* complexItem = surveyItems[nextComplexItemIndex];
422 423 424 425 426 427 428 429 430 431 432 433 434 435

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

436 437 438 439 440
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
441
            const QJsonObject itemObject = itemValue.toObject();
Don Gagne's avatar
Don Gagne committed
442
            SimpleMissionItem* item = new SimpleMissionItem(vehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
443
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
444
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
445
                nextSequenceNumber = item->lastSequenceNumber() + 1;
446
                visualItems->append(item);
447 448 449 450
            } else {
                return false;
            }
        }
451
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
452 453

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

Don Gagne's avatar
Don Gagne committed
456
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
457
            MissionSettingsItem* settingsItem = new MissionSettingsItem(vehicle, visualItems);
458 459 460
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
461 462 463 464
        } else {
            return false;
        }
    } else {
465
        _addMissionSettings(vehicle, visualItems, true /* addToCenter */);
466 467 468 469 470
    }

    return true;
}

471
bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
472 473 474 475 476 477
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
478 479 480
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
481 482 483 484 485 486 487
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

488
    // Mission Settings
Don Gagne's avatar
Don Gagne committed
489
    QGeoCoordinate homeCoordinate;
490
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
Don Gagne's avatar
Don Gagne committed
491 492 493
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
Don Gagne's avatar
Don Gagne committed
494
    if (json.contains(_jsonVehicleTypeKey) && vehicle->isOfflineEditingVehicle()) {
495
        appSettings->offlineEditingVehicleType()->setRawValue(json[_jsonVehicleTypeKey].toDouble());
496 497
    }
    if (json.contains(_jsonCruiseSpeedKey)) {
498
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
499 500
    }
    if (json.contains(_jsonHoverSpeedKey)) {
501
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
502 503
    }

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

            if (item->load(stream)) {
638
                visualItems->append(item);
639 640 641 642 643 644
            } else {
                errorString = QStringLiteral("The mission file is corrupted.");
                return false;
            }
        }
    } else {
645
        errorString = QStringLiteral("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
646 647 648
        return false;
    }

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

652 653 654 655 656
        // 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
657 658
            }
        }
659 660 661
    }

    return true;
662 663
}

664
void MissionController::loadFromFile(const QString& filename)
665
{
Don Gagne's avatar
Don Gagne committed
666 667
    QmlObjectListModel* newVisualItems = NULL;

668
    if (!loadItemsFromFile(_activeVehicle, filename, &newVisualItems)) {
Don Gagne's avatar
Don Gagne committed
669 670 671 672 673 674
        return;
    }

    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
675
        _settingsItem = NULL;
Don Gagne's avatar
Don Gagne committed
676 677 678 679 680
    }

    _visualItems = newVisualItems;

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

684
    MissionController::_scanForAdditionalSettings(_visualItems, _activeVehicle);
685

Don Gagne's avatar
Don Gagne committed
686 687 688
    _initAllVisualItems();
}

689
bool MissionController::loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems)
Don Gagne's avatar
Don Gagne committed
690 691 692
{
    *visualItems = NULL;

693 694 695
    QString errorString;

    if (filename.isEmpty()) {
Don Gagne's avatar
Don Gagne committed
696
        return false;
697 698
    }

Don Gagne's avatar
Don Gagne committed
699
    *visualItems = new QmlObjectListModel();
700 701 702 703

    QFile file(filename);

    if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
Don Gagne's avatar
Don Gagne committed
704
        errorString = file.errorString() + QStringLiteral(" ") + filename;
705
    } else {
706 707
        QByteArray  bytes = file.readAll();
        QTextStream stream(&bytes);
708

709 710 711
        QString firstLine = stream.readLine();
        if (firstLine.contains(QRegExp("QGC.*WPL"))) {
            stream.seek(0);
Don Gagne's avatar
Don Gagne committed
712
            _loadTextMissionFile(vehicle, stream, *visualItems, errorString);
713
        } else {
714
            _loadJsonMissionFile(vehicle, bytes, *visualItems, errorString);
715 716
        }
    }
717

718
    if (!errorString.isEmpty()) {
Don Gagne's avatar
Don Gagne committed
719
        (*visualItems)->deleteLater();
720

721
        qgcApp()->showMessage(errorString);
Don Gagne's avatar
Don Gagne committed
722
        return false;
723 724
    }

Don Gagne's avatar
Don Gagne committed
725
    return true;
726 727
}

728
void MissionController::saveToFile(const QString& filename)
729
{
730 731 732
    if (filename.isEmpty()) {
        return;
    }
733

734
    QString missionFilename = filename;
735
    if (!QFileInfo(filename).fileName().contains(".")) {
736
        missionFilename += QString(".%1").arg(AppSettings::missionFileExtension);
737 738
    }

739
    QFile file(missionFilename);
740

741
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
742
        qgcApp()->showMessage(tr("Mission save %1 : %2").arg(filename).arg(file.errorString()));
743
    } else {
744
        QJsonObject missionFileObject;      // top level json object
745

Don Gagne's avatar
Don Gagne committed
746
        missionFileObject[JsonHelper::jsonVersionKey] =         _missionFileVersion;
747
        missionFileObject[JsonHelper::jsonGroundStationKey] =   JsonHelper::jsonGroundStationValue;
748

749
        // Mission settings
750

751
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
752
        if (!settingsItem) {
753
            qWarning() << "First item is not MissionSettingsItem";
754 755
            return;
        }
Don Gagne's avatar
Don Gagne committed
756
        QJsonValue coordinateValue;
757
        JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
Don Gagne's avatar
Don Gagne committed
758
        missionFileObject[_jsonPlannedHomePositionKey] = coordinateValue;
759 760
        missionFileObject[_jsonFirmwareTypeKey] = _activeVehicle->firmwareType();
        missionFileObject[_jsonVehicleTypeKey] = _activeVehicle->vehicleType();
DonLakeFlyer's avatar
DonLakeFlyer committed
761 762
        missionFileObject[_jsonCruiseSpeedKey] = _activeVehicle->defaultCruiseSpeed();
        missionFileObject[_jsonHoverSpeedKey] = _activeVehicle->defaultHoverSpeed();
763

764
        // Save the visual items
765

DonLakeFlyer's avatar
DonLakeFlyer committed
766
        QJsonArray rgJsonMissionItems;
767
        for (int i=0; i<_visualItems->count(); i++) {
768
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785

            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();
            }
786
        }
787 788

        missionFileObject[_jsonItemsKey] = rgJsonMissionItems;
789 790

        QJsonDocument saveDoc(missionFileObject);
791
        file.write(saveDoc.toJson());
792 793
    }

794 795 796 797
    // 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);
    }
798 799
}

800
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
801
{
Don Gagne's avatar
Don Gagne committed
802
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
803
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
804 805 806 807
    bool            distanceOk =    false;

    // Convert to fixed altitudes

808
    distanceOk = true;
809
    if (currentItem->coordinateHasRelativeAltitude()) {
810 811
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
812
    if (prevItem->exitCoordinateHasRelativeAltitude()) {
813
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
814 815 816
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
817 818 819
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
820
    } else {
Don Gagne's avatar
Don Gagne committed
821
        *altDifference = 0.0;
822
        *azimuth = 0.0;
823
        *distance = 0.0;
824 825 826
    }
}

827
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
828 829 830 831 832 833 834
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

835
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
836 837
}

838 839
void MissionController::_recalcWaypointLines(void)
{
840 841 842
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

843
    bool showHomePosition = _settingsItem->coordinate().isValid();
844

845
    qCDebug(MissionControllerLog) << "_recalcWaypointLines showHomePosition" << showHomePosition;
846

Nate Weibley's avatar
Nate Weibley committed
847 848
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
849 850 851 852 853 854 855
    _waypointLines.clear();

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


856
        // If we still haven't found the first coordinate item and we hit a takeoff command, link back to home
857 858
        if (firstCoordinateItem &&
                item->isSimpleItem() &&
859 860
                (qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF ||
                 qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) {
861 862 863 864 865 866 867
            linkBackToHome = true;
        }

        if (item->specifiesCoordinate()) {
            if (!item->isStandaloneCoordinate()) {
                firstCoordinateItem = false;
                VisualItemPair pair(lastCoordinateItem, item);
868
                if (lastCoordinateItem != _settingsItem || (showHomePosition && linkBackToHome)) {
869 870
                    if (old_table.contains(pair)) {
                        // Do nothing, this segment already exists and is wired up
Nate Weibley's avatar
Nate Weibley committed
871
                        _linesTable[pair] = old_table.take(pair);
872 873 874 875
                    } 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
876
                                endNotifier    = &VisualMissionItem::coordinateChanged;
877 878 879 880 881 882
                        // 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
883
                        connect(item, &VisualMissionItem::coordinateChanged, this, &MissionController::_recalcMissionFlightStatus);
Nate Weibley's avatar
Nate Weibley committed
884
                        _linesTable[pair] = linevect;
885 886 887 888 889 890 891 892 893 894
                    }
                }
                lastCoordinateItem = item;
            }
        }
    }

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
895 896
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
897 898 899 900 901 902 903 904 905 906
            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
907
    _recalcMissionFlightStatus();
908 909 910 911

    emit waypointLinesChanged();
}

912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941
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
942
void MissionController::_recalcMissionFlightStatus()
943
{
944
    if (!_visualItems->count()) {
945
        return;
946
    }
947 948 949 950

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

951
    bool showHomePosition = _settingsItem->coordinate().isValid();
952

DonLakeFlyer's avatar
DonLakeFlyer committed
953
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
954

955 956 957
    // 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.
958

959
    // No values for first item
960
    lastCoordinateItem->setAltDifference(0.0);
961
    lastCoordinateItem->setAzimuth(0.0);
962
    lastCoordinateItem->setDistance(0.0);
963

964 965
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
966 967
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
968

969
    _resetMissionFlightStatus();
970

DonLakeFlyer's avatar
DonLakeFlyer committed
971
    bool vtolInHover = true;
Don Gagne's avatar
Don Gagne committed
972
    bool linkBackToHome = false;
973

DonLakeFlyer's avatar
DonLakeFlyer committed
974
    for (int i=0; i<_visualItems->count(); i++) {
975
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
976 977 978
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

979 980
        // Assume the worst
        item->setAzimuth(0.0);
981
        item->setDistance(0.0);
982

DonLakeFlyer's avatar
DonLakeFlyer committed
983 984 985 986 987 988 989 990
        // 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;
991
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
992
                    _missionFlightStatus.cruiseSpeed = newSpeed;
993
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
994 995
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
996
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
997 998 999 1000
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1001 1002 1003 1004 1005 1006
        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
1007 1008 1009 1010 1011
        }

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

1014 1015 1016 1017 1018 1019 1020 1021
        // 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
1022
        if (simpleItem && _activeVehicle->vtol()) {
1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036
            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;
1037 1038
                }
            }
1039 1040 1041
                break;
            default:
                break;
1042
            }
Don Gagne's avatar
Don Gagne committed
1043 1044
        }

1045
        if (item->specifiesCoordinate()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1046 1047
            // Update vehicle yaw assuming direction to next waypoint
            if (item != lastCoordinateItem) {
1048 1049
                _missionFlightStatus.vehicleYaw = lastCoordinateItem->exitCoordinate().azimuthTo(item->coordinate());
                lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
DonLakeFlyer's avatar
DonLakeFlyer committed
1050 1051
            }

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

1054
            double absoluteAltitude = item->coordinate().altitude();
1055
            if (item->coordinateHasRelativeAltitude()) {
1056 1057 1058 1059 1060
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1061 1062 1063 1064 1065 1066 1067 1068 1069 1070
            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
1071
                firstCoordinateItem = false;
1072
                if (lastCoordinateItem != _settingsItem || linkBackToHome) {
1073 1074
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1075

1076
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1077 1078 1079
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1080

1081
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1082

DonLakeFlyer's avatar
DonLakeFlyer committed
1083 1084 1085 1086
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
                    if (_activeVehicle->vtol()) {
1087
                        if (vtolInHover) {
1088
                            _addHoverTime(hoverTime, distance, item->sequenceNumber());
1089
                        } else {
1090
                            _addCruiseTime(cruiseTime, distance, item->sequenceNumber());
1091 1092
                        }
                    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1093
                        if (_activeVehicle->multiRotor()) {
1094
                            _addHoverTime(hoverTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1095
                        } else {
1096
                            _addCruiseTime(cruiseTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1097
                        }
1098
                    }
1099
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1100

1101
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1102 1103
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1104
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1105

1106 1107
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
DonLakeFlyer's avatar
DonLakeFlyer committed
1108 1109
                    if (_activeVehicle->vtol()) {
                        if (vtolInHover) {
1110
                            _addHoverTime(hoverTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1111
                        } else {
1112
                            _addCruiseTime(cruiseTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1113 1114 1115
                        }
                    } else {
                        if (_activeVehicle->multiRotor()) {
1116
                            _addHoverTime(hoverTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1117
                        } else {
1118
                            _addCruiseTime(cruiseTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1119 1120
                        }
                    }
1121
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1122 1123

                item->setMissionFlightStatus(_missionFlightStatus);
1124
            }
1125 1126

            lastCoordinateItem = item;
1127 1128
        }
    }
1129
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1130

1131 1132 1133
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1134

DonLakeFlyer's avatar
DonLakeFlyer committed
1135 1136 1137 1138 1139 1140 1141
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1142 1143
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1144

1145 1146
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1147 1148
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1149 1150 1151

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1152
            if (item->coordinateHasRelativeAltitude()) {
1153 1154 1155 1156 1157 1158
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1159
            }
1160 1161 1162 1163
        }
    }
}

1164 1165 1166
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1167 1168 1169 1170 1171 1172
    // 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));

1173 1174
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1175 1176 1177
    }
}

1178 1179 1180
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1181
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1182 1183 1184

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

1185 1186
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1187 1188 1189 1190 1191

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1192
        } else if (item->isSimpleItem()) {
1193 1194 1195 1196 1197
            currentParentItem->childItems()->append(item);
        }
    }
}

1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214
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));
        }
    }
}


1215 1216
void MissionController::_recalcAll(void)
{
1217 1218 1219
    if (_editMode) {
        _setPlannedHomePositionFromFirstCoordinate();
    }
1220
    _recalcSequence();
1221 1222 1223 1224
    _recalcChildItems();
    _recalcWaypointLines();
}

1225
/// Initializes a new set of mission items
1226
void MissionController::_initAllVisualItems(void)
1227
{
1228 1229
    // Setup home position at index 0

1230 1231 1232
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1233 1234
        return;
    }
1235
    _settingsItem->setIsCurrentItem(true);
1236

1237 1238
    if (!_editMode && _activeVehicle) {
        _settingsItem->setCoordinate(_activeVehicle->homePosition());
1239
    }
1240

1241
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
1242
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);
1243

1244 1245 1246 1247
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1248

1249
    _recalcAll();
1250

1251
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1252 1253 1254
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1255
    emit containsItemsChanged(containsItems());
1256
    emit plannedHomePositionChanged(plannedHomePosition());
1257

1258
    _visualItems->setDirty(false);
1259 1260
}

1261
void MissionController::_deinitAllVisualItems(void)
1262
{
1263 1264 1265
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1266 1267
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1268 1269
    }

1270
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1271
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1272 1273
}

1274
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1275
{
1276 1277
    _visualItems->setDirty(false);

1278
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1279 1280
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1281 1282
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1283
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1284

1285 1286 1287 1288 1289 1290 1291 1292
    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";
        }
1293 1294
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1295
        if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1296
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcMissionFlightStatus);
1297 1298 1299
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1300
    }
1301 1302
}

1303
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1304
{
1305 1306
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1307 1308
}

1309
void MissionController::_itemCommandChanged(void)
1310
{
1311 1312
    _recalcChildItems();
    _recalcWaypointLines();
1313 1314
}

1315
void MissionController::_activeVehicleBeingRemoved(void)
1316
{
1317
    qCDebug(MissionControllerLog) << "MissionController::_activeVehicleBeingRemoved";
1318

1319
    MissionManager* missionManager = _activeVehicle->missionManager();
1320 1321 1322 1323

    disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailableFromVehicle);
    disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
    disconnect(missionManager, &MissionManager::currentItemChanged,         this, &MissionController::_currentMissionItemChanged);
1324 1325
    disconnect(missionManager, &MissionManager::lastCurrentItemChanged,     this, &MissionController::resumeMissionItemChanged);
    disconnect(missionManager, &MissionManager::resumeMissionReady,         this, &MissionController::resumeMissionReady);
1326
    disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
Don Gagne's avatar
Don Gagne committed
1327

Don Gagne's avatar
Don Gagne committed
1328 1329
    // 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
1330 1331
    removeAll();
}
Don Gagne's avatar
Don Gagne committed
1332

1333 1334 1335 1336 1337
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();
1338

1339 1340 1341 1342 1343
    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);
1344 1345
    connect(missionManager, &MissionManager::lastCurrentItemChanged,    this, &MissionController::resumeMissionItemChanged);
    connect(missionManager, &MissionManager::resumeMissionReady,        this, &MissionController::resumeMissionReady);
1346
    connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);
DonLakeFlyer's avatar
DonLakeFlyer committed
1347 1348
    connect(_activeVehicle, &Vehicle::defaultCruiseSpeedChanged,        this, &MissionController::_recalcMissionFlightStatus);
    connect(_activeVehicle, &Vehicle::defaultHoverSpeedChanged,         this, &MissionController::_recalcMissionFlightStatus);
1349
    connect(_activeVehicle, &Vehicle::vehicleTypeChanged,               this, &MissionController::complexMissionItemNamesChanged);
1350

1351
    if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
1352 1353 1354
        // 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();
1355
    }
1356

1357
    _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
1358 1359

    emit complexMissionItemNamesChanged();
1360
    emit resumeMissionItemChanged();
1361 1362 1363 1364
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
1365 1366
    if (_visualItems) {
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1367
        if (settingsItem) {
1368
            settingsItem->setCoordinate(homePosition);
1369
        } else {
1370
            qWarning() << "First item is not MissionSettingsItem";
1371
        }
1372
    }
1373 1374 1375
}

void MissionController::_inProgressChanged(bool inProgress)
1376
{
1377
    emit syncInProgressChanged(inProgress);
1378
}
1379

1380
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
1381
{
1382 1383 1384
    bool        found = false;
    double      foundAltitude;
    MAV_FRAME   foundFrame;
1385

1386 1387 1388 1389 1390 1391
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1394 1395 1396
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1397
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
1398 1399 1400
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1401
                    break;
1402 1403
                }
            }
1404 1405 1406
        }
    }

1407
    if (found) {
1408 1409
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1410 1411 1412
    }

    return found;
1413
}
1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426

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

1427 1428
/// Add the Mission Settings complex item to the front of the items
void MissionController::_addMissionSettings(Vehicle* vehicle, QmlObjectListModel* visualItems, bool addToCenter)
1429
{
1430
    MissionSettingsItem* settingsItem = new MissionSettingsItem(vehicle, visualItems);
1431

1432
    visualItems->insert(0, settingsItem);
1433

1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458
    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;
                    }
1459 1460
                }
            }
1461

1462 1463 1464
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1465
        }
1466 1467
    } else {
        settingsItem->setCoordinate(vehicle->homePosition());
1468 1469
    }
}
1470

1471
int MissionController::resumeMissionItem(void) const
1472
{
1473 1474 1475

    int resumeIndex = -1;

1476
    if (!_editMode) {
1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489
        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;
}
1490

1491 1492 1493
void MissionController::_currentMissionItemChanged(int sequenceNumber)
{
    if (!_editMode) {
1494 1495 1496 1497
        if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            sequenceNumber++;
        }

1498 1499
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1500 1501 1502 1503
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
    }
}
1504

1505
bool MissionController::syncInProgress(void) const
1506
{
1507 1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519
    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);
1520
    }
1521
}
1522

1523 1524
QString MissionController::fileExtension(void) const
{
1525
    return AppSettings::missionFileExtension;
1526
}
1527

1528 1529
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1530 1531 1532
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, vehicle);

1533 1534 1535 1536 1537 1538
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1539
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
1540
        if (settingsItem && settingsItem->scanForMissionSettings(visualItems, scanIndex)) {
1541 1542 1543 1544
            continue;
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1545
        if (simpleItem) {
1546 1547 1548 1549 1550
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
1551 1552 1553
        }
    }
}
1554 1555 1556 1557 1558 1559 1560 1561 1562 1563 1564 1565 1566 1567 1568 1569

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();
}
1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581

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

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

    return complexItems;
}
1582

1583
void MissionController::_visualItemsDirtyChanged(bool dirty)
1584
{
1585 1586 1587 1588 1589 1590 1591 1592 1593
    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
1594 1595
    }
}
1596 1597 1598 1599 1600 1601 1602 1603

void MissionController::resumeMission(int resumeIndex)
{
    if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
        resumeIndex--;
    }
    _activeVehicle->missionManager()->generateResumeMission(resumeIndex);
}
1604 1605 1606 1607 1608 1609 1610 1611 1612

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1613 1614 1615 1616 1617 1618 1619 1620 1621 1622

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