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


11
#include "MissionCommandUIInfo.h"
12 13 14 15
#include "MissionController.h"
#include "MultiVehicleManager.h"
#include "MissionManager.h"
#include "CoordinateVector.h"
16
#include "FirmwarePlugin.h"
17
#include "QGCApplication.h"
18
#include "SimpleMissionItem.h"
19
#include "SurveyMissionItem.h"
20
#include "FixedWingLandingComplexItem.h"
21
#include "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
        if (_editMode) {
193
            MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
194
        }
195

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

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

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

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

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

    return endActionSet;
}

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

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

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

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

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

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

314
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
315

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

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

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

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

    _recalcAll();

361
    return newItem->sequenceNumber();
362 363
}

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

    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();
Don Gagne's avatar
Don Gagne committed
482
        _visualItems->deleteLater();
483
        _settingsItem = NULL;
484
        _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
485
        _addMissionSettings(_visualItems, false /* addToCenter */);
486
        _initAllVisualItems();
487
        setDirty(true);
488
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
489 490 491
    }
}

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

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

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

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

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

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

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

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

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

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

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

    return true;
}

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

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

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

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

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

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

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

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

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

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

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

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

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

    return true;
825 826
}

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

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

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

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

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

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

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

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

    _initLoadedVisualItems(loadedVisualItems);

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

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

907
    // Mission settings
908

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

922
    // Save the visual items
923

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

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

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

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

946
    json[_jsonItemsKey] = rgJsonMissionItems;
947 948
}

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

    // Convert to fixed altitudes

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

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

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

    distanceOk = true;

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

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

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

1014
    bool showHomePosition = _settingsItem->coordinate().isValid();
1015

1016
    qCDebug(MissionControllerLog) << "_recalcWaypointLines showHomePosition" << showHomePosition;
1017

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

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


1036
        // If we still haven't found the first coordinate item and we hit a takeoff command, link back to home
1037 1038
        if (firstCoordinateItem &&
                item->isSimpleItem() &&
1039 1040 1041
                (!_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_NAV_TAKEOFF) ||
                    qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF ||
                    qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) {
1042
            linkStartToHome = true;
1043 1044 1045
            if (!_editMode) {
                _waypointPath.append(QVariant::fromValue(lastCoordinateItem->coordinate()));
            }
1046 1047 1048 1049 1050
        }

        if (item->specifiesCoordinate()) {
            if (!item->isStandaloneCoordinate()) {
                firstCoordinateItem = false;
1051
                if (lastCoordinateItem != _settingsItem || (showHomePosition && linkStartToHome)) {
1052 1053 1054 1055 1056 1057
                    if (_editMode) {
                        VisualItemPair pair(lastCoordinateItem, item);
                        _addWaypointLineSegment(old_table, pair);
                    } else {
                        _waypointPath.append(QVariant::fromValue(item->coordinate()));
                    }
1058 1059 1060 1061 1062
                }
                lastCoordinateItem = item;
            }
        }
    }
1063
    if (linkEndToHome && lastCoordinateItem != _settingsItem && showHomePosition) {
1064 1065 1066 1067 1068 1069
        if (_editMode) {
            VisualItemPair pair(lastCoordinateItem, _settingsItem);
            _addWaypointLineSegment(old_table, pair);
        } else {
            _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
        }
1070
    }
1071 1072 1073 1074

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

1089 1090 1091 1092 1093 1094 1095 1096
    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)));
    }

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

1101 1102 1103 1104 1105 1106
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);
1107 1108 1109
        // 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.
1110
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133
            _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);
}

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 1180
/// 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
1181
void MissionController::_recalcMissionFlightStatus()
1182
{
1183
    if (!_visualItems->count()) {
1184
        return;
1185
    }
1186 1187 1188 1189

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

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

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

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

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

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

1208
    _resetMissionFlightStatus();
1209

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

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

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

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

        // Look for gimbal change
1250 1251 1252 1253 1254 1255 1256
        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
1257 1258 1259 1260 1261
        }

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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


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

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

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

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

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

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

1501
    _recalcAll();
1502

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

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

1510
    setDirty(false);
1511 1512
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1683
    visualItems->insert(0, settingsItem);
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 1709
    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;
                    }
1710 1711
                }
            }
1712

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

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

1725
    int resumeIndex = 0;
1726

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

    return resumeIndex;
}
1739

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

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

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

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

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


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

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

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

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

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

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

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

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

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

    return complexItems;
}
1851

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

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

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

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

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
1892 1893 1894

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

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

1926
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1927
{
1928 1929 1930 1931
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1932
}
1933 1934 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

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