MissionController.cc 64.9 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
#include "QGCQGeoCoordinate.h"
27

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

33 34
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

MissionController::MissionController(QObject *parent)
52
    : PlanElementController(parent)
53
    , _visualItems(NULL)
54
    , _settingsItem(NULL)
55
    , _firstItemsFromVehicle(false)
56
    , _missionItemsRequested(false)
57 58
    , _surveyMissionItemName(tr("Survey"))
    , _fwLandingMissionItemName(tr("Fixed Wing Landing"))
59
    , _appSettings(qgcApp()->toolbox()->settingsManager()->appSettings())
60
{
61
    _resetMissionFlightStatus();
62 63 64 65
}

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

67 68
}

69 70 71 72 73 74 75 76 77 78 79 80
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();
81
    _missionFlightStatus.vehicleYaw =           0.0;
82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101
    _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 104 105 106 107 108 109 110 111 112

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

113 114
}

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

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

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

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

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

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

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

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

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

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

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

183
        _missionItemsRequested = false;
184

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

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

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

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

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

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

    return endActionSet;
}

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

244
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
245

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

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

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

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

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

    _recalcAll();

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

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

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

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

    _recalcAll();

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

    return true;
}

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

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

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

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

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

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

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

    return true;
663 664
}

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

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

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

    _visualItems = newVisualItems;

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

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

Don Gagne's avatar
Don Gagne committed
687
    _initAllVisualItems();
688 689 690 691 692

    if (!_activeVehicle->isOfflineEditingVehicle()) {
        // Needs a sync to vehicle
        setDirty(true);
    }
Don Gagne's avatar
Don Gagne committed
693 694
}

695
bool MissionController::loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems)
Don Gagne's avatar
Don Gagne committed
696 697 698
{
    *visualItems = NULL;

699 700 701
    QString errorString;

    if (filename.isEmpty()) {
Don Gagne's avatar
Don Gagne committed
702
        return false;
703 704
    }

Don Gagne's avatar
Don Gagne committed
705
    *visualItems = new QmlObjectListModel();
706 707 708 709

    QFile file(filename);

    if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
Don Gagne's avatar
Don Gagne committed
710
        errorString = file.errorString() + QStringLiteral(" ") + filename;
711
    } else {
712 713
        QByteArray  bytes = file.readAll();
        QTextStream stream(&bytes);
714

715 716 717
        QString firstLine = stream.readLine();
        if (firstLine.contains(QRegExp("QGC.*WPL"))) {
            stream.seek(0);
Don Gagne's avatar
Don Gagne committed
718
            _loadTextMissionFile(vehicle, stream, *visualItems, errorString);
719
        } else {
720
            _loadJsonMissionFile(vehicle, bytes, *visualItems, errorString);
721 722
        }
    }
723

724
    if (!errorString.isEmpty()) {
Don Gagne's avatar
Don Gagne committed
725
        (*visualItems)->deleteLater();
726

727
        qgcApp()->showMessage(errorString);
Don Gagne's avatar
Don Gagne committed
728
        return false;
729 730
    }

Don Gagne's avatar
Don Gagne committed
731
    return true;
732 733
}

734
void MissionController::saveToFile(const QString& filename)
735
{
736 737 738
    if (filename.isEmpty()) {
        return;
    }
739

740
    QString missionFilename = filename;
741
    if (!QFileInfo(filename).fileName().contains(".")) {
742
        missionFilename += QString(".%1").arg(AppSettings::missionFileExtension);
743 744
    }

745
    QFile file(missionFilename);
746

747
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
748
        qgcApp()->showMessage(tr("Mission save %1 : %2").arg(filename).arg(file.errorString()));
749
    } else {
750
        QJsonObject missionFileObject;      // top level json object
751

Don Gagne's avatar
Don Gagne committed
752
        missionFileObject[JsonHelper::jsonVersionKey] =         _missionFileVersion;
753
        missionFileObject[JsonHelper::jsonGroundStationKey] =   JsonHelper::jsonGroundStationValue;
754

755
        // Mission settings
756

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

770
        // Save the visual items
771

DonLakeFlyer's avatar
DonLakeFlyer committed
772
        QJsonArray rgJsonMissionItems;
773
        for (int i=0; i<_visualItems->count(); i++) {
774
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791

            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();
            }
792
        }
793 794

        missionFileObject[_jsonItemsKey] = rgJsonMissionItems;
795 796

        QJsonDocument saveDoc(missionFileObject);
797
        file.write(saveDoc.toJson());
798 799
    }

