MissionController.cc 76.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
    , _currentPlanViewIndex(-1)
    , _currentPlanViewItem(NULL)
70
{
71
    _resetMissionFlightStatus();
72
    managerVehicleChanged(_managerVehicle);
73 74 75 76
}

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

78 79
}

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

106 107 108 109
    _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);
110
    }
111 112 113 114 115 116 117 118 119 120 121

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

122 123
}

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

128
    PlanElementController::start(editMode);
129 130 131 132 133
    _init();
}

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

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

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

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

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

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

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

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

191
        if (_editMode) {
192
            MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
193
        }
194

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

202
void MissionController::loadFromVehicle(void)
203
{
DonLakeFlyer's avatar
DonLakeFlyer committed
204 205 206 207 208 209 210 211
    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();
    }
212 213
}

214
void MissionController::sendToVehicle(void)
215
{
DonLakeFlyer's avatar
DonLakeFlyer committed
216 217 218 219 220
    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
221
        qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
DonLakeFlyer's avatar
DonLakeFlyer committed
222 223 224 225 226 227 228 229 230
        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
231 232
}

233 234 235 236 237
/// 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
238 239 240 241
    if (visualMissionItems->count() == 0) {
        return false;
    }

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

    return endActionSet;
}

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

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

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

    QString coord;
    QStringList coords;
    // Drop home position
    bool dropPoint = true;
286
    for(const auto& item : missionItems) {
287 288 289 290 291 292 293 294
        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
295
            coord = QString::number(item->param6(),'f',7) \
296
                + "," \
yaoling's avatar
yaoling committed
297
                + QString::number(item->param5(),'f',7) \
298
                + "," \
yaoling's avatar
yaoling committed
299
                + QString::number(item->param7() + altitude,'f',2);
300 301 302 303 304 305 306 307
            coords.append(coord);
        }
    }
    Kml kml;
    kml.points(coords);
    kml.save(document);
}

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

313
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
314

315
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
316

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

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

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

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

    _recalcAll();

359
    return newItem->sequenceNumber();
360 361
}

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

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

400
    _visualItems->insert(i, newItem);
401 402 403

    _recalcAll();

404
    return newItem->sequenceNumber();
405 406
}

407 408
void MissionController::removeMissionItem(int index)
{
409 410 411 412 413 414
    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);
415
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
416

417
    _deinitVisualItem(item);
418
    item->deleteLater();
419

420 421 422 423 424 425 426 427 428 429
    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;
            }
        }

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

448
    _recalcAll();
449
    setDirty(true);
450 451
}

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

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

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

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

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

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

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

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

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

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

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

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

    return true;
}

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

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

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

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

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

720 721 722 723 724 725 726 727
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;
728 729 730 731 732 733
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
734 735

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

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

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

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

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

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

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

    return true;
799 800
}

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

809
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
810 811

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

815
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
816

Don Gagne's avatar
Don Gagne committed
817
    _initAllVisualItems();
818
}
819

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

826
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851
        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;
852
    }
853

854 855 856 857 858 859 860 861 862 863 864 865 866
    _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);
867
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
868 869 870 871 872 873
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
874
    return true;
875 876
}

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

881
    // Mission settings
882

883 884 885 886 887 888 889 890
    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;
891 892 893 894
    json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
895

896
    // Save the visual items
897

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

902 903
        visualItem->save(rgJsonMissionItems);
    }
904

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

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

920
    json[_jsonItemsKey] = rgJsonMissionItems;
921 922
}

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

    // Convert to fixed altitudes

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

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

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

    distanceOk = true;

958
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
959 960
}

961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982
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;
    }
}

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

988
    bool showHomePosition = _settingsItem->coordinate().isValid();
989

990
    qCDebug(MissionControllerLog) << "_recalcWaypointLines showHomePosition" << showHomePosition;
991

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

996 997 998 999 1000 1001 1002 1003 1004
    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;
1005 1006 1007 1008
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));


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

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

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

    emit waypointLinesChanged();
}

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

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 1128 1129
/// 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
1130
void MissionController::_recalcMissionFlightStatus()
1131
{
1132
    if (!_visualItems->count()) {
1133
        return;
1134
    }
1135 1136 1137 1138

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

1139
    bool showHomePosition = _settingsItem->coordinate().isValid();
1140

DonLakeFlyer's avatar
DonLakeFlyer committed
1141
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1142

1143 1144 1145
    // 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.
1146

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

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

1157
    _resetMissionFlightStatus();
1158

DonLakeFlyer's avatar
DonLakeFlyer committed
1159
    bool vtolInHover = true;
1160
    bool linkStartToHome = false;
1161 1162 1163 1164 1165 1166 1167 1168 1169 1170
    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();
        }
    }
