MissionController.cc 75.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
#include "MissionCommandUIInfo.h"
12 13 14 15
#include "MissionController.h"
#include "MultiVehicleManager.h"
#include "MissionManager.h"
#include "CoordinateVector.h"
16
#include "FirmwarePlugin.h"
17
#include "QGCApplication.h"
18
#include "SimpleMissionItem.h"
19
#include "SurveyMissionItem.h"
20
#include "FixedWingLandingComplexItem.h"
21
#include "StructureScanComplexItem.h"
22
#include "StructureScanComplexItem.h"
23
#include "JsonHelper.h"
24
#include "ParameterManager.h"
25
#include "QGroundControlQmlGlobal.h"
26
#include "SettingsManager.h"
27
#include "AppSettings.h"
28
#include "MissionSettingsItem.h"
29
#include "QGCQGeoCoordinate.h"
30
#include "PlanMasterController.h"
31
#include "KML.h"
32

33
#ifndef __mobile__
34
#include "MainWindow.h"
35
#include "QGCQFileDialog.h"
36 37
#endif

38 39
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

56 57 58
MissionController::MissionController(PlanMasterController* masterController, QObject *parent)
    : PlanElementController(masterController, parent)
    , _missionManager(_managerVehicle->missionManager())
59
    , _visualItems(NULL)
60
    , _settingsItem(NULL)
61
    , _firstItemsFromVehicle(false)
DonLakeFlyer's avatar
DonLakeFlyer committed
62
    , _itemsRequested(false)
63 64
    , _surveyMissionItemName(tr("Survey"))
    , _fwLandingMissionItemName(tr("Fixed Wing Landing"))
65
    , _structureScanMissionItemName(tr("Structure Scan"))
66
    , _appSettings(qgcApp()->toolbox()->settingsManager()->appSettings())
67
    , _progressPct(0)
68
{
69
    _resetMissionFlightStatus();
70
    managerVehicleChanged(_managerVehicle);
71 72 73 74
}

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

76 77
}

78 79 80 81 82 83 84 85 86
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;
87 88 89
    _missionFlightStatus.cruiseSpeed =          _controllerVehicle->defaultCruiseSpeed();
    _missionFlightStatus.hoverSpeed =           _controllerVehicle->defaultHoverSpeed();
    _missionFlightStatus.vehicleSpeed =         _controllerVehicle->multiRotor() || _managerVehicle->vtol() ? _missionFlightStatus.hoverSpeed : _missionFlightStatus.cruiseSpeed;
90
    _missionFlightStatus.vehicleYaw =           0.0;
91 92 93 94 95 96 97 98 99 100 101 102 103
    _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;

104 105 106 107
    _controllerVehicle->firmwarePlugin()->batteryConsumptionData(_controllerVehicle, _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);
108
    }
109 110 111 112 113 114 115 116 117 118 119

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

120 121
}

122 123
void MissionController::start(bool editMode)
{
124 125
    qCDebug(MissionControllerLog) << "start editMode" << editMode;

126
    PlanElementController::start(editMode);
127 128 129 130 131
    _init();
}

void MissionController::_init(void)
{
132
    // We start with an empty mission
133
    _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
134
    _addMissionSettings(_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";

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

153
        QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
154
        const QList<MissionItem*>& newMissionItems = _missionManager->missionItems();
155 156 157
        qCDebug(MissionControllerLog) << "loading from vehicle: count"<< newMissionItems.count();

        int i = 0;
158
        if (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() && newMissionItems.count() != 0) {
159
            // First item is fake home position
DonLakeFlyer's avatar
DonLakeFlyer committed
160
            _addMissionSettings(newControllerMissionItems, false /* addToCenter */);
161
            MissionSettingsItem* settingsItem = newControllerMissionItems->value<MissionSettingsItem*>(0);
162 163 164 165
            if (!settingsItem) {
                qWarning() << "First item is not settings item";
                return;
            }
166 167 168 169
            MissionItem* fakeHomeItem = newMissionItems[0];
            if (fakeHomeItem->coordinate().latitude() != 0 || fakeHomeItem->coordinate().longitude() != 0) {
                settingsItem->setCoordinate(fakeHomeItem->coordinate());
            }
170 171
            i = 1;
        }
172

173 174
        for (; i<newMissionItems.count(); i++) {
            const MissionItem* missionItem = newMissionItems[i];
175
            newControllerMissionItems->append(new SimpleMissionItem(_controllerVehicle, *missionItem, this));
176 177 178
        }

        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
179
        _visualItems->deleteLater();
180
        _settingsItem = NULL;
181 182
        _visualItems = NULL;
        _updateContainsItems(); // This will clear containsItems which will be set again below. This will re-pop Start Mission confirmation.
183 184
        _visualItems = newControllerMissionItems;

185
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
DonLakeFlyer's avatar
DonLakeFlyer committed
186
            _addMissionSettings(_visualItems, _editMode && _visualItems->count() > 0 /* addToCenter */);
187 188
        }

189
        if (_editMode) {
190
            MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
191
        }
192

193
        _initAllVisualItems();
194
        _updateContainsItems();
195
        emit newItemsFromVehicle();
196
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
197
    _itemsRequested = false;
198 199
}