800 801 802 803
    // 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);
    }
804 805
}

806
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
807
{
Don Gagne's avatar
Don Gagne committed
808
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
809
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
810 811 812 813
    bool            distanceOk =    false;

    // Convert to fixed altitudes

814
    distanceOk = true;
815
    if (currentItem->coordinateHasRelativeAltitude()) {
816 817
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
818
    if (prevItem->exitCoordinateHasRelativeAltitude()) {
819
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
820 821 822
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
823 824 825
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
826
    } else {
Don Gagne's avatar
Don Gagne committed
827
        *altDifference = 0.0;
828
        *azimuth = 0.0;
829
        *distance = 0.0;
830 831 832
    }
}

833
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
834 835 836 837 838 839 840
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

841
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
842 843
}

844 845
void MissionController::_recalcWaypointLines(void)
{
846 847 848
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

849
    bool showHomePosition = _settingsItem->coordinate().isValid();
850

851
    qCDebug(MissionControllerLog) << "_recalcWaypointLines showHomePosition" << showHomePosition;
852

Nate Weibley's avatar
Nate Weibley committed
853 854
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
855 856 857 858 859 860 861
    _waypointLines.clear();

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


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

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

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

    emit waypointLinesChanged();
}

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

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

957
    bool showHomePosition = _settingsItem->coordinate().isValid();
958

DonLakeFlyer's avatar
DonLakeFlyer committed
959
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
960

961 962 963
    // 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.
964

965
    // No values for first item
966
    lastCoordinateItem->setAltDifference(0.0);
967
    lastCoordinateItem->setAzimuth(0.0);
968
    lastCoordinateItem->setDistance(0.0);
969

970 971
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
972 973
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
974

975
    _resetMissionFlightStatus();
976

DonLakeFlyer's avatar
DonLakeFlyer committed
977
    bool vtolInHover = true;
Don Gagne's avatar
Don Gagne committed
978
    bool linkBackToHome = false;
979

DonLakeFlyer's avatar
DonLakeFlyer committed
980
    for (int i=0; i<_visualItems->count(); i++) {
981
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
982 983 984
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

985 986
        // Assume the worst
        item->setAzimuth(0.0);
987
        item->setDistance(0.0);
988

DonLakeFlyer's avatar
DonLakeFlyer committed
989 990 991 992 993 994 995 996
        // 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;
997
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
998
                    _missionFlightStatus.cruiseSpeed = newSpeed;
999
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1000 1001
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1002
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1003 1004 1005 1006
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1007 1008 1009 1010 1011 1012
        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
1013 1014 1015 1016 1017
        }

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

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

1051
        if (item->specifiesCoordinate()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1052 1053
            // Update vehicle yaw assuming direction to next waypoint
            if (item != lastCoordinateItem) {
1054 1055
                _missionFlightStatus.vehicleYaw = lastCoordinateItem->exitCoordinate().azimuthTo(item->coordinate());
                lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
DonLakeFlyer's avatar
DonLakeFlyer committed
1056 1057
            }

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

1060
            double absoluteAltitude = item->coordinate().altitude();
1061
            if (item->coordinateHasRelativeAltitude()) {
1062 1063 1064 1065 1066
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

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

1082
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1083 1084 1085
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1086

1087
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1088

DonLakeFlyer's avatar
DonLakeFlyer committed
1089 1090 1091 1092
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
                    if (_activeVehicle->vtol()) {
1093
                        if (vtolInHover) {
1094
                            _addHoverTime(hoverTime, distance, item->sequenceNumber());
1095
                        } else {
1096
                            _addCruiseTime(cruiseTime, distance, item->sequenceNumber());
1097 1098
                        }
                    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1099
                        if (_activeVehicle->multiRotor()) {
1100
                            _addHoverTime(hoverTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1101
                        } else {
1102
                            _addCruiseTime(cruiseTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1103
                        }
1104
                    }
1105
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1106

1107
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1108 1109
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1110
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1111

1112 1113
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
DonLakeFlyer's avatar
DonLakeFlyer committed
1114 1115
                    if (_activeVehicle->vtol()) {
                        if (vtolInHover) {
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
                        }
                    } else {
                        if (_activeVehicle->multiRotor()) {
1122
                            _addHoverTime(hoverTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1123
                        } else {
1124
                            _addCruiseTime(cruiseTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1125 1126
                        }
                    }
1127
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1128 1129

                item->setMissionFlightStatus(_missionFlightStatus);
1130
            }
1131 1132

            lastCoordinateItem = item;
1133 1134
        }
    }
1135
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1136

1137 1138 1139
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1140

DonLakeFlyer's avatar
DonLakeFlyer committed
1141 1142 1143 1144 1145 1146 1147
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1148 1149
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1150

1151 1152
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1153 1154
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1155 1156 1157

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1158
            if (item->coordinateHasRelativeAltitude()) {
1159 1160 1161 1162 1163 1164
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1165
            }
1166 1167 1168 1169
        }
    }
}

