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


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

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

38 39
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

// Deprecated V1 format keys
const char* MissionController::_jsonComplexItemsKey =           "complexItems";
const char* MissionController::_jsonMavAutopilotKey =           "MAV_AUTOPILOT";

const int   MissionController::_missionFileVersion =            2;
55

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

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

78 79
}

80 81 82 83 84 85 86 87 88
void MissionController::_resetMissionFlightStatus(void)
{
    _missionFlightStatus.totalDistance =        0.0;
    _missionFlightStatus.maxTelemetryDistance = 0.0;
    _missionFlightStatus.totalTime =            0.0;
    _missionFlightStatus.hoverTime =            0.0;
    _missionFlightStatus.cruiseTime =           0.0;
    _missionFlightStatus.hoverDistance =        0.0;
    _missionFlightStatus.cruiseDistance =       0.0;
89 90 91
    _missionFlightStatus.cruiseSpeed =          _controllerVehicle->defaultCruiseSpeed();
    _missionFlightStatus.hoverSpeed =           _controllerVehicle->defaultHoverSpeed();
    _missionFlightStatus.vehicleSpeed =         _controllerVehicle->multiRotor() || _managerVehicle->vtol() ? _missionFlightStatus.hoverSpeed : _missionFlightStatus.cruiseSpeed;
92
    _missionFlightStatus.vehicleYaw =           0.0;
93
    _missionFlightStatus.gimbalYaw =            std::numeric_limits<double>::quiet_NaN();
94
    _missionFlightStatus.gimbalPitch =          std::numeric_limits<double>::quiet_NaN();
95 96 97 98 99 100 101 102 103 104 105 106

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

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

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

123 124
}

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

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

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

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

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

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

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

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

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

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

192
        MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
193

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

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

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

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

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

    return endActionSet;
}

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

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

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

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

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

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

312
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
313

314
        // PlanManager takes control of MissionItems so no need to delete
315
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
316 317
    }
}
318

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

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

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

    _recalcAll();

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

362 363 364 365 366
int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
{
    int sequenceNumber = _nextSequenceNumber();
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, this);
    newItem->setSequenceNumber(sequenceNumber);
367 368 369
    newItem->setCommand((MavlinkQmlSingleton::Qml_MAV_CMD)(_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains((MAV_CMD)MAV_CMD_DO_SET_ROI_LOCATION) ?
        MAV_CMD_DO_SET_ROI_LOCATION :
        MAV_CMD_DO_SET_ROI));
370 371
    _initVisualItem(newItem);
    newItem->setDefaultsForCommand();
372
    newItem->setCoordinate(coordinate);
373 374 375 376 377 378 379 380 381 382 383 384 385 386 387

    double      prevAltitude;
    MAV_FRAME   prevFrame;

    if (_findPreviousAltitude(i, &prevAltitude, &prevFrame)) {
        newItem->missionItem().setFrame(prevFrame);
        newItem->missionItem().setParam7(prevAltitude);
    }
    _visualItems->insert(i, newItem);

    _recalcAll();

    return newItem->sequenceNumber();
}

388
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
389
{
390 391
    ComplexMissionItem* newItem;

392
    int sequenceNumber = _nextSequenceNumber();
393
    if (itemName == _surveyMissionItemName) {
394
        newItem = new SurveyMissionItem(_controllerVehicle, _visualItems);
395
        newItem->setCoordinate(mapCenterCoordinate);
396 397 398 399
        // 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;
400 401 402
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
        CameraSection* cameraSection = settingsItem->cameraSection();
        // Set camera to photo mode (leave alone if user already specified)
403
        if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
404
            cameraSection->setSpecifyCameraMode(true);
405
            cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
406 407
        }
        // Point gimbal straight down
408
        if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
409 410 411
            // If the user already specified a gimbal angle leave it alone
            if (!cameraSection->specifyGimbal()) {
                cameraSection->setSpecifyGimbal(true);
412
                cameraSection->gimbalPitch()->setRawValue(-90.0);
413 414
            }
        }
