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


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

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

38 39
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

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

const int   MissionController::_missionFileVersion =            2;
55

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

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

78 79
}

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

    // Battery information

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

107 108 109 110
    _controllerVehicle->firmwarePlugin()->batteryConsumptionData(_controllerVehicle, _missionFlightStatus.mAhBattery, _missionFlightStatus.hoverAmps, _missionFlightStatus.cruiseAmps);
    if (_missionFlightStatus.mAhBattery != 0) {
        double batteryPercentRemainingAnnounce = qgcApp()->toolbox()->settingsManager()->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toDouble();
        _missionFlightStatus.ampMinutesAvailable = (double)_missionFlightStatus.mAhBattery / 1000.0 * 60.0 * ((100.0 - batteryPercentRemainingAnnounce) / 100.0);
111
    }
112 113 114 115 116 117 118 119 120 121 122

    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionTimeChanged();
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);

123 124
}

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

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

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

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

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

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

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

176 177
        for (; i<newMissionItems.count(); i++) {
            const MissionItem* missionItem = newMissionItems[i];
178
            newControllerMissionItems->append(new SimpleMissionItem(_controllerVehicle, *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
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
317

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

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

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

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

    _recalcAll();

364
    return newItem->sequenceNumber();
365 366
}

367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390
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();
}

391
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
392
{
393 394
    ComplexMissionItem* newItem;

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

429
    _visualItems->insert(i, newItem);
430 431 432

    _recalcAll();

433
    return newItem->sequenceNumber();
434 435
}

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

446
    _deinitVisualItem(item);
447
    item->deleteLater();
448

449 450 451 452 453 454 455 456 457 458
    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;
            }
        }

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

477
    _recalcAll();
478
    setDirty(true);
479 480
}

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

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

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

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

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

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

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

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

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

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

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

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

    return true;
}

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

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

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

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

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

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

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

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

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

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

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

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

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

    return true;
828 829
}

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

838
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
839 840

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

844
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
845

Don Gagne's avatar
Don Gagne committed
846
    _initAllVisualItems();
847
}
848

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

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

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

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
903
    return true;
904 905
}

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

910
    // Mission settings
911

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

925
    // Save the visual items
926

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

931 932
        visualItem->save(rgJsonMissionItems);
    }
933

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

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

949
    json[_jsonItemsKey] = rgJsonMissionItems;
950 951
}

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

    // Convert to fixed altitudes

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

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

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

    distanceOk = true;

987
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
988 989
}

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

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

1017
    bool showHomePosition = _settingsItem->coordinate().isValid();
1018

1019
    qCDebug(MissionControllerLog) << "_recalcWaypointLines showHomePosition" << showHomePosition;
1020

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

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


1038
        // If we still haven't found the first coordinate item and we hit a takeoff command, link back to home
1039 1040
        if (firstCoordinateItem &&
                item->isSimpleItem() &&
1041 1042 1043
                (!_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)) {
1044
            linkStartToHome = true;
1045 1046 1047 1048 1049 1050
        }

        if (item->specifiesCoordinate()) {
            if (!item->isStandaloneCoordinate()) {
                firstCoordinateItem = false;
                VisualItemPair pair(lastCoordinateItem, item);
1051 1052
                if (lastCoordinateItem != _settingsItem || (showHomePosition && linkStartToHome)) {
                    _addWaypointLineSegment(old_table, pair);
1053 1054 1055 1056 1057
                }
                lastCoordinateItem = item;
            }
        }
    }
1058 1059 1060 1061
    if (linkEndToHome && lastCoordinateItem != _settingsItem && showHomePosition) {
        VisualItemPair pair(lastCoordinateItem, _settingsItem);
        _addWaypointLineSegment(old_table, pair);
    }
1062 1063 1064 1065

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1066 1067
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
1068 1069 1070 1071 1072 1073 1074 1075 1076 1077
            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
1078
    _recalcMissionFlightStatus();
1079 1080 1081 1082

    emit waypointLinesChanged();
}

1083 1084 1085 1086 1087 1088
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);
1089 1090 1091
        // 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.
1092
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115
            _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);
}

