MissionController.cc 74.5 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
9 10


11
#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 "JsonHelper.h"
22
#include "ParameterManager.h"
23
#include "QGroundControlQmlGlobal.h"
24
#include "SettingsManager.h"
25
#include "AppSettings.h"
26
#include "MissionSettingsItem.h"
27
#include "QGCQGeoCoordinate.h"
28
#include "PlanMasterController.h"
29
#include "KML.h"
30

31
#ifndef __mobile__
32
#include "MainWindow.h"
33
#include "QGCQFileDialog.h"
34 35
#endif

36 37
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

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

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

73 74
}

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

    // Battery information

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

101 102 103 104
    _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);
105
    }
106 107 108 109 110 111 112 113 114 115 116

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

117 118
}

119 120
void MissionController::start(bool editMode)
{
121 122
    qCDebug(MissionControllerLog) << "start editMode" << editMode;

123
    PlanElementController::start(editMode);
124 125 126 127 128
    _init();
}

void MissionController::_init(void)
{
129
    // We start with an empty mission
130
    _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
131
    _addMissionSettings(_visualItems, false /* addToCenter */);
132
    _initAllVisualItems();
133 134
}

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

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

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

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

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

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

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

186
        if (_editMode) {
187
            MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
188
        }
189

190
        _initAllVisualItems();
191
        _updateContainsItems();
192
        emit newItemsFromVehicle();
193
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
194
    _itemsRequested = false;
195 196
}

197
void MissionController::loadFromVehicle(void)
198
{
DonLakeFlyer's avatar
DonLakeFlyer committed
199 200 201 202 203 204 205 206
    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();
    }
207 208
}

209
void MissionController::sendToVehicle(void)
210
{
DonLakeFlyer's avatar
DonLakeFlyer committed
211 212 213 214 215
    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
216
        qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
DonLakeFlyer's avatar
DonLakeFlyer committed
217 218 219 220 221 222 223 224 225
        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
226 227
}

228 229 230 231 232
/// 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
233 234 235 236
    if (visualMissionItems->count() == 0) {
        return false;
    }

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

    return endActionSet;
}

261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298
void MissionController::convertToKMLDocument(QDomDocument& document)
{
    QJsonObject missionJson;
    QmlObjectListModel* visualItems = new QmlObjectListModel();
    QList<MissionItem*> missionItens;
    QString error;
    save(missionJson);
    _loadItemsFromJson(missionJson, visualItems, error);
    _convertToMissionItems(visualItems, missionItens, this);

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

    QString coord;
    QStringList coords;
    // Drop home position
    bool dropPoint = true;
    for(const auto& item : missionItens) {
        if(dropPoint) {
            dropPoint = false;
            continue;
        }
        const MissionCommandUIInfo* uiInfo = \
            qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, item->command());

        if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
            coord = QString::number(item->param6()) \
                + "," \
                + QString::number(item->param5()) \
                + "," \
                + QString::number(item->param7() + altitude);
            coords.append(coord);
        }
    }
    Kml kml;
    kml.points(coords);
    kml.save(document);
}

Don Gagne's avatar
Don Gagne committed
299 300 301
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
302
        QList<MissionItem*> rgMissionItems;
303

304
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
305

306
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
307

308 309
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
310
        }
311 312
    }
}
313

314 315 316 317 318 319
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
320 321
        VisualMissionItem* lastItem = _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1);
        return lastItem->lastSequenceNumber() + 1;
322 323 324
    }
}

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

341 342 343
        if (_findPreviousAltitude(i, &prevAltitude, &prevFrame)) {
            newItem->missionItem().setFrame(prevFrame);
            newItem->missionItem().setParam7(prevAltitude);
344
        }
345
    }
346
    _visualItems->insert(i, newItem);
347 348 349

    _recalcAll();

350
    return newItem->sequenceNumber();
351 352
}

353
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
354
{
355 356
    ComplexMissionItem* newItem;

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

389
    _visualItems->insert(i, newItem);
390 391 392

    _recalcAll();

393
    return newItem->sequenceNumber();
394 395
}

396 397
void MissionController::removeMissionItem(int index)
{
398 399 400 401 402 403
    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);