200
void MissionController::loadFromVehicle(void)
201
{
DonLakeFlyer's avatar
DonLakeFlyer committed
202 203 204 205 206 207 208 209
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::loadFromVehicle called while offline";
    } else if (syncInProgress()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::loadFromVehicle called while syncInProgress";
    } else {
        _itemsRequested = true;
        _managerVehicle->missionManager()->loadFromVehicle();
    }
210 211
}

212
void MissionController::sendToVehicle(void)
213
{
DonLakeFlyer's avatar
DonLakeFlyer committed
214 215 216 217 218
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::sendToVehicle called while offline";
    } else if (syncInProgress()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::sendToVehicle called while syncInProgress";
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
219
        qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
DonLakeFlyer's avatar
DonLakeFlyer committed
220 221 222 223 224 225 226 227 228
        if (_visualItems->count() == 1) {
            // This prevents us from sending a possibly bogus home position to the vehicle
            QmlObjectListModel emptyModel;
            sendItemsToVehicle(_managerVehicle, &emptyModel);
        } else {
            sendItemsToVehicle(_managerVehicle, _visualItems);
        }
        setDirty(false);
    }
Don Gagne's avatar
Don Gagne committed
229 230
}

231 232 233 234 235
/// 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)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
236 237 238 239
    if (visualMissionItems->count() == 0) {
        return false;
    }

240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255
    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
256
    MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
257 258 259 260 261 262 263
    if (settingsItem) {
        endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
    }

    return endActionSet;
}

264 265 266 267
void MissionController::convertToKMLDocument(QDomDocument& document)
{
    QJsonObject missionJson;
    QmlObjectListModel* visualItems = new QmlObjectListModel();
268
    QList<MissionItem*> missionItems;
269 270 271
    QString error;
    save(missionJson);
    _loadItemsFromJson(missionJson, visualItems, error);
272 273 274 275 276
    _convertToMissionItems(visualItems, missionItems, this);

    if (missionItems.count() == 0) {
        return;
    }
277 278 279 280 281 282 283

    float altitude = missionJson[_jsonPlannedHomePositionKey].toArray()[2].toDouble();

    QString coord;
    QStringList coords;
    // Drop home position
    bool dropPoint = true;
284
    for(const auto& item : missionItems) {
285 286 287 288 289 290 291 292
        if(dropPoint) {
            dropPoint = false;
            continue;
        }
        const MissionCommandUIInfo* uiInfo = \
            qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, item->command());

        if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
yaoling's avatar
yaoling committed
293
            coord = QString::number(item->param6(),'f',7) \
294
                + "," \
yaoling's avatar
yaoling committed
295
                + QString::number(item->param5(),'f',7) \
296
                + "," \
yaoling's avatar
yaoling committed
297
                + QString::number(item->param7() + altitude,'f',2);
298 299 300 301 302 303 304 305
            coords.append(coord);
        }
    }
    Kml kml;
    kml.points(coords);
    kml.save(document);
}

Don Gagne's avatar
Don Gagne committed
306 307 308
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
309
        QList<MissionItem*> rgMissionItems;
310

311
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
312

313
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
314

315 316
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
317
        }
318 319
    }
}
320

321 322 323 324 325 326
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
327 328
        VisualMissionItem* lastItem = _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1);
        return lastItem->lastSequenceNumber() + 1;
329 330 331
    }
}

332
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
333
{
334
    int sequenceNumber = _nextSequenceNumber();
335
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, this);
336
    newItem->setSequenceNumber(sequenceNumber);
337
    newItem->setCoordinate(coordinate);
338 339 340
    newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
    _initVisualItem(newItem);
    if (_visualItems->count() == 1) {
341
        newItem->setCommand(_controllerVehicle->vtol() ? MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF : MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
342
    }
343
    newItem->setDefaultsForCommand();
Don Gagne's avatar
Don Gagne committed
344
    if ((MAV_CMD)newItem->command() == MAV_CMD_NAV_WAYPOINT) {
345 346
        double      prevAltitude;
        MAV_FRAME   prevFrame;
347

348 349 350
        if (_findPreviousAltitude(i, &prevAltitude, &prevFrame)) {
            newItem->missionItem().setFrame(prevFrame);
            newItem->missionItem().setParam7(prevAltitude);
351
        }
352
    }
353
    _visualItems->insert(i, newItem);
354 355 356

    _recalcAll();

357
    return newItem->sequenceNumber();
358 359
}

360
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
361
{
362 363
    ComplexMissionItem* newItem;

364
    int sequenceNumber = _nextSequenceNumber();
365
    if (itemName == _surveyMissionItemName) {
366
        newItem = new SurveyMissionItem(_controllerVehicle, _visualItems);
367
        newItem->setCoordinate(mapCenterCoordinate);
368 369 370 371
        // If the vehicle is known to have a gimbal then we automatically point the gimbal straight down if not already set
        bool rollSupported = false;
        bool pitchSupported = false;
        bool yawSupported = false;
372 373 374
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
        CameraSection* cameraSection = settingsItem->cameraSection();
        // Set camera to photo mode (leave alone if user already specified)
375
        if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
376
            cameraSection->setSpecifyCameraMode(true);
377
            cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
378 379
        }
        // Point gimbal straight down
380
        if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
381 382 383
            // If the user already specified a gimbal angle leave it alone
            if (!cameraSection->specifyGimbal()) {
                cameraSection->setSpecifyGimbal(true);
384
                cameraSection->gimbalPitch()->setRawValue(-90.0);
385 386
            }
        }