1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162
/// 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
1163
void MissionController::_recalcMissionFlightStatus()
1164
{
1165
    if (!_visualItems->count()) {
1166
        return;
1167
    }
1168 1169 1170 1171

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

1172
    bool showHomePosition = _settingsItem->coordinate().isValid();
1173

DonLakeFlyer's avatar
DonLakeFlyer committed
1174
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1175

1176 1177 1178
    // 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.
1179

1180
    // No values for first item
1181
    lastCoordinateItem->setAltDifference(0.0);
1182
    lastCoordinateItem->setAzimuth(0.0);
1183
    lastCoordinateItem->setDistance(0.0);
1184

1185 1186
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1187 1188
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1189

1190
    _resetMissionFlightStatus();
1191

DonLakeFlyer's avatar
DonLakeFlyer committed
1192
    bool vtolInHover = true;
1193
    bool linkStartToHome = false;
1194 1195 1196 1197 1198 1199 1200 1201 1202 1203
    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();
        }
    }
1204

DonLakeFlyer's avatar
DonLakeFlyer committed
1205
    for (int i=0; i<_visualItems->count(); i++) {
1206
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1207 1208 1209
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1210 1211
        // Assume the worst
        item->setAzimuth(0.0);
1212
        item->setDistance(0.0);
1213

DonLakeFlyer's avatar
DonLakeFlyer committed
1214 1215 1216
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1217
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1218
                _missionFlightStatus.hoverSpeed = newSpeed;
1219
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1220 1221
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1222
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1223
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1224
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1225 1226
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1227
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1228 1229 1230 1231
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1232 1233 1234 1235 1236 1237 1238
        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
1239 1240 1241 1242 1243
        }

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

1246 1247 1248
        // 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) {
1249
                linkStartToHome = true;
1250 1251 1252 1253 1254 1255 1256
                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);
                }
1257 1258 1259 1260
            }
        }

        // Update VTOL state
1261
        if (simpleItem && _controllerVehicle->vtol()) {
1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275
            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;
1276 1277
                }
            }
1278 1279 1280
                break;
            default:
                break;
1281
            }
Don Gagne's avatar
Don Gagne committed
1282 1283
        }

1284 1285 1286
        // Check for command specific time delays
        _addCommandTimeDelay(simpleItem, vtolInHover);

1287
        if (item->specifiesCoordinate()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1288 1289
            // Update vehicle yaw assuming direction to next waypoint
            if (item != lastCoordinateItem) {
1290 1291
                _missionFlightStatus.vehicleYaw = lastCoordinateItem->exitCoordinate().azimuthTo(item->coordinate());
                lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
DonLakeFlyer's avatar
DonLakeFlyer committed
1292 1293
            }

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

1296
            double absoluteAltitude = item->coordinate().altitude();
1297
            if (item->coordinateHasRelativeAltitude()) {
1298 1299 1300 1301 1302
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1303 1304 1305 1306
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1307 1308 1309
            }

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

1315
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1316 1317 1318
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1319

1320
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1321

DonLakeFlyer's avatar
DonLakeFlyer committed
1322 1323 1324
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1325
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1326
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1327

1328
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1329 1330
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1331
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1332

1333 1334
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1335 1336
                    double extraTime = complexItem->additionalTimeDelay();
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, extraTime, distance, item->sequenceNumber());
1337
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1338 1339

                item->setMissionFlightStatus(_missionFlightStatus);
1340
            }
1341 1342

            lastCoordinateItem = item;
1343 1344
        }
    }
1345
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1346

1347 1348 1349 1350 1351 1352 1353 1354
    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();
1355
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1356 1357
    }

1358 1359 1360
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1361

DonLakeFlyer's avatar
DonLakeFlyer committed
1362 1363 1364 1365 1366 1367 1368
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1369 1370
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1371

1372 1373
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1374 1375
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1376 1377 1378

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1379
            if (item->coordinateHasRelativeAltitude()) {
1380 1381 1382 1383
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1384
                item->setTerrainPercent(qQNaN());
1385 1386
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1387 1388 1389
                if (!qIsNaN(item->terrainAltitude())) {
                    item->setTerrainPercent((item->terrainAltitude() - minAltSeen) / altRange);
                }
1390
            }