404
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
405

406
    _deinitVisualItem(item);
407
    item->deleteLater();
408

409 410 411 412 413 414 415 416 417 418
    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;
            }
        }

419
        // If there is no longer a survey item in the mission remove added commands
420 421 422 423
        if (!foundSurvey) {
            bool rollSupported = false;
            bool pitchSupported = false;
            bool yawSupported = false;
424 425
            MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
            CameraSection* cameraSection = settingsItem->cameraSection();
426
            if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
427
                if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
428 429 430
                    cameraSection->setSpecifyGimbal(false);
                }
            }
431
            if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
432 433
                cameraSection->setSpecifyCameraMode(false);
            }
434 435 436
        }
    }

437
    _recalcAll();
438
    setDirty(true);
439 440
}

441
void MissionController::removeAll(void)
442
{
443 444
    if (_visualItems) {
        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
445
        _visualItems->deleteLater();
446
        _settingsItem = NULL;
447
        _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
448
        _addMissionSettings(_visualItems, false /* addToCenter */);
449
        _initAllVisualItems();
450
        setDirty(true);
451
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
452 453 454
    }
}

455
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
456 457 458 459 460 461 462 463 464
{
    // 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)) {
465 466 467
        return false;
    }

468
    // Read complex items
469
    QList<SurveyMissionItem*> surveyItems;
470 471 472 473
    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];
474

475 476 477 478 479
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

480
        SurveyMissionItem* item = new SurveyMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
481 482
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
483
            surveyItems.append(item);
484 485
        } else {
            return false;
486
        }
487
    }
488

489 490 491 492 493
    // 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
494
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
495

496
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
497 498 499 500
    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
501 502
        if (nextComplexItemIndex < surveyItems.count()) {
            SurveyMissionItem* complexItem = surveyItems[nextComplexItemIndex];
503 504 505 506 507 508 509 510 511 512 513 514 515 516

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

517 518 519 520 521
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
522
            const QJsonObject itemObject = itemValue.toObject();
523
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
524
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
525
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
526
                nextSequenceNumber = item->lastSequenceNumber() + 1;
527
                visualItems->append(item);
528 529 530 531
            } else {
                return false;
            }
        }
532
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
533 534

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

Don Gagne's avatar
Don Gagne committed
537
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
538
            MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
539 540 541
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
542 543 544 545
        } else {
            return false;
        }
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
546
        _addMissionSettings(visualItems, true /* addToCenter */);
547 548 549 550 551
    }

    return true;
}

552
bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
553 554 555 556 557 558
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
559
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
560 561
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
562 563 564 565 566 567 568
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

569
    // Mission Settings
570
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
571

572 573
    if (_masterController->offline()) {
        // We only update if offline since if we are online we use the online vehicle settings
574 575 576 577
        appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType((MAV_AUTOPILOT)json[_jsonFirmwareTypeKey].toInt()));
        if (json.contains(_jsonVehicleTypeKey)) {
            appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType((MAV_TYPE)json[_jsonVehicleTypeKey].toInt()));
        }
578
    }
579
    if (json.contains(_jsonCruiseSpeedKey)) {
580
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
581 582
    }
    if (json.contains(_jsonHoverSpeedKey)) {
583
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
584 585
    }

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

700 701 702 703 704 705 706 707
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;
708 709 710 711 712 713
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
714 715

    if (fileVersion == 1) {
716
        return _loadJsonMissionFileV1(json, visualItems, errorString);
717
    } else {
718
        return _loadJsonMissionFileV2(json, visualItems, errorString);
719 720 721
    }
}

722
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
723
{
724 725
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
726 727 728 729 730 731 732 733 734

    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;
735
            plannedHomePositionInFile = true;
736 737 738
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
739
            plannedHomePositionInFile = false;
740 741 742 743
        }
    }

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