415
    } else if (itemName == _fwLandingMissionItemName) {
416
        newItem = new FixedWingLandingComplexItem(_controllerVehicle, _visualItems);
417 418
    } else if (itemName == _structureScanMissionItemName) {
        newItem = new StructureScanComplexItem(_controllerVehicle, _visualItems);
419 420 421 422
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }
423
    newItem->setSequenceNumber(sequenceNumber);
424
    _initVisualItem(newItem);
425

426
    _visualItems->insert(i, newItem);
427 428 429

    _recalcAll();

430
    return newItem->sequenceNumber();
431 432
}

433 434
void MissionController::removeMissionItem(int index)
{
435 436 437 438 439 440
    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);
441
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
442

443
    _deinitVisualItem(item);
444
    item->deleteLater();
445

446 447 448 449 450 451 452 453 454 455
    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;
            }
        }

456
        // If there is no longer a survey item in the mission remove added commands
457 458 459 460
        if (!foundSurvey) {
            bool rollSupported = false;
            bool pitchSupported = false;
            bool yawSupported = false;
461 462
            MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
            CameraSection* cameraSection = settingsItem->cameraSection();
463
            if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
464
                if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
465 466 467
                    cameraSection->setSpecifyGimbal(false);
                }
            }
468
            if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
469 470
                cameraSection->setSpecifyCameraMode(false);
            }
471 472 473
        }
    }

474
    _recalcAll();
475
    setDirty(true);
476 477
}

478
void MissionController::removeAll(void)
479
{
480 481
    if (_visualItems) {
        _deinitAllVisualItems();
DonLakeFlyer's avatar
DonLakeFlyer committed
482
        _visualItems->clearAndDeleteContents();
Don Gagne's avatar
Don Gagne committed
483
        _visualItems->deleteLater();
484
        _settingsItem = NULL;
485
        _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
486
        _addMissionSettings(_visualItems, false /* addToCenter */);
487
        _initAllVisualItems();
488
        setDirty(true);
489
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
490 491 492
    }
}

493
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
494 495 496 497 498 499 500 501 502
{
    // 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)) {
503 504 505
        return false;
    }

506
    // Read complex items
507
    QList<SurveyMissionItem*> surveyItems;
508 509 510 511
    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];
512

513 514 515 516 517
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

518
        SurveyMissionItem* item = new SurveyMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
519 520
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
521
            surveyItems.append(item);
522 523
        } else {
            return false;
524
        }
525
    }
526

527 528 529 530 531
    // 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
532
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
533

534
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
535 536 537 538
    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
539 540
        if (nextComplexItemIndex < surveyItems.count()) {
            SurveyMissionItem* complexItem = surveyItems[nextComplexItemIndex];
541 542 543 544 545 546 547 548 549 550 551 552 553 554

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

555 556 557 558 559
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
560
            const QJsonObject itemObject = itemValue.toObject();
561
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
562
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
563
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
564
                nextSequenceNumber = item->lastSequenceNumber() + 1;
565
                visualItems->append(item);
566 567 568 569
            } else {
                return false;
            }
        }
570
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
571 572

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

Don Gagne's avatar
Don Gagne committed
575
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
576
            MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
577 578 579
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
580 581 582 583
        } else {
            return false;
        }
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
584
        _addMissionSettings(visualItems, true /* addToCenter */);
585 586 587 588 589
    }

    return true;
}

590
bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
591 592 593 594 595 596
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
597
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
598 599
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
600 601 602 603 604 605 606
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

607
    // Mission Settings
608
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
609

610 611
    if (_masterController->offline()) {
        // We only update if offline since if we are online we use the online vehicle settings
612 613 614 615
        appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType((MAV_AUTOPILOT)json[_jsonFirmwareTypeKey].toInt()));
        if (json.contains(_jsonVehicleTypeKey)) {
            appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType((MAV_TYPE)json[_jsonVehicleTypeKey].toInt()));
        }
616
    }
617
    if (json.contains(_jsonCruiseSpeedKey)) {
618
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
619 620
    }
    if (json.contains(_jsonHoverSpeedKey)) {
621
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
622 623
    }

