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

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

37 38
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

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

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

75 76
}

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

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

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

119 120
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

    return endActionSet;
}

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
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()) {
yaoling's avatar
yaoling committed
288
            coord = QString::number(item->param6(),'f',7) \
289
                + "," \
yaoling's avatar
yaoling committed
290
                + QString::number(item->param5(),'f',7) \
291
                + "," \
yaoling's avatar
yaoling committed
292
                + QString::number(item->param7() + altitude,'f',2);
293 294 295 296 297 298 299 300
            coords.append(coord);
        }
    }
    Kml kml;
    kml.points(coords);
    kml.save(document);
}

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

306
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
307

308
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
309

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

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

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

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

    _recalcAll();

352
    return newItem->sequenceNumber();
353 354
}

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

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

393
    _visualItems->insert(i, newItem);
394 395 396

    _recalcAll();

397
    return newItem->sequenceNumber();
398 399
}

400 401
void MissionController::removeMissionItem(int index)
{
402 403 404 405 406 407
    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);
408
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
409

410
    _deinitVisualItem(item);
411
    item->deleteLater();
412

413 414 415 416 417 418 419 420 421 422
    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;
            }
        }

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

441
    _recalcAll();
442
    setDirty(true);
443 444
}

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

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

472
    // Read complex items
473
    QList<SurveyMissionItem*> surveyItems;
474 475 476 477
    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];
478

479 480 481 482 483
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

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

493 494 495 496 497
    // 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
498
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
499

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

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

521 522 523 524 525
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

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

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

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

    return true;
}

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

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

573
    // Mission Settings
574
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
575

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

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

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

    if (fileVersion == 1) {
720
        return _loadJsonMissionFileV1(json, visualItems, errorString);
721
    } else {
722
        return _loadJsonMissionFileV2(json, visualItems, errorString);
723 724 725
    }
}

726
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
727
{
728 729
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
730 731 732 733 734 735 736 737 738

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

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

752
        while (!stream.atEnd()) {
753
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
754 755

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

772
    if (!plannedHomePositionInFile) {
773 774 775 776 777
        // 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
778 779
            }
        }
780 781 782
    }

    return true;
783 784
}

785
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
786
{
Don Gagne's avatar
Don Gagne committed
787 788 789
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
790
        _settingsItem = NULL;
Don Gagne's avatar
Don Gagne committed
791 792
    }

793
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
794 795

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

799
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
800

Don Gagne's avatar
Don Gagne committed
801
    _initAllVisualItems();
802
}
803

804 805 806 807 808 809
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

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

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

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
858
    return true;
859 860
}

861
void MissionController::save(QJsonObject& json)
862
{
863
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
864

865
    // Mission settings
866

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

880
    // Save the visual items
881

882 883 884
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
885

886 887
        visualItem->save(rgJsonMissionItems);
    }
888

889 890 891
    // Mission settings has a special case for end mission action
    if (settingsItem) {
        QList<MissionItem*> rgMissionItems;
892

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

904
    json[_jsonItemsKey] = rgJsonMissionItems;
905 906
}

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

    // Convert to fixed altitudes

915
    distanceOk = true;
916
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
917 918
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
919
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
920
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
921 922 923
    }

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

934
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
935 936 937 938 939 940 941
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

942
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
943 944
}

945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966
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;
    }
}

967 968
void MissionController::_recalcWaypointLines(void)
{
969 970 971
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

972
    bool showHomePosition = _settingsItem->coordinate().isValid();
973

974
    qCDebug(MissionControllerLog) << "_recalcWaypointLines showHomePosition" << showHomePosition;
975

Nate Weibley's avatar
Nate Weibley committed
976 977
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
978 979
    _waypointLines.clear();

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


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

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

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

    emit waypointLinesChanged();
}

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

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 1110 1111 1112 1113
/// 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
1114
void MissionController::_recalcMissionFlightStatus()
1115
{
1116
    if (!_visualItems->count()) {
1117
        return;
1118
    }
1119 1120 1121 1122

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

1123
    bool showHomePosition = _settingsItem->coordinate().isValid();
1124

DonLakeFlyer's avatar
DonLakeFlyer committed
1125
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1126

1127 1128 1129
    // 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.
1130

1131
    // No values for first item
1132
    lastCoordinateItem->setAltDifference(0.0);
1133
    lastCoordinateItem->setAzimuth(0.0);
1134
    lastCoordinateItem->setDistance(0.0);
1135

1136 1137
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1138 1139
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1140

1141
    _resetMissionFlightStatus();
1142

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1156
    for (int i=0; i<_visualItems->count(); i++) {
1157
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1158 1159 1160
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1161 1162
        // Assume the worst
        item->setAzimuth(0.0);
1163
        item->setDistance(0.0);
1164

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

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

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

1196 1197 1198
        // 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) {
1199
                linkStartToHome = true;
1200 1201 1202 1203 1204 1205 1206
                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);
                }
1207 1208 1209 1210
            }
        }

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

1234 1235 1236
        // Check for command specific time delays
        _addCommandTimeDelay(simpleItem, vtolInHover);

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

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

1246
            double absoluteAltitude = item->coordinate().altitude();
1247
            if (item->coordinateHasRelativeAltitude()) {
1248 1249 1250 1251 1252
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1253 1254 1255 1256
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1257 1258 1259
            }

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

1265
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1266 1267 1268
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1269

1270
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1271

DonLakeFlyer's avatar
DonLakeFlyer committed
1272 1273 1274
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1275
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1276
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1277

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

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

                item->setMissionFlightStatus(_missionFlightStatus);
1290
            }
1291 1292

            lastCoordinateItem = item;
1293 1294
        }
    }