748
        while (!stream.atEnd()) {
749
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
750 751

            if (item->load(stream)) {
752 753 754 755 756 757
                if (firstItem && plannedHomePositionInFile) {
                    settingsItem->setCoordinate(item->coordinate());
                } else {
                    visualItems->append(item);
                }
                firstItem = false;
758 759 760 761 762 763
            } else {
                errorString = QStringLiteral("The mission file is corrupted.");
                return false;
            }
        }
    } else {
764
        errorString = QStringLiteral("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
765 766 767
        return false;
    }

768
    if (!plannedHomePositionInFile) {
769 770 771 772 773
        // 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
774 775
            }
        }
776 777 778
    }

    return true;
779 780
}

781
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
782
{
Don Gagne's avatar
Don Gagne committed
783 784 785
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
786
        _settingsItem = NULL;
Don Gagne's avatar
Don Gagne committed
787 788
    }

789
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
790 791

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

795
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
796

Don Gagne's avatar
Don Gagne committed
797
    _initAllVisualItems();
798
}
799

800 801 802 803 804 805
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

806
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831
        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;
832
    }
833

834 835 836 837 838 839 840 841 842 843 844 845 846
    _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);
847
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
848 849 850 851 852 853
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
854
    return true;
855 856
}

857
void MissionController::save(QJsonObject& json)
858
{
859
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
860

861
    // Mission settings
862

863 864 865 866 867 868 869 870
    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;
871 872 873 874
    json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
875

876
    // Save the visual items
877

878 879 880
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
881

882 883
        visualItem->save(rgJsonMissionItems);
    }
884

885 886 887
    // Mission settings has a special case for end mission action
    if (settingsItem) {
        QList<MissionItem*> rgMissionItems;
888

889 890 891 892 893
        if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
894
        }
895 896
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
897 898 899
        }
    }

900
    json[_jsonItemsKey] = rgJsonMissionItems;
901 902
}

903
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
904
{
Don Gagne's avatar
Don Gagne committed
905
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
906
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
907 908 909 910
    bool            distanceOk =    false;

    // Convert to fixed altitudes

911
    distanceOk = true;
912
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
913 914
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
915
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
916
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
917 918 919
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
920 921 922
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
923
    } else {
Don Gagne's avatar
Don Gagne committed
924
        *altDifference = 0.0;
925
        *azimuth = 0.0;
926
        *distance = 0.0;
927 928 929
    }
}

930
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
931 932 933 934 935 936 937
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

938
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
939 940
}

941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962
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;
    }
}

963 964
void MissionController::_recalcWaypointLines(void)
{
965 966 967
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

968
    bool showHomePosition = _settingsItem->coordinate().isValid();
969

970
    qCDebug(MissionControllerLog) << "_recalcWaypointLines showHomePosition" << showHomePosition;
971

Nate Weibley's avatar
Nate Weibley committed
972 973
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
974 975
    _waypointLines.clear();

976 977 978 979 980 981 982 983 984
    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;
985 986 987 988
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));


989
        // If we still haven't found the first coordinate item and we hit a takeoff command, link back to home
990 991
        if (firstCoordinateItem &&
                item->isSimpleItem() &&
992 993
                (qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF ||
                 qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) {
994
            linkStartToHome = true;
995 996 997 998 999 1000
        }

        if (item->specifiesCoordinate()) {
            if (!item->isStandaloneCoordinate()) {
                firstCoordinateItem = false;
                VisualItemPair pair(lastCoordinateItem, item);
1001 1002
                if (lastCoordinateItem != _settingsItem || (showHomePosition && linkStartToHome)) {
                    _addWaypointLineSegment(old_table, pair);
1003 1004 1005 1006 1007
                }
                lastCoordinateItem = item;
            }
        }
    }
1008 1009 1010 1011
    if (linkEndToHome && lastCoordinateItem != _settingsItem && showHomePosition) {
        VisualItemPair pair(lastCoordinateItem, _settingsItem);
        _addWaypointLineSegment(old_table, pair);
    }
1012 1013 1014 1015

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1016 1017
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
1018 1019 1020 1021 1022 1023 1024 1025 1026 1027
            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
1028
    _recalcMissionFlightStatus();
1029 1030 1031 1032

    emit waypointLinesChanged();
}

1033 1034 1035 1036 1037 1038
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);
1039
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062
            _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);
}