624 625 626 627 628
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
629 630
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656
    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) {
657
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, visualItems);
658
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
659
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
660
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
661 662 663 664 665 666 667 668 669 670 671 672 673 674 675
                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;
676
                SurveyMissionItem* surveyItem = new SurveyMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
677 678 679 680 681 682
                if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(surveyItem);
683
            } else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
684
                qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
685
                FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(_controllerVehicle, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
686 687 688 689 690 691
                if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(landingItem);
692 693 694 695 696 697 698 699 700
            } else if (complexItemType == StructureScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Structure Scan: nextSequenceNumber" << nextSequenceNumber;
                StructureScanComplexItem* structureItem = new StructureScanComplexItem(_controllerVehicle, visualItems);
                if (!structureItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = structureItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Structure Scan load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(structureItem);
701
            } else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
702
                qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
703
                MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
704 705 706 707 708 709
                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
710 711 712 713 714 715 716 717 718 719 720 721 722
            } 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
723
            if ((MAV_CMD)doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746
                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;
}

747 748 749 750 751 752 753 754
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;
755 756 757 758 759 760
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
761 762

    if (fileVersion == 1) {
763
        return _loadJsonMissionFileV1(json, visualItems, errorString);
764
    } else {
765
        return _loadJsonMissionFileV2(json, visualItems, errorString);
766 767 768
    }
}

769
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
770
{
771 772
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
773 774 775 776 777 778 779 780 781

    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;
782
            plannedHomePositionInFile = true;
783 784 785
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
786
            plannedHomePositionInFile = false;
787 788 789 790
        }
    }

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

795
        while (!stream.atEnd()) {
796
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
797 798

            if (item->load(stream)) {
799 800 801 802 803 804
                if (firstItem && plannedHomePositionInFile) {
                    settingsItem->setCoordinate(item->coordinate());
                } else {
                    visualItems->append(item);
                }
                firstItem = false;
805
            } else {
806
                errorString = tr("The mission file is corrupted.");
807 808 809 810
                return false;
            }
        }
    } else {
811
        errorString = tr("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
812 813 814
        return false;
    }

815
    if (!plannedHomePositionInFile) {
816 817 818 819 820
        // 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
821 822
            }
        }
823 824 825
    }

    return true;
826 827
}

828
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
829
{
Don Gagne's avatar
Don Gagne committed
830 831 832
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
833
        _settingsItem = NULL;
Don Gagne's avatar
Don Gagne committed
834 835
    }

836
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
837 838

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

842
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
843

Don Gagne's avatar
Don Gagne committed
844
    _initAllVisualItems();
845
}
846

847 848 849 850 851 852
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

853
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878
        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;
879
    }
880

881 882 883 884 885 886 887 888 889 890 891 892 893
    _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);
894
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
895 896 897 898 899 900
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
901
    return true;
902 903
}

904
void MissionController::save(QJsonObject& json)
905
{
906
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
907

908
    // Mission settings
909

910 911 912 913 914 915 916 917
    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;
918 919 920 921
    json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
922

923
    // Save the visual items
924

925 926 927
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
928

929 930
        visualItem->save(rgJsonMissionItems);
    }
931

932 933 934
    // Mission settings has a special case for end mission action
    if (settingsItem) {
        QList<MissionItem*> rgMissionItems;
935

936 937 938 939 940
        if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
941
        }
942 943
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
944 945 946
        }
    }

947
    json[_jsonItemsKey] = rgJsonMissionItems;
948 949
}

950
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
951
{
Don Gagne's avatar
Don Gagne committed
952
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
953
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
954 955 956 957
    bool            distanceOk =    false;

    // Convert to fixed altitudes

958
    distanceOk = true;
959
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
960 961
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
962
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
963
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
964 965 966
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
967 968 969
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
970
    } else {
Don Gagne's avatar
Don Gagne committed
971
        *altDifference = 0.0;
972
        *azimuth = 0.0;
973
        *distance = 0.0;
974 975 976
    }
}

977
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
978 979 980 981 982 983 984
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

985
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
986 987
}

988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009
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;
    }
}