1171

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

1177 1178
        // Assume the worst
        item->setAzimuth(0.0);
1179
        item->setDistance(0.0);
1180

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

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

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

1212 1213 1214
        // 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) {
1215
                linkStartToHome = true;
1216 1217 1218 1219 1220 1221 1222
                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);
                }
1223 1224 1225 1226
            }
        }

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

1250 1251 1252
        // Check for command specific time delays
        _addCommandTimeDelay(simpleItem, vtolInHover);

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

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

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

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

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

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

1286
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1287

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

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

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

                item->setMissionFlightStatus(_missionFlightStatus);
1306
            }
1307 1308

            lastCoordinateItem = item;
1309 1310
        }
    }
1311
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1312

1313 1314 1315 1316 1317 1318 1319 1320
    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();
1321
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1322 1323
    }

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

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

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

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

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

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

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

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

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

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

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

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

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


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

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

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

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

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

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

1449
    _recalcAll();
1450

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

    emit visualItemsChanged();
1455
    emit containsItemsChanged(containsItems());
1456
    emit plannedHomePositionChanged(plannedHomePosition());
1457

1458
    setDirty(false);
1459 1460
}

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

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

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

1474
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1475
{
1476
    setDirty(false);
1477

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

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

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

1512
void MissionController::_itemCommandChanged(void)
1513
{
1514 1515
    _recalcChildItems();
    _recalcWaypointLines();
1516 1517
}

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

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

1533 1534
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1535 1536
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1537 1538 1539 1540 1541
    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);
1542
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1543 1544 1545 1546
    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);
1547

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

1552
    emit complexMissionItemNamesChanged();
1553
    emit resumeMissionIndexChanged();
1554 1555
}

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

void MissionController::_inProgressChanged(bool inProgress)
1572
{
1573
    emit syncInProgressChanged(inProgress);
1574
}
1575

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

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

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

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

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

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

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

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

Don Gagne's avatar
Don Gagne committed
1628 1629
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1630
    visualItems->insert(0, settingsItem);
1631

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

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

1669
int MissionController::resumeMissionIndex(void) const
1670
{
1671

1672
    int resumeIndex = 0;
1673

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

    return resumeIndex;
}
1686

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

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

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

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

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


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

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

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

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

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

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

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
1774 1775 1776 1777 1778 1779 1780 1781
    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();
    }
1782
}
1783 1784 1785 1786 1787 1788

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

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

    return complexItems;
}
1798

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

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

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

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

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
1839 1840 1841

bool MissionController::showPlanFromManagerVehicle (void)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1842
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle" << _editMode;
DonLakeFlyer's avatar
DonLakeFlyer committed
1843 1844
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
1845
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
1846 1847 1848 1849 1850 1851 1852 1853 1854 1855 1856 1857 1858 1859 1860 1861 1862 1863 1864
    } 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;
        }
    }
}

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

1873
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1874
{
1875 1876 1877 1878
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1879
}
1880 1881 1882 1883 1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895 1896 1897 1898 1899 1900 1901 1902 1903 1904 1905 1906 1907 1908 1909

int MissionController::currentPlanViewIndex(void) const
{
    return _currentPlanViewIndex;
}

VisualMissionItem* MissionController::currentPlanViewItem(void) const
{
    return _currentPlanViewItem;
}

void MissionController::setCurrentPlanViewIndex(int sequenceNumber, bool force)
{
    if(_visualItems && (force || sequenceNumber != _currentPlanViewIndex)) {
        _currentPlanViewItem  = NULL;
        _currentPlanViewIndex = -1;
        for (int i = 0; i < _visualItems->count(); i++) {
            VisualMissionItem* pVI = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
            if (pVI && pVI->sequenceNumber() == sequenceNumber) {
                pVI->setIsCurrentItem(true);
                _currentPlanViewItem  = pVI;
                _currentPlanViewIndex = sequenceNumber;
            } else {
                pVI->setIsCurrentItem(false);
            }
        }
        emit currentPlanViewIndexChanged();
        emit currentPlanViewItemChanged();
    }
}