1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 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
/// 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
1110
void MissionController::_recalcMissionFlightStatus()
1111
{
1112
    if (!_visualItems->count()) {
1113
        return;
1114
    }
1115 1116 1117 1118

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

1119
    bool showHomePosition = _settingsItem->coordinate().isValid();
1120

DonLakeFlyer's avatar
DonLakeFlyer committed
1121
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1122

1123 1124 1125
    // 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.
1126

1127
    // No values for first item
1128
    lastCoordinateItem->setAltDifference(0.0);
1129
    lastCoordinateItem->setAzimuth(0.0);
1130
    lastCoordinateItem->setDistance(0.0);
1131

1132 1133
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1134 1135
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1136

1137
    _resetMissionFlightStatus();
1138

DonLakeFlyer's avatar
DonLakeFlyer committed
1139
    bool vtolInHover = true;
1140
    bool linkStartToHome = false;
1141 1142 1143 1144 1145 1146 1147 1148 1149 1150
    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();
        }
    }
1151

DonLakeFlyer's avatar
DonLakeFlyer committed
1152
    for (int i=0; i<_visualItems->count(); i++) {
1153
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1154 1155 1156
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1157 1158
        // Assume the worst
        item->setAzimuth(0.0);
1159
        item->setDistance(0.0);
1160

DonLakeFlyer's avatar
DonLakeFlyer committed
1161 1162 1163
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1164
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1165
                _missionFlightStatus.hoverSpeed = newSpeed;
1166
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1167 1168
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1169
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1170
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1171
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1172 1173
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1174
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1175 1176 1177 1178
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1179
        if (_managerVehicle->vehicleYawsToNextWaypointInMission()) {
1180 1181 1182 1183 1184
            // We current only support gimbal display in this mode
            double gimbalYaw = item->specifiedGimbalYaw();
            if (!qIsNaN(gimbalYaw)) {
                _missionFlightStatus.gimbalYaw = gimbalYaw;
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1185 1186 1187 1188 1189
        }

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

1192 1193 1194
        // 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) {
1195
                linkStartToHome = true;
1196 1197 1198 1199 1200 1201 1202
                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);
                }
1203 1204 1205 1206
            }
        }

        // Update VTOL state
1207
        if (simpleItem && _controllerVehicle->vtol()) {
1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221
            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;
1222 1223
                }
            }
1224 1225 1226
                break;
            default:
                break;
1227
            }
Don Gagne's avatar
Don Gagne committed
1228 1229
        }

1230 1231 1232
        // Check for command specific time delays
        _addCommandTimeDelay(simpleItem, vtolInHover);

1233
        if (item->specifiesCoordinate()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1234 1235
            // Update vehicle yaw assuming direction to next waypoint
            if (item != lastCoordinateItem) {
1236 1237
                _missionFlightStatus.vehicleYaw = lastCoordinateItem->exitCoordinate().azimuthTo(item->coordinate());
                lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
DonLakeFlyer's avatar
DonLakeFlyer committed
1238 1239
            }

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

1242
            double absoluteAltitude = item->coordinate().altitude();
1243
            if (item->coordinateHasRelativeAltitude()) {
1244 1245 1246 1247 1248
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1249 1250 1251 1252
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1253 1254 1255
            }

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

1261
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1262 1263 1264
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1265

1266
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1267

DonLakeFlyer's avatar
DonLakeFlyer committed
1268 1269 1270
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1271
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1272
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1273

1274
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1275 1276
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1277
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1278

1279 1280
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1281 1282
                    double extraTime = complexItem->additionalTimeDelay();
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, extraTime, distance, item->sequenceNumber());
1283
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1284 1285

                item->setMissionFlightStatus(_missionFlightStatus);
1286
            }
1287 1288

            lastCoordinateItem = item;
1289 1290
        }
    }
1291
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1292

1293 1294 1295 1296 1297 1298 1299 1300
    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();
1301
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1302 1303
    }

1304 1305 1306
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1307

DonLakeFlyer's avatar
DonLakeFlyer committed
1308 1309 1310 1311 1312 1313 1314
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1315 1316
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1317