1010 1011
void MissionController::_recalcWaypointLines(void)
{
1012 1013 1014
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

1015
    bool homePositionValid = _settingsItem->coordinate().isValid();
1016

1017
    qCDebug(MissionControllerLog) << "_recalcWaypointLines homePositionValid" << homePositionValid;
1018

Nate Weibley's avatar
Nate Weibley committed
1019 1020
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
1021
    _waypointLines.clear();
1022
    _waypointPath.clear();
1023

1024 1025 1026 1027 1028 1029 1030 1031 1032
    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;
1033 1034 1035
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));

1036 1037 1038 1039 1040 1041
        // If we still haven't found the first coordinate item and we hit a takeoff command this means the mission starts from the ground.
        // Link the first item back to home to show that.
        if (firstCoordinateItem && item->isSimpleItem()) {
            MAV_CMD command = (MAV_CMD)qobject_cast<SimpleMissionItem*>(item)->command();
            if (command == MAV_CMD_NAV_TAKEOFF || command == MAV_CMD_NAV_VTOL_TAKEOFF) {
                linkStartToHome = true;
1042
            }
1043 1044
        }

1045 1046 1047 1048 1049 1050
        if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
            firstCoordinateItem = false;
            if (lastCoordinateItem != _settingsItem || (homePositionValid && linkStartToHome)) {
                if (_editMode) {
                    VisualItemPair pair(lastCoordinateItem, item);
                    _addWaypointLineSegment(old_table, pair);
1051 1052
                }
            }
1053 1054
            _waypointPath.append(QVariant::fromValue(item->coordinate()));
            lastCoordinateItem = item;
1055 1056
        }
    }
1057 1058 1059 1060 1061 1062

    if (linkStartToHome && homePositionValid) {
        _waypointPath.prepend(QVariant::fromValue(_settingsItem->coordinate()));
    }

    if (linkEndToHome && lastCoordinateItem != _settingsItem && homePositionValid) {
1063 1064 1065 1066 1067 1068
        if (_editMode) {
            VisualItemPair pair(lastCoordinateItem, _settingsItem);
            _addWaypointLineSegment(old_table, pair);
        } else {
            _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
        }
1069
    }
1070 1071 1072 1073

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1074 1075
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
1076 1077 1078 1079 1080 1081 1082 1083 1084 1085
            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
1086
    _recalcMissionFlightStatus();
1087

1088 1089 1090 1091 1092 1093 1094 1095
    if (_waypointPath.count() == 0) {
        // MapPolyLine has a bug where if you can from a path which has elements to an empty path the line drawn
        // is not cleared from the map. This hack works around that since it causes the previous lines to be remove
        // as then doesn't draw anything on the map.
        _waypointPath.append(QVariant::fromValue(QGeoCoordinate(0, 0)));
        _waypointPath.append(QVariant::fromValue(QGeoCoordinate(0, 0)));
    }

1096
    emit waypointLinesChanged();
1097
    emit waypointPathChanged();
1098 1099
}

1100 1101 1102 1103 1104 1105
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);
1106 1107 1108
        // FIXME: Battery change point code pretty much doesn't work. The reason is that is treats complex items as a black box. It needs to be able to look
        // inside complex items in order to determine a swap point that is interior to a complex item. Current the swap point display in PlanToolbar is
        // disabled to do this problem.
1109
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132
            _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);
}

1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179
/// 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
1180
void MissionController::_recalcMissionFlightStatus()
1181
{
1182
    if (!_visualItems->count()) {
1183
        return;
1184
    }
1185 1186 1187 1188

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

1189
    bool showHomePosition = _settingsItem->coordinate().isValid();
1190

DonLakeFlyer's avatar
DonLakeFlyer committed
1191
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1192

1193 1194 1195
    // 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.
1196

1197
    // No values for first item
1198
    lastCoordinateItem->setAltDifference(0.0);
1199
    lastCoordinateItem->setAzimuth(0.0);
1200
    lastCoordinateItem->setDistance(0.0);
1201

1202 1203
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1204 1205
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1206

1207
    _resetMissionFlightStatus();
1208

DonLakeFlyer's avatar
DonLakeFlyer committed
1209
    bool vtolInHover = true;
1210
    bool linkStartToHome = false;
1211 1212 1213 1214 1215 1216 1217 1218 1219 1220
    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();
        }
    }