387
    } else if (itemName == _fwLandingMissionItemName) {
388
        newItem = new FixedWingLandingComplexItem(_controllerVehicle, _visualItems);
389 390
    } else if (itemName == _structureScanMissionItemName) {
        newItem = new StructureScanComplexItem(_controllerVehicle, _visualItems);
391 392 393 394
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }
395
    newItem->setSequenceNumber(sequenceNumber);
396
    _initVisualItem(newItem);
397

398
    _visualItems->insert(i, newItem);
399 400 401

    _recalcAll();

402
    return newItem->sequenceNumber();
403 404
}

405 406
void MissionController::removeMissionItem(int index)
{
407 408 409 410 411 412
    if (index <= 0 || index >= _visualItems->count()) {
        qWarning() << "MissionController::removeMissionItem called with bad index - count:index" << _visualItems->count() << index;
        return;
    }

    bool surveyRemoved = _visualItems->value<SurveyMissionItem*>(index);
413
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
414

415
    _deinitVisualItem(item);
416
    item->deleteLater();
417

418 419 420 421 422 423 424 425 426 427
    if (surveyRemoved) {
        // Determine if the mission still has another survey in it
        bool foundSurvey = false;
        for (int i=1; i<_visualItems->count(); i++) {
            if (_visualItems->value<SurveyMissionItem*>(i)) {
                foundSurvey = true;
                break;
            }
        }

428
        // If there is no longer a survey item in the mission remove added commands
429 430 431 432
        if (!foundSurvey) {
            bool rollSupported = false;
            bool pitchSupported = false;
            bool yawSupported = false;
433 434
            MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
            CameraSection* cameraSection = settingsItem->cameraSection();
435
            if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
436
                if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
437 438 439
                    cameraSection->setSpecifyGimbal(false);
                }
            }
440
            if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
441 442
                cameraSection->setSpecifyCameraMode(false);
            }
443 444 445
        }
    }

446
    _recalcAll();
447
    setDirty(true);
448 449
}

450
void MissionController::removeAll(void)
451
{
452 453
    if (_visualItems) {
        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
454
        _visualItems->deleteLater();
455
        _settingsItem = NULL;
456
        _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
457
        _addMissionSettings(_visualItems, false /* addToCenter */);
458
        _initAllVisualItems();
459
        setDirty(true);
460
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
461 462 463
    }
}

464
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
465 466 467 468 469 470 471 472 473
{
    // 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)) {
474 475 476
        return false;
    }

477
    // Read complex items
478
    QList<SurveyMissionItem*> surveyItems;
479 480 481 482
    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];
483

484 485 486 487 488
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

489
        SurveyMissionItem* item = new SurveyMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
490 491
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
492
            surveyItems.append(item);
493 494
        } else {
            return false;
495
        }
496
    }
497

498 499 500 501 502
    // 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
503
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
504

505
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
506 507 508 509
    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
510 511
        if (nextComplexItemIndex < surveyItems.count()) {
            SurveyMissionItem* complexItem = surveyItems[nextComplexItemIndex];
512 513 514 515 516 517 518 519 520 521 522 523 524 525

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

526 527 528 529 530
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
531
            const QJsonObject itemObject = itemValue.toObject();
532
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
533
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
534
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
535
                nextSequenceNumber = item->lastSequenceNumber() + 1;
536
                visualItems->append(item);
537 538 539 540
            } else {
                return false;
            }
        }
541
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
542 543

    if (json.contains(_jsonPlannedHomePositionKey)) {
544
        SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
545

Don Gagne's avatar
Don Gagne committed
546
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
547
            MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
548 549 550
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
551 552 553 554
        } else {
            return false;
        }
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
555
        _addMissionSettings(visualItems, true /* addToCenter */);
556 557 558 559 560
    }

    return true;
}

561
bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
562 563 564 565 566 567
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
568
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
569 570
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
571 572 573 574 575 576 577
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

578
    // Mission Settings
579
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
580

581 582
    if (_masterController->offline()) {
        // We only update if offline since if we are online we use the online vehicle settings
583 584 585 586
        appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType((MAV_AUTOPILOT)json[_jsonFirmwareTypeKey].toInt()));
        if (json.contains(_jsonVehicleTypeKey)) {
            appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType((MAV_TYPE)json[_jsonVehicleTypeKey].toInt()));
        }
587
    }
588
    if (json.contains(_jsonCruiseSpeedKey)) {
589
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
590 591
    }
    if (json.contains(_jsonHoverSpeedKey)) {
592
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
593 594
    }

595 596 597 598 599
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
600 601
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627
    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) {
628
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, visualItems);
629
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
630
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
631
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
632 633 634 635 636 637 638 639 640 641 642 643 644 645 646
                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;
647
                SurveyMissionItem* surveyItem = new SurveyMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
648 649 650 651 652 653
                if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(surveyItem);
654
            } else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
655
                qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
656
                FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(_controllerVehicle, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
657 658 659 660 661 662
                if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(landingItem);
663 664 665 666 667 668 669 670 671
            } else if (complexItemType == StructureScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Structure Scan: nextSequenceNumber" << nextSequenceNumber;
                StructureScanComplexItem* structureItem = new StructureScanComplexItem(_controllerVehicle, visualItems);
                if (!structureItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = structureItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Structure Scan load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(structureItem);
672
            } else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
673
                qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
674
                MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
675 676 677 678 679 680
                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
681 682 683 684 685 686 687 688 689 690 691 692 693
            } 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