1391 1392 1393 1394
        }
    }
}

1395 1396 1397
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1398 1399 1400 1401 1402 1403
    // 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));

1404 1405
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1406 1407 1408
    }
}

1409 1410 1411
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1412
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1413 1414 1415

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

1416 1417
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1418 1419 1420 1421 1422

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1423
        } else if (item->isSimpleItem()) {
1424 1425 1426 1427 1428
            currentParentItem->childItems()->append(item);
        }
    }
}

1429 1430 1431 1432 1433 1434
void MissionController::_setPlannedHomePositionFromFirstCoordinate(void)
{
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1435
    // Set the planned home position to be a delta from first coordinate
1436 1437 1438 1439 1440 1441 1442 1443 1444 1445
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

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


1446 1447
void MissionController::_recalcAll(void)
{
1448 1449 1450
    if (_editMode) {
        _setPlannedHomePositionFromFirstCoordinate();
    }
1451
    _recalcSequence();
1452 1453 1454 1455
    _recalcChildItems();
    _recalcWaypointLines();
}

1456
/// Initializes a new set of mission items
1457
void MissionController::_initAllVisualItems(void)
1458
{
1459 1460
    // Setup home position at index 0

1461 1462 1463
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1464 1465
        return;
    }
1466 1467 1468
    if (_editMode) {
        _settingsItem->setIsCurrentItem(true);
    }
1469

1470
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1471
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1472
    }
1473

1474 1475 1476
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1477

1478 1479 1480 1481
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1482

1483
    _recalcAll();
1484

1485
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1486 1487 1488
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1489
    emit containsItemsChanged(containsItems());
1490
    emit plannedHomePositionChanged(plannedHomePosition());
1491

1492
    setDirty(false);
1493 1494
}

1495
void MissionController::_deinitAllVisualItems(void)
1496
{
1497 1498 1499
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1500 1501
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1502 1503
    }

1504
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1505
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1506 1507
}

1508
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1509
{
1510
    setDirty(false);
1511

1512
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1513 1514
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1515 1516
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1517
    connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged,                this, &MissionController::_recalcMissionFlightStatus);
1518
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1519
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1520

1521 1522 1523 1524 1525 1526 1527 1528
    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";
        }
1529 1530
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1531
        if (complexItem) {
1532
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
1533
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
1534
            connect(complexItem, &ComplexMissionItem::additionalTimeDelayChanged,   this, &MissionController::_recalcMissionFlightStatus);
1535 1536 1537
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1538
    }
1539 1540
}

1541
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1542
{
1543 1544
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1545 1546
}

1547
void MissionController::_itemCommandChanged(void)
1548
{
1549 1550
    _recalcChildItems();
    _recalcWaypointLines();
1551 1552
}

1553
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1554
{
1555 1556 1557 1558 1559 1560
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1561

1562 1563
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1564
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1565 1566
        return;
    }
1567

1568 1569
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1570 1571
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1572 1573 1574 1575 1576
    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);
1577
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1578 1579 1580 1581
    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);
1582

1583 1584
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1585
    }
1586

1587
    emit complexMissionItemNamesChanged();
1588
    emit resumeMissionIndexChanged();
1589 1590
}

1591
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1592
{
1593 1594
    if (_visualItems) {
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1595
        if (settingsItem) {
1596
            settingsItem->setHomePositionFromVehicle(homePosition);
1597
        } else {
1598
            qWarning() << "First item is not MissionSettingsItem";
1599
        }
1600 1601 1602
        // Don't let this trip the dirty bit. Otherwise plan will keep getting marked dirty if vehicle home
        // changes.
        _visualItems->setDirty(false);
1603
    }
1604 1605 1606
}

void MissionController::_inProgressChanged(bool inProgress)
1607
{
1608
    emit syncInProgressChanged(inProgress);
1609
}
1610

1611
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
1612
{
1613 1614 1615
    bool        found = false;
    double      foundAltitude;
    MAV_FRAME   foundFrame;
1616

1617 1618 1619 1620 1621 1622
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1625 1626 1627
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1628
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
1629 1630 1631
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1632
                    break;
1633 1634
                }
            }