1318 1319
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1320 1321
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1322 1323 1324

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1325
            if (item->coordinateHasRelativeAltitude()) {
1326 1327 1328 1329
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1330
                item->setTerrainPercent(qQNaN());
1331 1332
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1333 1334 1335
                if (!qIsNaN(item->terrainAltitude())) {
                    item->setTerrainPercent((item->terrainAltitude() - minAltSeen) / altRange);
                }
1336
            }
1337 1338 1339 1340
        }
    }
}

1341 1342 1343
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1344 1345 1346 1347 1348 1349
    // 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));

1350 1351
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1352 1353 1354
    }
}

1355 1356 1357
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1358
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1359 1360 1361

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

1362 1363
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1364 1365 1366 1367 1368

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1369
        } else if (item->isSimpleItem()) {
1370 1371 1372 1373 1374
            currentParentItem->childItems()->append(item);
        }
    }
}

1375 1376 1377 1378 1379 1380
void MissionController::_setPlannedHomePositionFromFirstCoordinate(void)
{
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1381
    // Set the planned home position to be a delta from first coordinate
1382 1383 1384 1385 1386 1387 1388 1389 1390 1391
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

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


1392 1393
void MissionController::_recalcAll(void)
{
1394 1395 1396
    if (_editMode) {
        _setPlannedHomePositionFromFirstCoordinate();
    }
1397
    _recalcSequence();
1398 1399 1400 1401
    _recalcChildItems();
    _recalcWaypointLines();
}

1402
/// Initializes a new set of mission items
1403
void MissionController::_initAllVisualItems(void)
1404
{
1405 1406
    // Setup home position at index 0

1407 1408 1409
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1410 1411
        return;
    }
1412 1413 1414
    if (_editMode) {
        _settingsItem->setIsCurrentItem(true);
    }
1415

1416
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1417
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1418
    }
1419

1420 1421 1422
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1423

1424 1425 1426 1427
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1428

1429
    _recalcAll();
1430

1431
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1432 1433 1434
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1435
    emit containsItemsChanged(containsItems());
1436
    emit plannedHomePositionChanged(plannedHomePosition());
1437

1438
    setDirty(false);
1439 1440
}

1441
void MissionController::_deinitAllVisualItems(void)
1442
{
1443 1444 1445
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1446 1447
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1448 1449
    }

1450
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1451
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1452 1453
}

1454
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1455
{
1456
    setDirty(false);
1457

1458
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1459 1460
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1461 1462
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1463
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1464
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1465

1466 1467 1468 1469 1470 1471 1472 1473
    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";
        }
1474 1475
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1476
        if (complexItem) {
1477 1478
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
            connect(complexItem, &ComplexMissionItem::additionalTimeDelayChanged,   this, &MissionController::_recalcMissionFlightStatus);
1479 1480 1481
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1482
    }
1483 1484
}

1485
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1486
{
1487 1488
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1489 1490
}

1491
void MissionController::_itemCommandChanged(void)
1492
{
1493 1494
    _recalcChildItems();
    _recalcWaypointLines();
1495 1496
}

1497
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1498
{
1499 1500 1501 1502 1503 1504
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1505

1506 1507
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1508
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1509 1510
        return;
    }
1511

1512 1513
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1514 1515
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1516 1517 1518 1519 1520
    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);
1521
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1522 1523 1524 1525
    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);
1526

1527 1528
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1529
    }
1530

1531
    emit complexMissionItemNamesChanged();
1532
    emit resumeMissionIndexChanged();
1533 1534
}

1535
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1536
{
1537 1538
    if (_visualItems) {
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1539
        if (settingsItem) {
1540
            settingsItem->setHomePositionFromVehicle(homePosition);
1541
        } else {
1542
            qWarning() << "First item is not MissionSettingsItem";
1543
        }
1544 1545 1546 1547
        if (_visualItems->count() == 1) {
            // Don't let this trip the dirty bit
            _visualItems->setDirty(false);
        }
1548
    }
1549 1550 1551
}

void MissionController::_inProgressChanged(bool inProgress)
1552
{
1553
    emit syncInProgressChanged(inProgress);
1554
}
1555