694
            if ((MAV_CMD)doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717
                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;
}

718 719 720 721 722 723 724 725
bool MissionController::_loadItemsFromJson(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
{
    // 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;
    }

    int fileVersion;
726 727 728 729 730 731
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
732 733

    if (fileVersion == 1) {
734
        return _loadJsonMissionFileV1(json, visualItems, errorString);
735
    } else {
736
        return _loadJsonMissionFileV2(json, visualItems, errorString);
737 738 739
    }
}

740
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
741
{
742 743
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
744 745 746 747 748 749 750 751 752

    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;
753
            plannedHomePositionInFile = true;
754 755 756
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
757
            plannedHomePositionInFile = false;
758 759 760 761
        }
    }

    if (versionOk) {
762
        // Start with planned home in center
DonLakeFlyer's avatar
DonLakeFlyer committed
763
        _addMissionSettings(visualItems, true /* addToCenter */);
764 765
        MissionSettingsItem* settingsItem = visualItems->value<MissionSettingsItem*>(0);

766
        while (!stream.atEnd()) {
767
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
768 769

            if (item->load(stream)) {
770 771 772 773 774 775
                if (firstItem && plannedHomePositionInFile) {
                    settingsItem->setCoordinate(item->coordinate());
                } else {
                    visualItems->append(item);
                }
                firstItem = false;
776
            } else {
777
                errorString = tr("The mission file is corrupted.");
778 779 780 781
                return false;
            }
        }
    } else {
782
        errorString = tr("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
783 784 785
        return false;
    }

786
    if (!plannedHomePositionInFile) {
787 788 789 790 791
        // 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
792 793
            }
        }
794 795 796
    }

    return true;
797 798
}

799
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
800
{
Don Gagne's avatar
Don Gagne committed
801 802 803
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
804
        _settingsItem = NULL;
Don Gagne's avatar
Don Gagne committed
805 806
    }

807
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
808 809

    if (_visualItems->count() == 0) {
DonLakeFlyer's avatar
DonLakeFlyer committed
810
        _addMissionSettings(_visualItems, true /* addToCenter */);
Don Gagne's avatar
Don Gagne committed
811 812
    }

813
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
814

Don Gagne's avatar
Don Gagne committed
815
    _initAllVisualItems();
816
}
817

818 819 820 821 822 823
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

824
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849
        errorString = errorMessage.arg(errorStr);
        return false;
    }
    _initLoadedVisualItems(loadedVisualItems);

    return true;
}

bool MissionController::loadJsonFile(QFile& file, QString& errorString)
{
    QString         errorStr;
    QString         errorMessage = tr("Mission: %1");
    QJsonDocument   jsonDoc;
    QByteArray      bytes = file.readAll();

    if (!JsonHelper::isJsonFile(bytes, jsonDoc, errorStr)) {
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    QJsonObject json = jsonDoc.object();
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);
    if (!_loadItemsFromJson(json, loadedVisualItems, errorStr)) {
        errorString = errorMessage.arg(errorStr);
        return false;
850
    }
851

852 853 854 855 856 857 858 859 860 861 862 863 864
    _initLoadedVisualItems(loadedVisualItems);

    return true;
}

bool MissionController::loadTextFile(QFile& file, QString& errorString)
{
    QString     errorStr;
    QString     errorMessage = tr("Mission: %1");
    QByteArray  bytes = file.readAll();
    QTextStream stream(bytes);

    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);
865
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
866 867 868 869 870 871
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
872
    return true;
873 874
}

875
void MissionController::save(QJsonObject& json)
876
{
877
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
878

879
    // Mission settings
880

881 882 883 884 885 886 887 888
    MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsItem";
        return;
    }
    QJsonValue coordinateValue;
    JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
    json[_jsonPlannedHomePositionKey] = coordinateValue;
889 890 891 892
    json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
893

894
    // Save the visual items
895

896 897 898
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
899

900 901
        visualItem->save(rgJsonMissionItems);
    }
902

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

907 908 909 910 911
        if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
912
        }
913 914
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
915 916 917
        }
    }

918
    json[_jsonItemsKey] = rgJsonMissionItems;
919 920
}

921
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
922
{
Don Gagne's avatar
Don Gagne committed
923
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
924
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
925 926 927 928
    bool            distanceOk =    false;

    // Convert to fixed altitudes

929
    distanceOk = true;
930
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
931 932
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
933
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
934
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
935 936 937
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
938 939 940
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
941
    } else {
Don Gagne's avatar
Don Gagne committed
942
        *altDifference = 0.0;
943
        *azimuth = 0.0;
944
        *distance = 0.0;
945 946 947
    }
}

948
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
949 950 951 952 953 954 955
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

956
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
957 958
}