1170 1171 1172
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1173 1174 1175 1176 1177 1178
    // 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));

1179 1180
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1181 1182 1183
    }
}

1184 1185 1186
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1187
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1188 1189 1190

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

1191 1192
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1193 1194 1195 1196 1197

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1198
        } else if (item->isSimpleItem()) {
1199 1200 1201 1202 1203
            currentParentItem->childItems()->append(item);
        }
    }
}

1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220
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));
        }
    }
}


1221 1222
void MissionController::_recalcAll(void)
{
1223 1224 1225
    if (_editMode) {
        _setPlannedHomePositionFromFirstCoordinate();
    }
1226
    _recalcSequence();
1227 1228 1229 1230
    _recalcChildItems();
    _recalcWaypointLines();
}

1231
/// Initializes a new set of mission items
1232
void MissionController::_initAllVisualItems(void)
1233
{
1234 1235
    // Setup home position at index 0

1236 1237 1238
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1239 1240
        return;
    }
1241 1242 1243
    if (_editMode) {
        _settingsItem->setIsCurrentItem(true);
    }
1244

1245 1246
    if (!_editMode && _activeVehicle) {
        _settingsItem->setCoordinate(_activeVehicle->homePosition());
1247
    }
1248

1249
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
1250
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);
1251

1252 1253 1254 1255
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1256

1257
    _recalcAll();
1258

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

    emit visualItemsChanged();
1263
    emit containsItemsChanged(containsItems());
1264
    emit plannedHomePositionChanged(plannedHomePosition());
1265

1266
    _visualItems->setDirty(false);
1267 1268
}

1269
void MissionController::_deinitAllVisualItems(void)
1270
{
1271 1272 1273
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1274 1275
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1276 1277
    }

1278
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1279
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1280 1281
}

1282
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1283
{
1284 1285
    _visualItems->setDirty(false);

1286
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1287 1288
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1289 1290
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1291
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1292

1293 1294 1295 1296 1297 1298 1299 1300
    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";
        }
1301 1302
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1303
        if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1304
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcMissionFlightStatus);
1305 1306 1307
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1308
    }
1309 1310
}

1311
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1312
{
1313 1314
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1315 1316
}

1317
void MissionController::_itemCommandChanged(void)
1318
{
1319 1320
    _recalcChildItems();
    _recalcWaypointLines();
1321 1322
}

1323
void MissionController::_activeVehicleBeingRemoved(void)
1324
{
1325
    qCDebug(MissionControllerLog) << "MissionController::_activeVehicleBeingRemoved";
1326

1327
    MissionManager* missionManager = _activeVehicle->missionManager();
1328 1329 1330

    disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailableFromVehicle);
    disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
1331 1332
    disconnect(missionManager, &MissionManager::currentIndexChanged,        this, &MissionController::_currentMissionIndexChanged);
    disconnect(missionManager, &MissionManager::lastCurrentIndexChanged,    this, &MissionController::resumeMissionIndexChanged);
1333
    disconnect(missionManager, &MissionManager::resumeMissionReady,         this, &MissionController::resumeMissionReady);
1334
    disconnect(missionManager, &MissionManager::cameraFeedback,             this, &MissionController::_cameraFeedback);
1335
    disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
Don Gagne's avatar
Don Gagne committed
1336

Don Gagne's avatar
Don Gagne committed
1337 1338
    // 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
1339 1340
    removeAll();
}
Don Gagne's avatar
Don Gagne committed
1341

1342 1343 1344 1345 1346
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();
1347

1348 1349 1350 1351
    MissionManager* missionManager = _activeVehicle->missionManager();

    connect(missionManager, &MissionManager::newMissionItemsAvailable,  this, &MissionController::_newMissionItemsAvailableFromVehicle);
    connect(missionManager, &MissionManager::inProgressChanged,         this, &MissionController::_inProgressChanged);
1352 1353
    connect(missionManager, &MissionManager::currentIndexChanged,       this, &MissionController::_currentMissionIndexChanged);
    connect(missionManager, &MissionManager::lastCurrentIndexChanged,   this, &MissionController::resumeMissionIndexChanged);