1556
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
1557
{
1558 1559 1560
    bool        found = false;
    double      foundAltitude;
    MAV_FRAME   foundFrame;
1561

1562 1563 1564 1565 1566 1567
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1570 1571 1572
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1573
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
1574 1575 1576
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1577
                    break;
1578 1579
                }
            }
1580 1581 1582
        }
    }

1583
    if (found) {
1584 1585
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1586 1587 1588
    }

    return found;
1589
}
1590 1591 1592 1593 1594 1595 1596 1597 1598 1599 1600 1601 1602

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

1603
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1604
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1605
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1606
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
1607

Don Gagne's avatar
Don Gagne committed
1608 1609
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1610
    visualItems->insert(0, settingsItem);
1611

1612 1613 1614 1615 1616 1617 1618 1619 1620 1621 1622 1623 1624 1625 1626 1627 1628 1629 1630 1631 1632 1633 1634 1635 1636
    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;
                    }
1637 1638
                }
            }
1639

1640 1641 1642
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1643
        }
Don Gagne's avatar
Don Gagne committed
1644 1645
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1646 1647
    }
}
1648

1649
int MissionController::resumeMissionIndex(void) const
1650
{
1651

1652
    int resumeIndex = 0;
1653

1654
    if (!_editMode) {
1655
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1656
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1657 1658
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1659 1660
        } else {
            resumeIndex = 0;
1661 1662 1663 1664 1665
        }
    }

    return resumeIndex;
}
1666

1667 1668 1669 1670 1671 1672 1673 1674 1675 1676 1677 1678 1679
int MissionController::currentMissionIndex(void) const
{
    if (_editMode) {
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

1680
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1681 1682
{
    if (!_editMode) {
1683
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1684 1685 1686
            sequenceNumber++;
        }

1687 1688
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1689 1690
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1691
        emit currentMissionIndexChanged(currentMissionIndex());
1692 1693
    }
}
1694

1695
bool MissionController::syncInProgress(void) const
1696
{
1697
    return _missionManager->inProgress();
1698 1699 1700 1701 1702 1703 1704 1705 1706 1707 1708 1709
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1710
    }
1711
}
1712

1713 1714
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1715 1716 1717
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, vehicle);

1718 1719 1720 1721 1722 1723
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1724
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
1725 1726 1727
        if (settingsItem) {
            scanIndex++;
            settingsItem->scanForMissionSettings(visualItems, scanIndex);
1728 1729 1730 1731
            continue;
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1732
        if (simpleItem) {
1733 1734 1735 1736 1737
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
1738 1739 1740
        }
    }
}
1741 1742 1743 1744 1745 1746 1747 1748 1749 1750 1751 1752 1753

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
1754 1755 1756 1757 1758 1759 1760 1761
    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();
    }
1762
}
1763 1764 1765 1766 1767 1768

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

    complexItems.append(_surveyMissionItemName);
1769
    if (_controllerVehicle->fixedWing()) {
1770 1771 1772 1773 1774
        complexItems.append(_fwLandingMissionItemName);
    }

    return complexItems;
}
1775

1776 1777
void MissionController::resumeMission(int resumeIndex)
{
1778
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1779 1780
        resumeIndex--;
    }
1781
    _missionManager->generateResumeMission(resumeIndex);
1782
}
1783 1784 1785 1786 1787 1788 1789 1790 1791

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1792 1793 1794 1795 1796 1797 1798 1799 1800 1801

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

1803 1804 1805 1806 1807 1808 1809
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
1810 1811 1812 1813 1814 1815

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
1816 1817 1818

bool MissionController::showPlanFromManagerVehicle (void)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1819
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle" << _editMode;
DonLakeFlyer's avatar
DonLakeFlyer committed
1820 1821
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
1822
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
1823 1824 1825 1826 1827 1828 1829 1830 1831 1832 1833 1834 1835 1836 1837 1838 1839 1840 1841
    } 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;
        }
    }
}

1842
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1843
{
1844 1845
    // Fly view always reloads on send complete
    if (!error && !_editMode) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1846 1847 1848 1849
        showPlanFromManagerVehicle();
    }
}

1850
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1851
{
1852 1853 1854 1855
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1856
}