959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980
void MissionController::_addWaypointLineSegment(CoordVectHashTable& prevItemPairHashTable, VisualItemPair& pair)
{
    if (prevItemPairHashTable.contains(pair)) {
        // Pair already exists and connected, just re-use
        _linesTable[pair] = prevItemPairHashTable.take(pair);
    } else {
        // Create a new segment and wire update notifiers
        auto linevect       = new CoordinateVector(pair.first->isSimpleItem() ? pair.first->coordinate() : pair.first->exitCoordinate(), pair.second->coordinate(), this);
        auto originNotifier = pair.first->isSimpleItem() ? &VisualMissionItem::coordinateChanged : &VisualMissionItem::exitCoordinateChanged;
        auto endNotifier    = &VisualMissionItem::coordinateChanged;

        // Use signals/slots to update the coordinate endpoints
        connect(pair.first,     originNotifier, linevect, &CoordinateVector::setCoordinate1);
        connect(pair.second,    endNotifier,    linevect, &CoordinateVector::setCoordinate2);

        // FIXME: We should ideally have signals for 2D position change, alt change, and 3D position change
        // Not optimal, but still pretty fast, do a full update of range/bearing/altitudes
        connect(pair.second, &VisualMissionItem::coordinateChanged, this, &MissionController::_recalcMissionFlightStatus);
        _linesTable[pair] = linevect;
    }
}

981 982
void MissionController::_recalcWaypointLines(void)
{
983 984 985
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

986
    bool showHomePosition = _settingsItem->coordinate().isValid();
987

988
    qCDebug(MissionControllerLog) << "_recalcWaypointLines showHomePosition" << showHomePosition;
989

Nate Weibley's avatar
Nate Weibley committed
990 991
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
992 993
    _waypointLines.clear();

994 995 996 997 998 999 1000 1001 1002
    bool linkEndToHome;
    SimpleMissionItem* lastItem = _visualItems->value<SimpleMissionItem*>(_visualItems->count() - 1);
    if (lastItem && (int)lastItem->command() == MAV_CMD_NAV_RETURN_TO_LAUNCH) {
        linkEndToHome = true;
    } else {
        linkEndToHome = _settingsItem->missionEndRTL();
    }

    bool linkStartToHome = false;
1003 1004 1005 1006
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));


1007
        // If we still haven't found the first coordinate item and we hit a takeoff command, link back to home
1008 1009
        if (firstCoordinateItem &&
                item->isSimpleItem() &&
1010 1011
                (qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF ||
                 qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) {
1012
            linkStartToHome = true;
1013 1014 1015 1016 1017 1018
        }

        if (item->specifiesCoordinate()) {
            if (!item->isStandaloneCoordinate()) {
                firstCoordinateItem = false;
                VisualItemPair pair(lastCoordinateItem, item);
1019 1020
                if (lastCoordinateItem != _settingsItem || (showHomePosition && linkStartToHome)) {
                    _addWaypointLineSegment(old_table, pair);
1021 1022 1023 1024 1025
                }
                lastCoordinateItem = item;
            }
        }
    }
1026 1027 1028 1029
    if (linkEndToHome && lastCoordinateItem != _settingsItem && showHomePosition) {
        VisualItemPair pair(lastCoordinateItem, _settingsItem);
        _addWaypointLineSegment(old_table, pair);
    }
1030 1031 1032 1033

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1034 1035
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
1036 1037 1038 1039 1040 1041 1042 1043 1044 1045
            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
1046
    _recalcMissionFlightStatus();
1047 1048 1049 1050

    emit waypointLinesChanged();
}

1051 1052 1053 1054 1055 1056
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);
1057
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080
            _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);
}

1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127
/// Adds additional time to a mission as specified by the command
void MissionController::_addCommandTimeDelay(SimpleMissionItem* simpleItem, bool vtolInHover)
{
    double seconds = 0;

    if (!simpleItem) {
        return;
    }

    // This routine is currently quite minimal and only handles the simple cases.
    switch ((int)simpleItem->command()) {
    case MAV_CMD_NAV_WAYPOINT:
    case MAV_CMD_CONDITION_DELAY:
        seconds = simpleItem->missionItem().param1();
        break;
    }

    _addTimeDistance(vtolInHover, 0, 0, seconds, 0, -1);
}