1354
    connect(missionManager, &MissionManager::resumeMissionReady,        this, &MissionController::resumeMissionReady);
1355
    connect(missionManager, &MissionManager::cameraFeedback,            this, &MissionController::_cameraFeedback);
1356
    connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);
DonLakeFlyer's avatar
DonLakeFlyer committed
1357 1358
    connect(_activeVehicle, &Vehicle::defaultCruiseSpeedChanged,        this, &MissionController::_recalcMissionFlightStatus);
    connect(_activeVehicle, &Vehicle::defaultHoverSpeedChanged,         this, &MissionController::_recalcMissionFlightStatus);
1359
    connect(_activeVehicle, &Vehicle::vehicleTypeChanged,               this, &MissionController::complexMissionItemNamesChanged);
1360

1361
    if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
1362 1363 1364
        // 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();
1365
    }
1366

1367
    _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
1368 1369

    emit complexMissionItemNamesChanged();
1370
    emit resumeMissionIndexChanged();
1371 1372 1373 1374
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
1375 1376
    if (_visualItems) {
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1377
        if (settingsItem) {
1378
            settingsItem->setCoordinate(homePosition);
1379
        } else {
1380
            qWarning() << "First item is not MissionSettingsItem";
1381
        }
1382
    }
1383 1384 1385
}

void MissionController::_inProgressChanged(bool inProgress)
1386
{
1387
    emit syncInProgressChanged(inProgress);
1388
}
1389

1390
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
1391
{
1392 1393 1394
    bool        found = false;
    double      foundAltitude;
    MAV_FRAME   foundFrame;
1395

1396 1397 1398 1399 1400 1401
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1404 1405 1406
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1407
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
1408 1409 1410
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1411
                    break;
1412 1413
                }
            }
1414 1415 1416
        }
    }

1417
    if (found) {
1418 1419
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1420 1421 1422
    }

    return found;
1423
}
1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436

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

1437 1438
/// Add the Mission Settings complex item to the front of the items
void MissionController::_addMissionSettings(Vehicle* vehicle, QmlObjectListModel* visualItems, bool addToCenter)
1439
{
1440
    MissionSettingsItem* settingsItem = new MissionSettingsItem(vehicle, visualItems);
1441

1442
    visualItems->insert(0, settingsItem);
1443

1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468
    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;
                    }
1469 1470
                }
            }
1471

1472 1473 1474
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1475
        }
1476 1477
    } else {
        settingsItem->setCoordinate(vehicle->homePosition());
1478 1479
    }
}
1480

1481
int MissionController::resumeMissionIndex(void) const
1482
{
1483

1484
    int resumeIndex = 0;
1485

1486
    if (!_editMode) {
1487
        resumeIndex = _activeVehicle->missionManager()->lastCurrentIndex() + (_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1488
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1489 1490
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1491 1492
        } else {
            resumeIndex = 0;
1493 1494 1495
        }
    }

1496
    qDebug() << "resumeIndex" << resumeIndex;
1497 1498
    return resumeIndex;
}
1499

1500
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1501 1502
{
    if (!_editMode) {
1503 1504 1505 1506
        if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            sequenceNumber++;
        }

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

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

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

1537 1538
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1539 1540 1541
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, vehicle);

1542 1543 1544 1545 1546 1547
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1548
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
1549 1550 1551
        if (settingsItem) {
            scanIndex++;
            settingsItem->scanForMissionSettings(visualItems, scanIndex);
1552 1553 1554 1555
            continue;
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1556
        if (simpleItem) {
1557 1558 1559 1560 1561
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
1562 1563 1564
        }
    }
}
1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580

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();
}
1581 1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592

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

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

    return complexItems;
}
1593

1594 1595 1596 1597 1598 1599 1600
void MissionController::resumeMission(int resumeIndex)
{
    if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
        resumeIndex--;
    }
    _activeVehicle->missionManager()->generateResumeMission(resumeIndex);
}
1601 1602 1603 1604 1605 1606 1607 1608 1609

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

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);
    }
}
1620 1621 1622 1623 1624 1625 1626 1627 1628 1629 1630 1631 1632

void MissionController::_cameraFeedback(QGeoCoordinate imageCoordinate, int index)
{
    Q_UNUSED(index);
    if (!_editMode) {
        _cameraPoints.append(new QGCQGeoCoordinate(imageCoordinate, this));
    }
}

void MissionController::clearCameraPoints(void)
{
    _cameraPoints.clearAndDeleteContents();
}