1221

DonLakeFlyer's avatar
DonLakeFlyer committed
1222
    for (int i=0; i<_visualItems->count(); i++) {
1223
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1224 1225 1226
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1227 1228
        // Assume the worst
        item->setAzimuth(0.0);
1229
        item->setDistance(0.0);
1230

DonLakeFlyer's avatar
DonLakeFlyer committed
1231 1232 1233
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1234
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1235
                _missionFlightStatus.hoverSpeed = newSpeed;
1236
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1237 1238
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1239
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1240
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1241
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1242 1243
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1244
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1245 1246 1247 1248
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1249 1250 1251 1252 1253 1254 1255
        double gimbalYaw = item->specifiedGimbalYaw();
        if (!qIsNaN(gimbalYaw)) {
            _missionFlightStatus.gimbalYaw = gimbalYaw;
        }
        double gimbalPitch = item->specifiedGimbalPitch();
        if (!qIsNaN(gimbalPitch)) {
            _missionFlightStatus.gimbalPitch = gimbalPitch;
DonLakeFlyer's avatar
DonLakeFlyer committed
1256 1257 1258 1259 1260
        }

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

1263 1264 1265
        // 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) {
1266
                linkStartToHome = true;
1267 1268 1269 1270 1271 1272 1273
                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);
                }
1274 1275 1276 1277
            }
        }

        // Update VTOL state
1278
        if (simpleItem && _controllerVehicle->vtol()) {
1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292
            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;
1293 1294
                }
            }
1295 1296 1297
                break;
            default:
                break;
1298
            }
Don Gagne's avatar
Don Gagne committed
1299 1300
        }

1301 1302 1303
        // Check for command specific time delays
        _addCommandTimeDelay(simpleItem, vtolInHover);

1304
        if (item->specifiesCoordinate()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1305 1306
            // Update vehicle yaw assuming direction to next waypoint
            if (item != lastCoordinateItem) {
1307 1308
                _missionFlightStatus.vehicleYaw = lastCoordinateItem->exitCoordinate().azimuthTo(item->coordinate());
                lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
DonLakeFlyer's avatar
DonLakeFlyer committed
1309 1310
            }

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

1313
            double absoluteAltitude = item->coordinate().altitude();
1314
            if (item->coordinateHasRelativeAltitude()) {
1315 1316 1317 1318 1319
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1320 1321 1322 1323
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1324 1325 1326
            }

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

1332
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1333 1334 1335
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1336

1337
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1338

DonLakeFlyer's avatar
DonLakeFlyer committed
1339 1340 1341
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1342
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1343
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1344

1345
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1346 1347
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1348
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1349

1350 1351
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1352 1353
                    double extraTime = complexItem->additionalTimeDelay();
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, extraTime, distance, item->sequenceNumber());
1354
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1355 1356

                item->setMissionFlightStatus(_missionFlightStatus);
1357
            }
1358 1359

            lastCoordinateItem = item;
1360 1361
        }
    }
1362
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1363

1364 1365 1366 1367 1368 1369 1370 1371
    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();
1372
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1373 1374
    }

1375 1376 1377
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1378

DonLakeFlyer's avatar
DonLakeFlyer committed
1379 1380 1381 1382 1383 1384 1385
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1386 1387
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1388

1389 1390
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1391 1392
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1393 1394 1395

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1396
            if (item->coordinateHasRelativeAltitude()) {
1397 1398 1399 1400
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1401
                item->setTerrainPercent(qQNaN());
1402 1403
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1404 1405 1406
                if (!qIsNaN(item->terrainAltitude())) {
                    item->setTerrainPercent((item->terrainAltitude() - minAltSeen) / altRange);
                }
1407
            }
1408 1409 1410 1411
        }
    }
}

1412 1413 1414
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1415 1416 1417 1418 1419 1420
    // 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));

1421 1422
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1423 1424 1425
    }
}

1426 1427 1428
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1429
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1430 1431 1432

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