/// Adds the specified time to the appropriate hover or cruise time values.
///     @param vtolInHover true: vtol is currrent in hover mode
///     @param hoverTime    Amount of time tp add to hover
///     @param cruiseTime   Amount of time to add to cruise
///     @param extraTime    Amount of additional time to add to hover/cruise
///     @param seqNum       Sequence number of waypoint for these values, -1 for no waypoint associated
void MissionController::_addTimeDistance(bool vtolInHover, double hoverTime, double cruiseTime, double extraTime, double distance, int seqNum)
{
    if (_controllerVehicle->vtol()) {
        if (vtolInHover) {
            _addHoverTime(hoverTime, distance, seqNum);
            _addHoverTime(extraTime, 0, -1);
        } else {
            _addCruiseTime(cruiseTime, distance, seqNum);
            _addCruiseTime(extraTime, 0, -1);
        }
    } else {
        if (_controllerVehicle->multiRotor()) {
            _addHoverTime(hoverTime, distance, seqNum);
            _addHoverTime(extraTime, 0, -1);
        } else {
            _addCruiseTime(cruiseTime, distance, seqNum);
            _addCruiseTime(extraTime, 0, -1);
        }
    }
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1128
void MissionController::_recalcMissionFlightStatus()
1129
{
1130
    if (!_visualItems->count()) {
1131
        return;
1132
    }
1133 1134 1135 1136

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

1137
    bool showHomePosition = _settingsItem->coordinate().isValid();
1138

DonLakeFlyer's avatar
DonLakeFlyer committed
1139
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1140

1141 1142 1143
    // 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.
1144

1145
    // No values for first item
1146
    lastCoordinateItem->setAltDifference(0.0);
1147
    lastCoordinateItem->setAzimuth(0.0);
1148
    lastCoordinateItem->setDistance(0.0);
1149

1150 1151
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1152 1153
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1154

1155
    _resetMissionFlightStatus();
1156

DonLakeFlyer's avatar
DonLakeFlyer committed
1157
    bool vtolInHover = true;
1158
    bool linkStartToHome = false;
1159 1160 1161 1162 1163 1164 1165 1166 1167 1168
    bool linkEndToHome = false;

    if (showHomePosition) {
        SimpleMissionItem* lastItem = _visualItems->value<SimpleMissionItem*>(_visualItems->count() - 1);
        if (lastItem && (int)lastItem->command() == MAV_CMD_NAV_RETURN_TO_LAUNCH) {
            linkEndToHome = true;
        } else {
            linkEndToHome = _settingsItem->missionEndRTL();
        }
    }
1169

DonLakeFlyer's avatar
DonLakeFlyer committed
1170
    for (int i=0; i<_visualItems->count(); i++) {
1171
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1172 1173 1174
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1175 1176
        // Assume the worst
        item->setAzimuth(0.0);
1177
        item->setDistance(0.0);
1178

DonLakeFlyer's avatar
DonLakeFlyer committed
1179 1180 1181
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1182
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1183
                _missionFlightStatus.hoverSpeed = newSpeed;
1184
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1185 1186
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1187
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1188
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1189
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1190 1191
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1192
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1193 1194 1195 1196
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1197
        if (_managerVehicle->vehicleYawsToNextWaypointInMission()) {
1198 1199 1200 1201 1202
            // We current only support gimbal display in this mode
            double gimbalYaw = item->specifiedGimbalYaw();
            if (!qIsNaN(gimbalYaw)) {
                _missionFlightStatus.gimbalYaw = gimbalYaw;
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1203 1204 1205 1206 1207
        }

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

1210 1211 1212
        // 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) {
1213
                linkStartToHome = true;
1214 1215 1216 1217 1218 1219 1220
                if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
                    // We have to special case takeoff, assuming vehicle takes off straight up to specified altitude
                    double azimuth, distance, altDifference;
                    _calcPrevWaypointValues(homePositionAltitude, _settingsItem, simpleItem, &azimuth, &distance, &altDifference);
                    double takeoffTime = qAbs(altDifference) / _appSettings->offlineEditingAscentSpeed()->rawValue().toDouble();
                    _addHoverTime(takeoffTime, 0, -1);
                }
1221 1222 1223 1224
            }
        }

        // Update VTOL state
1225
        if (simpleItem && _controllerVehicle->vtol()) {
1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239
            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;
1240 1241
                }
            }
1242 1243 1244
                break;
            default:
                break;
1245
            }
Don Gagne's avatar
Don Gagne committed
1246 1247
        }

1248 1249 1250
        // Check for command specific time delays
        _addCommandTimeDelay(simpleItem, vtolInHover);

1251
        if (item->specifiesCoordinate()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1252 1253
            // Update vehicle yaw assuming direction to next waypoint
            if (item != lastCoordinateItem) {
1254 1255
                _missionFlightStatus.vehicleYaw = lastCoordinateItem->exitCoordinate().azimuthTo(item->coordinate());
                lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
DonLakeFlyer's avatar
DonLakeFlyer committed
1256 1257
            }

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

1260
            double absoluteAltitude = item->coordinate().altitude();
1261
            if (item->coordinateHasRelativeAltitude()) {
1262 1263 1264 1265 1266
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1267 1268 1269 1270
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1271 1272 1273
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1274
                firstCoordinateItem = false;
1275
                if (lastCoordinateItem != _settingsItem || linkStartToHome) {
1276 1277
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1278

1279
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1280 1281 1282
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1283

1284
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1285

DonLakeFlyer's avatar
DonLakeFlyer committed
1286 1287 1288
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1289
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1290
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1291

1292
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1293 1294
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1295
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1296

1297 1298
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1299 1300
                    double extraTime = complexItem->additionalTimeDelay();
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, extraTime, distance, item->sequenceNumber());
1301
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1302 1303

                item->setMissionFlightStatus(_missionFlightStatus);
1304
            }
1305 1306

            lastCoordinateItem = item;
1307 1308
        }
    }
1309
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1310

1311 1312 1313 1314 1315 1316 1317 1318
    if (linkEndToHome && lastCoordinateItem != _settingsItem) {
        double azimuth, distance, altDifference;
        _calcPrevWaypointValues(homePositionAltitude, lastCoordinateItem, _settingsItem, &azimuth, &distance, &altDifference);

        // Calculate time/distance
        double hoverTime = distance / _missionFlightStatus.hoverSpeed;
        double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
        double landTime = qAbs(altDifference) / _appSettings->offlineEditingDescentSpeed()->rawValue().toDouble();
1319
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1320 1321
    }

1322 1323 1324
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1325

DonLakeFlyer's avatar
DonLakeFlyer committed
1326 1327 1328 1329 1330 1331 1332
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1333 1334
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1335