1295
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1296

1297 1298 1299 1300 1301 1302 1303 1304
    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();
1305
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1306 1307
    }

1308 1309 1310
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1311

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

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

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

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

1354 1355
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1356 1357 1358
    }
}

1359 1360 1361
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1362
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1363 1364 1365

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

1366 1367
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1368 1369 1370 1371 1372

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1373
        } else if (item->isSimpleItem()) {
1374 1375 1376 1377 1378
            currentParentItem->childItems()->append(item);
        }
    }
}

1379 1380 1381 1382 1383 1384
void MissionController::_setPlannedHomePositionFromFirstCoordinate(void)
{
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

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

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


1396 1397
void MissionController::_recalcAll(void)
{
1398 1399 1400
    if (_editMode) {
        _setPlannedHomePositionFromFirstCoordinate();
    }
1401
    _recalcSequence();
1402 1403 1404 1405
    _recalcChildItems();
    _recalcWaypointLines();
}

1406
/// Initializes a new set of mission items
1407
void MissionController::_initAllVisualItems(void)
1408
{
1409 1410
    // Setup home position at index 0

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

1420
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1421
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1422
    }
1423

1424 1425 1426
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1427

1428 1429 1430 1431
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1432

1433
    _recalcAll();
1434

1435
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1436 1437 1438
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1439
    emit containsItemsChanged(containsItems());
1440
    emit plannedHomePositionChanged(plannedHomePosition());
1441

1442
    setDirty(false);
1443 1444
}

1445
void MissionController::_deinitAllVisualItems(void)
1446
{
1447 1448 1449
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1450 1451
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1452 1453
    }

1454
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1455
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1456 1457
}

1458
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1459
{
1460
    setDirty(false);
1461

1462
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1463 1464
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1465 1466
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1467
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1468
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1469

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

1490
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1491
{
1492 1493
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1494 1495
}

1496
void MissionController::_itemCommandChanged(void)
1497
{
1498 1499
    _recalcChildItems();
    _recalcWaypointLines();
1500 1501
}

1502
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1503
{
1504 1505 1506 1507 1508 1509
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1510

1511 1512
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1513
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1514 1515
        return;
    }
1516

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

1532 1533
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1534
    }
1535

1536
    emit complexMissionItemNamesChanged();
1537
    emit resumeMissionIndexChanged();
1538 1539
}

1540
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1541
{
1542 1543
    if (_visualItems) {
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1544
        if (settingsItem) {
1545
            settingsItem->setHomePositionFromVehicle(homePosition);
1546
        } else {
1547
            qWarning() << "First item is not MissionSettingsItem";
1548
        }
1549 1550 1551
        // Don't let this trip the dirty bit. Otherwise plan will keep getting marked dirty if vehicle home
        // changes.
        _visualItems->setDirty(false);
1552
    }
1553 1554 1555
}

void MissionController::_inProgressChanged(bool inProgress)
1556
{
1557
    emit syncInProgressChanged(inProgress);
1558
}
1559

1560
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
1561
{
1562 1563 1564
    bool        found = false;
    double      foundAltitude;
    MAV_FRAME   foundFrame;
1565

1566 1567 1568 1569 1570 1571
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

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

1587
    if (found) {
1588 1589
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1590 1591 1592
    }

    return found;
1593
}
1594 1595 1596 1597 1598 1599 1600 1601 1602 1603 1604 1605 1606

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

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

Don Gagne's avatar
Don Gagne committed
1612 1613
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1614
    visualItems->insert(0, settingsItem);
1615

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

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

1653
int MissionController::resumeMissionIndex(void) const
1654
{
1655

1656
    int resumeIndex = 0;
1657

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

    return resumeIndex;
}
1670

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

1684
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1685 1686
{
    if (!_editMode) {
1687
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1688 1689 1690
            sequenceNumber++;
        }

1691 1692
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1693 1694
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1695
        emit currentMissionIndexChanged(currentMissionIndex());
1696 1697
    }
}
1698

1699
bool MissionController::syncInProgress(void) const
1700
{
1701
    return _missionManager->inProgress();
1702 1703 1704 1705 1706 1707 1708 1709 1710 1711 1712 1713
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1714
    }
1715
}
1716

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

1722 1723 1724 1725 1726 1727
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1728
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
1729 1730 1731
        if (settingsItem) {
            scanIndex++;
            settingsItem->scanForMissionSettings(visualItems, scanIndex);
1732 1733 1734 1735
            continue;
        }

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

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
1758 1759 1760 1761 1762 1763 1764 1765
    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();
    }
1766
}
1767 1768 1769 1770 1771 1772

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

    complexItems.append(_surveyMissionItemName);
1773
    if (_controllerVehicle->fixedWing()) {
1774 1775
        complexItems.append(_fwLandingMissionItemName);
    }
1776 1777 1778
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
        complexItems.append(_structureScanMissionItemName);
    }
1779 1780 1781

    return complexItems;
}
1782

1783 1784
void MissionController::resumeMission(int resumeIndex)
{
1785
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1786 1787
        resumeIndex--;
    }
1788
    _missionManager->generateResumeMission(resumeIndex);
1789
}
1790 1791 1792 1793 1794 1795 1796 1797 1798

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1799 1800 1801 1802 1803 1804 1805 1806 1807 1808

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

1810 1811 1812 1813 1814 1815 1816
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
1817 1818 1819 1820 1821 1822

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
1823 1824 1825

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

1849
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1850
{
1851 1852
    // Fly view always reloads on send complete
    if (!error && !_editMode) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1853 1854 1855 1856
        showPlanFromManagerVehicle();
    }
}

1857
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1858
{
1859 1860 1861 1862
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1863
}