1433 1434
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1435 1436 1437 1438 1439

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1440
        } else if (item->isSimpleItem()) {
1441 1442 1443 1444 1445
            currentParentItem->childItems()->append(item);
        }
    }
}

1446 1447 1448 1449 1450 1451
void MissionController::_setPlannedHomePositionFromFirstCoordinate(void)
{
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1452
    // Set the planned home position to be a delta from first coordinate
1453 1454 1455 1456 1457 1458 1459 1460 1461 1462
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

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


1463 1464
void MissionController::_recalcAll(void)
{
1465 1466 1467
    if (_editMode) {
        _setPlannedHomePositionFromFirstCoordinate();
    }
1468
    _recalcSequence();
1469 1470 1471 1472
    _recalcChildItems();
    _recalcWaypointLines();
}

1473
/// Initializes a new set of mission items
1474
void MissionController::_initAllVisualItems(void)
1475
{
1476 1477
    // Setup home position at index 0

1478 1479 1480
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1481 1482
        return;
    }
1483 1484 1485
    if (_editMode) {
        _settingsItem->setIsCurrentItem(true);
    }
1486

1487
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1488
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1489
    }
1490

1491 1492 1493
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1494

1495 1496 1497 1498
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1499

1500
    _recalcAll();
1501

1502
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1503 1504 1505
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1506
    emit containsItemsChanged(containsItems());
1507
    emit plannedHomePositionChanged(plannedHomePosition());
1508

1509
    setDirty(false);
1510 1511
}

1512
void MissionController::_deinitAllVisualItems(void)
1513
{
1514 1515 1516
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1517 1518
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1519 1520
    }

1521
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1522
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1523 1524
}

1525
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1526
{
1527
    setDirty(false);
1528

1529
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1530 1531
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1532 1533
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1534
    connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged,                this, &MissionController::_recalcMissionFlightStatus);
1535
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1536
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1537

1538 1539 1540 1541 1542 1543 1544 1545
    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";
        }
1546 1547
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1548
        if (complexItem) {
1549
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
1550
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
1551
            connect(complexItem, &ComplexMissionItem::additionalTimeDelayChanged,   this, &MissionController::_recalcMissionFlightStatus);
1552 1553 1554
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1555
    }
1556 1557
}

1558
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1559
{
1560 1561
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1562 1563
}

1564
void MissionController::_itemCommandChanged(void)
1565
{
1566 1567
    _recalcChildItems();
    _recalcWaypointLines();
1568 1569
}

1570
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1571
{
1572 1573 1574 1575 1576 1577
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1578

1579 1580
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1581
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1582 1583
        return;
    }
1584

1585 1586
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1587 1588
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1589 1590 1591 1592 1593
    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);
1594
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1595 1596 1597 1598
    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);
1599

1600 1601
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1602
    }
1603

1604
    emit complexMissionItemNamesChanged();
1605
    emit resumeMissionIndexChanged();
1606 1607
}

1608
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1609
{
1610 1611
    if (_visualItems) {
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1612
        if (settingsItem) {
1613
            settingsItem->setHomePositionFromVehicle(homePosition);
1614
        } else {
1615
            qWarning() << "First item is not MissionSettingsItem";
1616
        }
1617 1618 1619
        // Don't let this trip the dirty bit. Otherwise plan will keep getting marked dirty if vehicle home
        // changes.
        _visualItems->setDirty(false);
1620
    }
1621 1622 1623
}

void MissionController::_inProgressChanged(bool inProgress)
1624
{
1625
    emit syncInProgressChanged(inProgress);
1626
}
1627

1628
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
1629
{
1630 1631 1632
    bool        found = false;
    double      foundAltitude;
    MAV_FRAME   foundFrame;
1633

1634 1635 1636 1637 1638 1639
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1642 1643 1644
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1645
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
1646 1647 1648
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1649
                    break;
1650 1651
                }
            }
1652 1653 1654
        }
    }

1655
    if (found) {
1656 1657
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1658 1659 1660
    }

    return found;
1661
}
1662 1663 1664 1665 1666 1667 1668 1669 1670 1671 1672 1673 1674

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