1336 1337
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1338 1339
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1340 1341 1342

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1343
            if (item->coordinateHasRelativeAltitude()) {
1344 1345 1346 1347
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1348
                item->setTerrainPercent(qQNaN());
1349 1350
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1351 1352 1353
                if (!qIsNaN(item->terrainAltitude())) {
                    item->setTerrainPercent((item->terrainAltitude() - minAltSeen) / altRange);
                }
1354
            }
1355 1356 1357 1358
        }
    }
}

1359 1360 1361
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1362 1363 1364 1365 1366 1367
    // 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));

1368 1369
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1370 1371 1372
    }
}

1373 1374 1375
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1376
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1377 1378 1379

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

1380 1381
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1382 1383 1384 1385 1386

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1387
        } else if (item->isSimpleItem()) {
1388 1389 1390 1391 1392
            currentParentItem->childItems()->append(item);
        }
    }
}

1393 1394 1395 1396 1397 1398
void MissionController::_setPlannedHomePositionFromFirstCoordinate(void)
{
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1399
    // Set the planned home position to be a delta from first coordinate
1400 1401 1402 1403 1404 1405 1406 1407 1408 1409
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

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


1410 1411
void MissionController::_recalcAll(void)
{
1412 1413 1414
    if (_editMode) {
        _setPlannedHomePositionFromFirstCoordinate();
    }
1415
    _recalcSequence();
1416 1417 1418 1419
    _recalcChildItems();
    _recalcWaypointLines();
}

1420
/// Initializes a new set of mission items
1421
void MissionController::_initAllVisualItems(void)
1422
{
1423 1424
    // Setup home position at index 0

1425 1426 1427
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1428 1429
        return;
    }
1430 1431 1432
    if (_editMode) {
        _settingsItem->setIsCurrentItem(true);
    }
1433

1434
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1435
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1436
    }
1437

1438 1439 1440
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1441

1442 1443 1444 1445
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1446

1447
    _recalcAll();
1448

1449
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1450 1451 1452
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1453
    emit containsItemsChanged(containsItems());
1454
    emit plannedHomePositionChanged(plannedHomePosition());
1455

1456
    setDirty(false);
1457 1458
}

1459
void MissionController::_deinitAllVisualItems(void)
1460
{
1461 1462 1463
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1464 1465
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1466 1467
    }

1468
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1469
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1470 1471
}

1472
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1473
{
1474
    setDirty(false);
1475

1476
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1477 1478
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1479 1480
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1481
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1482
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1483

1484 1485 1486 1487 1488 1489 1490 1491
    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";
        }
1492 1493
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1494
        if (complexItem) {
1495
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
1496
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
1497
            connect(complexItem, &ComplexMissionItem::additionalTimeDelayChanged,   this, &MissionController::_recalcMissionFlightStatus);
1498 1499 1500
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1501
    }
1502 1503
}

1504
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1505
{
1506 1507
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1508 1509
}

1510
void MissionController::_itemCommandChanged(void)
1511
{
1512 1513
    _recalcChildItems();
    _recalcWaypointLines();
1514 1515
}

1516
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1517
{
1518 1519 1520 1521 1522 1523
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1524

1525 1526
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1527
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1528 1529
        return;
    }
1530

1531 1532
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1533 1534
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1535 1536 1537 1538 1539
    connect(_missionManager, &MissionManager::inProgressChanged,        this, &MissionController::_inProgressChanged);
    connect(_missionManager, &MissionManager::progressPct,              this, &MissionController::_progressPctChanged);
    connect(_missionManager, &MissionManager::currentIndexChanged,      this, &MissionController::_currentMissionIndexChanged);
    connect(_missionManager, &MissionManager::lastCurrentIndexChanged,  this, &MissionController::resumeMissionIndexChanged);
    connect(_missionManager, &MissionManager::resumeMissionReady,       this, &MissionController::resumeMissionReady);
1540
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1541 1542 1543 1544
    connect(_managerVehicle, &Vehicle::homePositionChanged,             this, &MissionController::_managerVehicleHomePositionChanged);
    connect(_managerVehicle, &Vehicle::defaultCruiseSpeedChanged,       this, &MissionController::_recalcMissionFlightStatus);
    connect(_managerVehicle, &Vehicle::defaultHoverSpeedChanged,        this, &MissionController::_recalcMissionFlightStatus);
    connect(_managerVehicle, &Vehicle::vehicleTypeChanged,              this, &MissionController::complexMissionItemNamesChanged);
1545

1546 1547
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1548
    }
1549

1550
    emit complexMissionItemNamesChanged();
1551
    emit resumeMissionIndexChanged();
1552 1553
}

1554
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1555
{
1556 1557
    if (_visualItems) {
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1558
        if (settingsItem) {
1559
            settingsItem->setHomePositionFromVehicle(homePosition);
1560
        } else {
1561
            qWarning() << "First item is not MissionSettingsItem";
1562
        }
1563 1564 1565
        // Don't let this trip the dirty bit. Otherwise plan will keep getting marked dirty if vehicle home
        // changes.
        _visualItems->setDirty(false);
1566
    }
1567 1568 1569
}

void MissionController::_inProgressChanged(bool inProgress)
1570
{
1571
    emit syncInProgressChanged(inProgress);
1572
}
1573