1635 1636 1637
        }
    }

1638
    if (found) {
1639 1640
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1641 1642 1643
    }

    return found;
1644
}
1645 1646 1647 1648 1649 1650 1651 1652 1653 1654 1655 1656 1657

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

1658
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1659
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1660
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1661
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
1662

Don Gagne's avatar
Don Gagne committed
1663 1664
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1665
    visualItems->insert(0, settingsItem);
1666

1667 1668 1669 1670 1671 1672 1673 1674 1675 1676 1677 1678 1679 1680 1681 1682 1683 1684 1685 1686 1687 1688 1689 1690 1691
    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;
                    }
1692 1693
                }
            }
1694

1695 1696 1697
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1698
        }
Don Gagne's avatar
Don Gagne committed
1699 1700
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1701 1702
    }
}
1703

1704
int MissionController::resumeMissionIndex(void) const
1705
{
1706

1707
    int resumeIndex = 0;
1708

1709
    if (!_editMode) {
1710
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1711
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1712 1713
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1714 1715
        } else {
            resumeIndex = 0;
1716 1717 1718 1719 1720
        }
    }

    return resumeIndex;
}
1721

1722 1723 1724 1725 1726 1727 1728 1729 1730 1731 1732 1733 1734
int MissionController::currentMissionIndex(void) const
{
    if (_editMode) {
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

1735
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1736 1737
{
    if (!_editMode) {
1738
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1739 1740 1741
            sequenceNumber++;
        }

1742 1743
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1744 1745
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1746
        emit currentMissionIndexChanged(currentMissionIndex());
1747 1748
    }
}
1749

1750
bool MissionController::syncInProgress(void) const
1751
{
1752
    return _missionManager->inProgress();
1753 1754 1755 1756 1757 1758 1759 1760 1761 1762 1763 1764
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1765
    }
1766
}
1767

1768 1769
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1770 1771 1772
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, vehicle);

1773 1774 1775 1776 1777 1778
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1779
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
1780 1781 1782
        if (settingsItem) {
            scanIndex++;
            settingsItem->scanForMissionSettings(visualItems, scanIndex);
1783 1784 1785 1786
            continue;
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1787
        if (simpleItem) {
1788 1789 1790 1791 1792
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
1793 1794 1795
        }
    }
}
1796 1797 1798 1799 1800 1801 1802 1803 1804 1805 1806 1807 1808

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
1809 1810 1811 1812 1813 1814 1815 1816
    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();
    }
1817
}
1818 1819 1820 1821 1822 1823

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

    complexItems.append(_surveyMissionItemName);
1824
    if (_controllerVehicle->fixedWing()) {
1825 1826
        complexItems.append(_fwLandingMissionItemName);
    }
1827 1828 1829
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
        complexItems.append(_structureScanMissionItemName);
    }
1830 1831 1832

    return complexItems;
}
1833

1834 1835
void MissionController::resumeMission(int resumeIndex)
{
1836
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1837 1838
        resumeIndex--;
    }
1839
    _missionManager->generateResumeMission(resumeIndex);
1840
}
1841 1842 1843 1844 1845 1846 1847 1848 1849

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1850 1851 1852 1853 1854 1855 1856 1857 1858 1859

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

1861 1862 1863 1864 1865 1866 1867
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
1868 1869 1870 1871 1872 1873

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
1874 1875 1876

bool MissionController::showPlanFromManagerVehicle (void)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1877
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle" << _editMode;
DonLakeFlyer's avatar
DonLakeFlyer committed
1878 1879
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
1880
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
1881 1882 1883 1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895 1896 1897 1898 1899
    } 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;
        }
    }
}

1900
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1901
{
1902 1903
    // Fly view always reloads on send complete
    if (!error && !_editMode) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1904 1905 1906 1907
        showPlanFromManagerVehicle();
    }
}

1908
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1909
{
1910 1911 1912 1913
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1914
}
1915 1916 1917 1918 1919 1920 1921 1922 1923 1924 1925 1926 1927 1928 1929 1930 1931 1932 1933 1934 1935 1936 1937 1938 1939 1940 1941 1942 1943 1944

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