1675
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1676
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1677
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1678
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
1679

Don Gagne's avatar
Don Gagne committed
1680 1681
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1682
    visualItems->insert(0, settingsItem);
1683

1684 1685 1686 1687 1688 1689 1690 1691 1692 1693 1694 1695 1696 1697 1698 1699 1700 1701 1702 1703 1704 1705 1706 1707 1708
    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;
                    }
1709 1710
                }
            }
1711

1712 1713 1714
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1715
        }
Don Gagne's avatar
Don Gagne committed
1716 1717
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1718 1719
    }
}
1720

1721
int MissionController::resumeMissionIndex(void) const
1722
{
1723

1724
    int resumeIndex = 0;
1725

1726
    if (!_editMode) {
1727
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1728
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1729 1730
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1731 1732
        } else {
            resumeIndex = 0;
1733 1734 1735 1736 1737
        }
    }

    return resumeIndex;
}
1738

1739 1740 1741 1742 1743 1744 1745 1746 1747 1748 1749 1750 1751
int MissionController::currentMissionIndex(void) const
{
    if (_editMode) {
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

1752
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1753 1754
{
    if (!_editMode) {
1755
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1756 1757 1758
            sequenceNumber++;
        }

1759 1760
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1761 1762
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1763
        emit currentMissionIndexChanged(currentMissionIndex());
1764 1765
    }
}
1766

1767
bool MissionController::syncInProgress(void) const
1768
{
1769
    return _missionManager->inProgress();
1770 1771 1772 1773 1774 1775 1776 1777 1778 1779 1780 1781
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1782
    }
1783
}
1784

1785 1786
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1787 1788 1789 1790
    if (_editMode) {
        // First we look for a Fixed Wing Landing Pattern which is at the end
        FixedWingLandingComplexItem::scanForItem(visualItems, vehicle);
    }
1791

1792 1793 1794 1795 1796 1797
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1798 1799 1800 1801 1802 1803 1804
        if (_editMode) {
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
1805 1806 1807
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1808
        if (simpleItem) {
1809 1810 1811 1812 1813
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
1814 1815 1816
        }
    }
}
1817 1818 1819 1820 1821 1822 1823 1824 1825 1826 1827 1828 1829

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
1830 1831 1832 1833 1834 1835 1836 1837
    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();
    }
1838
}
1839 1840 1841 1842 1843 1844

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

    complexItems.append(_surveyMissionItemName);
1845
    if (_controllerVehicle->fixedWing()) {
1846 1847
        complexItems.append(_fwLandingMissionItemName);
    }
1848 1849 1850
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
        complexItems.append(_structureScanMissionItemName);
    }
1851 1852 1853

    return complexItems;
}
1854

1855 1856
void MissionController::resumeMission(int resumeIndex)
{
1857
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1858 1859
        resumeIndex--;
    }
1860
    _missionManager->generateResumeMission(resumeIndex);
1861
}
1862 1863 1864 1865 1866 1867 1868 1869 1870

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1871 1872 1873 1874 1875 1876 1877 1878 1879 1880

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

1882 1883 1884 1885 1886 1887 1888
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
1889 1890 1891 1892 1893 1894

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
1895 1896 1897

bool MissionController::showPlanFromManagerVehicle (void)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1898
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle" << _editMode;
DonLakeFlyer's avatar
DonLakeFlyer committed
1899 1900
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
1901
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
1902 1903 1904 1905 1906 1907 1908 1909 1910 1911 1912 1913 1914 1915 1916 1917 1918 1919 1920
    } 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;
        }
    }
}

1921
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1922
{
1923 1924
    // Fly view always reloads on send complete
    if (!error && !_editMode) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1925 1926 1927 1928
        showPlanFromManagerVehicle();
    }
}

1929
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1930
{
1931 1932 1933 1934
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1935
}
1936 1937 1938 1939 1940 1941 1942 1943 1944 1945 1946 1947 1948 1949 1950 1951 1952 1953 1954 1955 1956 1957 1958 1959 1960 1961 1962 1963 1964 1965

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

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

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