1574
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
1575
{
1576 1577 1578
    bool        found = false;
    double      foundAltitude;
    MAV_FRAME   foundFrame;
1579

1580 1581 1582 1583 1584 1585
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1588 1589 1590
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1591
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
1592 1593 1594
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1595
                    break;
1596 1597
                }
            }
1598 1599 1600
        }
    }

1601
    if (found) {
1602 1603
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1604 1605 1606
    }

    return found;
1607
}
1608 1609 1610 1611 1612 1613 1614 1615 1616 1617 1618 1619 1620

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

1621
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1622
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1623
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1624
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
1625

Don Gagne's avatar
Don Gagne committed
1626 1627
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1628
    visualItems->insert(0, settingsItem);
1629

1630 1631 1632 1633 1634 1635 1636 1637 1638 1639 1640 1641 1642 1643 1644 1645 1646 1647 1648 1649 1650 1651 1652 1653 1654
    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;
                    }
1655 1656
                }
            }
1657

1658 1659 1660
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1661
        }
Don Gagne's avatar
Don Gagne committed
1662 1663
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1664 1665
    }
}
1666

1667
int MissionController::resumeMissionIndex(void) const
1668
{
1669

1670
    int resumeIndex = 0;
1671

1672
    if (!_editMode) {
1673
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1674
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1675 1676
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1677 1678
        } else {
            resumeIndex = 0;
1679 1680 1681 1682 1683
        }
    }

    return resumeIndex;
}
1684

1685 1686 1687 1688 1689 1690 1691 1692 1693 1694 1695 1696 1697
int MissionController::currentMissionIndex(void) const
{
    if (_editMode) {
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

1698
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1699 1700
{
    if (!_editMode) {
1701
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1702 1703 1704
            sequenceNumber++;
        }

1705 1706
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1707 1708
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1709
        emit currentMissionIndexChanged(currentMissionIndex());
1710 1711
    }
}
1712

1713
bool MissionController::syncInProgress(void) const
1714
{
1715
    return _missionManager->inProgress();
1716 1717 1718 1719 1720 1721 1722 1723 1724 1725 1726 1727
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1728
    }
1729
}
1730

1731 1732
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1733 1734 1735
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, vehicle);

1736 1737 1738 1739 1740 1741
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1742
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
1743 1744 1745
        if (settingsItem) {
            scanIndex++;
            settingsItem->scanForMissionSettings(visualItems, scanIndex);
1746 1747 1748 1749
            continue;
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1750
        if (simpleItem) {
1751 1752 1753 1754 1755
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
1756 1757 1758
        }
    }
}
1759 1760 1761 1762 1763 1764 1765 1766 1767 1768 1769 1770 1771

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

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

void MissionController::removeAllFromVehicle(void)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1772 1773 1774 1775 1776 1777 1778 1779
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::removeAllFromVehicle called while offline";
    } else if (syncInProgress()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::removeAllFromVehicle called while syncInProgress";
    } else {
        _itemsRequested = true;
        _missionManager->removeAll();
    }
1780
}
1781 1782 1783 1784 1785 1786

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

    complexItems.append(_surveyMissionItemName);
1787
    if (_controllerVehicle->fixedWing()) {
1788 1789
        complexItems.append(_fwLandingMissionItemName);
    }
1790 1791 1792
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
        complexItems.append(_structureScanMissionItemName);
    }
1793 1794 1795

    return complexItems;
}
1796

1797 1798
void MissionController::resumeMission(int resumeIndex)
{
1799
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1800 1801
        resumeIndex--;
    }
1802
    _missionManager->generateResumeMission(resumeIndex);
1803
}
1804 1805 1806 1807 1808 1809 1810 1811 1812

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1813 1814 1815 1816 1817 1818 1819 1820 1821 1822

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

1824 1825 1826 1827 1828 1829 1830
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
1831 1832 1833 1834 1835 1836

void MissionController::_visualItemsDirtyChanged(bool dirty)
{
    // We could connect signal to signal and not need this but this is handy for setting a breakpoint on
    emit dirtyChanged(dirty);
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1837 1838 1839

bool MissionController::showPlanFromManagerVehicle (void)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1840
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle" << _editMode;
DonLakeFlyer's avatar
DonLakeFlyer committed
1841 1842
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
1843
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
1844 1845 1846 1847 1848 1849 1850 1851 1852 1853 1854 1855 1856 1857 1858 1859 1860 1861 1862
    } else {
        if (!_managerVehicle->initialPlanRequestComplete()) {
            // The vehicle hasn't completed initial load, we can just wait for newMissionItemsAvailable to be signalled automatically
            qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle: !initialPlanRequestComplete, wait for signal";
            return true;
        } else if (syncInProgress()) {
            // If the sync is already in progress, newMissionItemsAvailable will be signalled automatically when it is done. So no need to do anything.
            qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle: syncInProgress wait for signal";
            return true;
        } else {
            // Fake a _newMissionItemsAvailable with the current items
            qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle: sync complete simulate signal";
            _itemsRequested = true;
            _newMissionItemsAvailableFromVehicle(false /* removeAllRequested */);
            return false;
        }
    }
}

1863
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1864
{
1865 1866
    // Fly view always reloads on send complete
    if (!error && !_editMode) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1867 1868 1869 1870
        showPlanFromManagerVehicle();
    }
}

1871
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1872
{
1873 1874 1875 1876
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1877
}