MissionController.cc 100 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 "SurveyComplexItem.h"
20
#include "FixedWingLandingComplexItem.h"
21
#include "StructureScanComplexItem.h"
22
#include "CorridorScanComplexItem.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
#include "QGCCorePlugin.h"
33

34 35
#include "src/Wima/CircularSurveyComplexItem.h"

36
#ifndef __mobile__
37
#include "MainWindow.h"
38
#include "QGCQFileDialog.h"
39 40
#endif

41 42
#define UPDATE_TIMEOUT 5000 ///< How often we check for bounding box changes

43 44
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

45
const char* MissionController::_settingsGroup =                 "MissionController";
Don Gagne's avatar
Don Gagne committed
46 47
const char* MissionController::_jsonFileTypeValue =             "Mission";
const char* MissionController::_jsonItemsKey =                  "items";
48
const char* MissionController::_jsonPlannedHomePositionKey =    "plannedHomePosition";
Don Gagne's avatar
Don Gagne committed
49
const char* MissionController::_jsonFirmwareTypeKey =           "firmwareType";
50 51 52
const char* MissionController::_jsonVehicleTypeKey =            "vehicleType";
const char* MissionController::_jsonCruiseSpeedKey =            "cruiseSpeed";
const char* MissionController::_jsonHoverSpeedKey =             "hoverSpeed";
Don Gagne's avatar
Don Gagne committed
53 54 55 56 57 58 59
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;
60

61 62 63
const QString MissionController::patternFWLandingName      (QT_TRANSLATE_NOOP("MissionController", "Fixed Wing Landing"));
const QString MissionController::patternStructureScanName  (QT_TRANSLATE_NOOP("MissionController", "Structure Scan"));
const QString MissionController::patternCorridorScanName   (QT_TRANSLATE_NOOP("MissionController", "Corridor Scan"));
64

65
MissionController::MissionController(PlanMasterController* masterController, QObject *parent)
66 67 68 69 70 71 72 73 74 75 76 77 78 79
    : PlanElementController         (masterController, parent)
    , _missionManager               (_managerVehicle->missionManager())
    , _missionItemCount             (0)
    , _visualItems                  (nullptr)
    , _settingsItem                 (nullptr)
    , _firstItemsFromVehicle        (false)
    , _itemsRequested               (false)
    , _inRecalcSequence             (false)
    , _surveyMissionItemName        (tr("Survey"))
    , _circularSurveyMissionItemName(tr("Circular Survey"))
    , _appSettings                  (qgcApp()->toolbox()->settingsManager()->appSettings())
    , _progressPct                  (0)
    , _currentPlanViewIndex         (-1)
    , _currentPlanViewItem          (nullptr)
80
{
81
    _resetMissionFlightStatus();
82
    managerVehicleChanged(_managerVehicle);
83 84
    _updateTimer.setSingleShot(true);
    connect(&_updateTimer, &QTimer::timeout, this, &MissionController::_updateTimeout);
85

86 87 88 89
}

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

91 92
}

93 94 95 96 97 98 99 100 101
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;
102 103 104
    _missionFlightStatus.cruiseSpeed =          _controllerVehicle->defaultCruiseSpeed();
    _missionFlightStatus.hoverSpeed =           _controllerVehicle->defaultHoverSpeed();
    _missionFlightStatus.vehicleSpeed =         _controllerVehicle->multiRotor() || _managerVehicle->vtol() ? _missionFlightStatus.hoverSpeed : _missionFlightStatus.cruiseSpeed;
105
    _missionFlightStatus.vehicleYaw =           0.0;
106
    _missionFlightStatus.gimbalYaw =            std::numeric_limits<double>::quiet_NaN();
107
    _missionFlightStatus.gimbalPitch =          std::numeric_limits<double>::quiet_NaN();
108 109 110 111 112 113 114 115 116 117 118 119

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

120 121 122
    _controllerVehicle->firmwarePlugin()->batteryConsumptionData(_controllerVehicle, _missionFlightStatus.mAhBattery, _missionFlightStatus.hoverAmps, _missionFlightStatus.cruiseAmps);
    if (_missionFlightStatus.mAhBattery != 0) {
        double batteryPercentRemainingAnnounce = qgcApp()->toolbox()->settingsManager()->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toDouble();
123
        _missionFlightStatus.ampMinutesAvailable = static_cast<double>(_missionFlightStatus.mAhBattery) / 1000.0 * 60.0 * ((100.0 - batteryPercentRemainingAnnounce) / 100.0);
124
    }
125 126 127 128 129 130 131 132 133 134 135

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

136 137
}

138
void MissionController::start(bool flyView)
139
{
140
    qCDebug(MissionControllerLog) << "start flyView" << flyView;
141

142
    PlanElementController::start(flyView);
143 144 145 146 147
    _init();
}

void MissionController::_init(void)
{
148
    // We start with an empty mission
149
    _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
150
    _addMissionSettings(_visualItems, false /* addToCenter */);
151
    _initAllVisualItems();
152 153
}

154
// Called when new mission items have completed downloading from Vehicle
155
void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllRequested)
156
{
157
    qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle flyView:count" << _flyView << _missionManager->missionItems().count();
158

DonLakeFlyer's avatar
DonLakeFlyer committed
159 160
    // Fly view always reloads on _loadComplete
    // Plan view only reloads on _loadComplete if specifically requested
161
    if (_flyView || removeAllRequested || _itemsRequested || _visualItems->count() <= 1) {
162
        // Fly Mode (accept if):
Don Gagne's avatar
Don Gagne committed
163
        //      - Always accepts new items from the vehicle so Fly view is kept up to date
164
        // Edit Mode (accept if):
165 166
        //      - Remove all was requested from Fly view (clear mission on flight end)
        //      - A load from vehicle was manually requested
Don Gagne's avatar
Don Gagne committed
167
        //      - The initial automatic load from a vehicle completed and the current editor is empty
168

169
        QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
170
        const QList<MissionItem*>& newMissionItems = _missionManager->missionItems();
171 172
        qCDebug(MissionControllerLog) << "loading from vehicle: count"<< newMissionItems.count();

173 174 175
        _missionItemCount = newMissionItems.count();
        emit missionItemCountChanged(_missionItemCount);

176
        int i = 0;
177
        if (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() && newMissionItems.count() != 0) {
178
            // First item is fake home position
DonLakeFlyer's avatar
DonLakeFlyer committed
179
            _addMissionSettings(newControllerMissionItems, false /* addToCenter */);
180
            MissionSettingsItem* settingsItem = newControllerMissionItems->value<MissionSettingsItem*>(0);
181 182 183 184
            if (!settingsItem) {
                qWarning() << "First item is not settings item";
                return;
            }
185 186 187 188
            MissionItem* fakeHomeItem = newMissionItems[0];
            if (fakeHomeItem->coordinate().latitude() != 0 || fakeHomeItem->coordinate().longitude() != 0) {
                settingsItem->setCoordinate(fakeHomeItem->coordinate());
            }
189 190
            i = 1;
        }
191

192
        for (; i < newMissionItems.count(); i++) {
193
            const MissionItem* missionItem = newMissionItems[i];
194
            newControllerMissionItems->append(new SimpleMissionItem(_controllerVehicle, _flyView, *missionItem, this));
195 196 197
        }

        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
198
        _visualItems->deleteLater();
199 200
        _settingsItem = nullptr;
        _visualItems  = nullptr;
201
        _updateContainsItems(); // This will clear containsItems which will be set again below. This will re-pop Start Mission confirmation.
202 203
        _visualItems = newControllerMissionItems;

204
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
205
            _addMissionSettings(_visualItems, !_flyView && _visualItems->count() > 0 /* addToCenter */);
206 207
        }

208
        MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
209

210
        _initAllVisualItems();
211
        _updateContainsItems();
212
        emit newItemsFromVehicle();
213
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
214
    _itemsRequested = false;
215 216
}

217
void MissionController::loadFromVehicle(void)
218
{
DonLakeFlyer's avatar
DonLakeFlyer committed
219 220 221 222 223 224 225 226
    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();
    }
227 228
}

229 230 231 232
void MissionController::_warnIfTerrainFrameUsed(void)
{
    for (int i=1; i<_visualItems->count(); i++) {
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(i));
233
        if (simpleItem && simpleItem->altitudeMode() == QGroundControlQmlGlobal::AltitudeModeTerrainFrame) {
234 235 236 237 238 239
            qgcApp()->showMessage(tr("Warning: You are using MAV_FRAME_GLOBAL_TERRAIN_ALT in a mission. %1 does not support sending terrain tiles to vehicle.").arg(qgcApp()->applicationName()));
            break;
        }
    }
}

240
void MissionController::sendToVehicle(void)
241
{
DonLakeFlyer's avatar
DonLakeFlyer committed
242 243 244 245 246
    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
247
        qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
248
        _warnIfTerrainFrameUsed();
DonLakeFlyer's avatar
DonLakeFlyer committed
249 250 251 252 253 254 255 256 257
        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
258 259
}

260
/// Converts from visual items to MissionItems
261
///     @param missionItemParent QObject parent for newly allocated MissionItems, _surveyMissionItemName    (tr("Survey"))
262
/// @return true: Mission end action was added to end of list
263
bool MissionController::convertToMissionItems(QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent)
264
{
DonLakeFlyer's avatar
DonLakeFlyer committed
265 266 267 268
    if (visualMissionItems->count() == 0) {
        return false;
    }

269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284
    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
285
    MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
286 287 288 289 290 291 292
    if (settingsItem) {
        endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
    }

    return endActionSet;
}

293 294
void MissionController::convertToKMLDocument(QDomDocument& document)
{
295 296
    QObject*            deleteParent = new QObject();
    QList<MissionItem*> rgMissionItems;
297

298
    convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
299
    if (rgMissionItems.count() == 0) {
300 301
        return;
    }
302

303
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
304 305 306 307 308

    QString coord;
    QStringList coords;
    // Drop home position
    bool dropPoint = true;
309
    for(const auto& item : rgMissionItems) {
310 311 312 313 314
        if(dropPoint) {
            dropPoint = false;
            continue;
        }
        const MissionCommandUIInfo* uiInfo = \
315
                qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, item->command());
316 317

        if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
318
            double amslAltitude = item->param7() + (item->frame() == MAV_FRAME_GLOBAL ? 0 : homePositionAltitude);
yaoling's avatar
yaoling committed
319
            coord = QString::number(item->param6(),'f',7) \
320 321 322
                    + "," \
                    + QString::number(item->param5(),'f',7) \
                    + "," \
323
                    + QString::number(amslAltitude,'f',2);
324 325 326
            coords.append(coord);
        }
    }
327 328 329

    deleteParent->deleteLater();

330 331 332 333 334
    Kml kml;
    kml.points(coords);
    kml.save(document);
}

Don Gagne's avatar
Don Gagne committed
335 336 337
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
338
        QList<MissionItem*> rgMissionItems;
339

340
        convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
341

342
        // PlanManager takes control of MissionItems so no need to delete
343
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
344 345
    }
}
346

347 348 349 350 351 352
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
353 354
        VisualMissionItem* lastItem = _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1);
        return lastItem->lastSequenceNumber() + 1;
355 356 357
    }
}

358
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
359
{
360
    int sequenceNumber = _nextSequenceNumber();
361
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
362
    newItem->setSequenceNumber(sequenceNumber);
363
    newItem->setCoordinate(coordinate);
364
    newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
365
    _initVisualItem(newItem);
366
    if (_visualItems->count() == 1 && (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() || _controllerVehicle->multiRotor())) {
367
        MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
368
        if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) {
369 370
            newItem->setCommand(takeoffCmd);
        }
371
    }
372 373 374
    if (newItem->specifiesAltitude()) {
        double  prevAltitude;
        int     prevAltitudeMode;
375

376 377
        if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
            newItem->altitude()->setRawValue(prevAltitude);
378
            newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
379
        }
380
    }
381
    newItem->setMissionFlightStatus(_missionFlightStatus);
382
    _visualItems->insert(i, newItem);
383

384 385
    // We send the click coordinate through here to be able to set the planned home position from the user click location if needed
    _recalcAllWithClickCoordinate(coordinate);
386

387
    return newItem->sequenceNumber();
388 389
}

390 391 392 393 394 395 396 397 398
int MissionController::insertSimpleMissionItem(const MissionItem &missionItem, int i)
{
    int sequenceNumber = _nextSequenceNumber();
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, missionItem, this);
    newItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(newItem);
    MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
    if (newItem->command() ==  takeoffCmd) {
        if (!_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) {
399
            newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
400 401 402
            return -1; // can not add this takeoff command for this vehicle
        }
    }
403 404 405 406 407 408
    if (newItem->specifiesAltitude()) {        
        newItem->altitude()->setRawValue(missionItem.relativeAltitude());
        newItem->setAltitudeMode(QGroundControlQmlGlobal::AltitudeMode::AltitudeModeRelative);
    }
    newItem->setMissionFlightStatus(_missionFlightStatus);
    _visualItems->insert(i, newItem);
409

410 411 412
    return newItem->sequenceNumber();
}

413
int MissionController::insertSimpleMissionItem(SimpleMissionItem &missionItem, int i)
414 415 416 417 418 419 420 421 422 423
{
    int sequenceNumber = _nextSequenceNumber();
    SimpleMissionItem * newItem = new SimpleMissionItem(missionItem, _flyView, this);
    newItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(newItem);
    MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
    if (newItem->command() ==  takeoffCmd) {
        if (!_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) {
            newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
            return -1; // can not add this takeoff command for this vehicle
424 425
        }
    }
Valentin Platzgummer's avatar
Valentin Platzgummer committed
426
    newItem->setMissionFlightStatus(_missionFlightStatus);
427 428 429
    _visualItems->insert(i, newItem);

    return newItem->sequenceNumber();
430
}
431

432 433 434
int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
{
    int sequenceNumber = _nextSequenceNumber();
435
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
436
    newItem->setSequenceNumber(sequenceNumber);
437
    newItem->setCommand((_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_DO_SET_ROI_LOCATION) ?
438 439
        MAV_CMD_DO_SET_ROI_LOCATION :
        MAV_CMD_DO_SET_ROI));
440
    _initVisualItem(newItem);
441
    newItem->setCoordinate(coordinate);
442

443 444
    double  prevAltitude;
    int     prevAltitudeMode;
445

446 447
    if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
        newItem->altitude()->setRawValue(prevAltitude);
448
        newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
449 450 451 452 453 454 455 456
    }
    _visualItems->insert(i, newItem);

    _recalcAll();

    return newItem->sequenceNumber();
}

457
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
458
{
459 460
    ComplexMissionItem* newItem;

461
    int sequenceNumber = _nextSequenceNumber();
462
    if (itemName == _surveyMissionItemName) {
463
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
464
        newItem->setCoordinate(mapCenterCoordinate);
465
    } else if (itemName == patternFWLandingName) {
466
        newItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, _visualItems /* parent */);
467
    } else if (itemName == patternStructureScanName) {
468
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
469
    } else if (itemName == patternCorridorScanName) {
470
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
471 472
    } else if (itemName == _circularSurveyMissionItemName) {
        newItem = new CircularSurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
473 474 475 476 477
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }

478 479 480
    return _insertComplexMissionItemWorker(newItem, i);
}

481
int MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int i)
482 483 484 485
{
    ComplexMissionItem* newItem;

    if (itemName == _surveyMissionItemName) {
486
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
487 488
    } else if (itemName == _circularSurveyMissionItemName) {
        newItem = new CircularSurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
489
    } else if (itemName == patternStructureScanName) {
490
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
491
    } else if (itemName == patternCorridorScanName) {
492
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
493 494 495 496 497 498 499 500 501 502 503
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return _nextSequenceNumber();
    }

    return _insertComplexMissionItemWorker(newItem, i);
}

int MissionController::_insertComplexMissionItemWorker(ComplexMissionItem* complexItem, int i)
{
    int sequenceNumber = _nextSequenceNumber();
504 505 506
    bool surveyStyleItem =    qobject_cast<SurveyComplexItem*>(complexItem)
                           || qobject_cast<CorridorScanComplexItem*>(complexItem)
                           || qobject_cast<CircularSurveyComplexItem*>(complexItem);
507

508
    if (surveyStyleItem) {
509
        bool rollSupported  = false;
510
        bool pitchSupported = false;
511
        bool yawSupported   = false;
512 513 514

        // If the vehicle is known to have a gimbal then we automatically point the gimbal straight down if not already set

515 516
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
        CameraSection* cameraSection = settingsItem->cameraSection();
517

518
        // Set camera to photo mode (leave alone if user already specified)
519
        if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
520
            cameraSection->setSpecifyCameraMode(true);
521
            cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
522
        }
523

524
        // Point gimbal straight down
525
        if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
526 527 528
            // If the user already specified a gimbal angle leave it alone
            if (!cameraSection->specifyGimbal()) {
                cameraSection->setSpecifyGimbal(true);
529
                cameraSection->gimbalPitch()->setRawValue(-90.0);
530 531
            }
        }
532
    }
533

534 535
    complexItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(complexItem);
536

537 538 539 540 541
    if (i == -1) {
        _visualItems->append(complexItem);
    } else {
        _visualItems->insert(i, complexItem);
    }
542

543
    //-- Keep track of bounding box changes in complex items
544 545
    if(!complexItem->isSimpleItem()) {
        connect(complexItem, &ComplexMissionItem::boundingCubeChanged, this, &MissionController::_complexBoundingBoxChanged);
546
    }
547 548
    _recalcAll();

549
    return complexItem->sequenceNumber();
550 551
}

552 553
void MissionController::removeMissionItem(int index)
{
554 555 556 557 558
    if (index <= 0 || index >= _visualItems->count()) {
        qWarning() << "MissionController::removeMissionItem called with bad index - count:index" << _visualItems->count() << index;
        return;
    }

559 560 561
    bool removeSurveyStyle =    _visualItems->value<SurveyComplexItem*>(index)
                             || _visualItems->value<CorridorScanComplexItem*>(index)
                             || _visualItems->value<CircularSurveyComplexItem*>(index);
562
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
563

564
    _deinitVisualItem(item);
565
    item->deleteLater();
566

567 568
    if (removeSurveyStyle) {
        // Determine if the mission still has another survey style item in it
569 570
        bool foundSurvey = false;
        for (int i=1; i<_visualItems->count(); i++) {
571 572 573
            if (    _visualItems->value<SurveyComplexItem*>(i)
                 || _visualItems->value<CorridorScanComplexItem*>(i)
                 || _visualItems->value<CircularSurveyComplexItem*>(i)) {
574 575 576 577 578
                foundSurvey = true;
                break;
            }
        }

579
        // If there is no longer a survey item in the mission remove added commands
580 581 582 583
        if (!foundSurvey) {
            bool rollSupported = false;
            bool pitchSupported = false;
            bool yawSupported = false;
584 585
            MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
            CameraSection* cameraSection = settingsItem->cameraSection();
586
            if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
587
                if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
588 589 590
                    cameraSection->setSpecifyGimbal(false);
                }
            }
591
            if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
592 593
                cameraSection->setSpecifyCameraMode(false);
            }
594 595 596
        }
    }

597
    _recalcAll();
598
    setDirty(true);
599 600
}

601
void MissionController::removeAll(void)
602
{
603 604
    if (_visualItems) {
        _deinitAllVisualItems();
DonLakeFlyer's avatar
DonLakeFlyer committed
605
        _visualItems->clearAndDeleteContents();
Don Gagne's avatar
Don Gagne committed
606
        _visualItems->deleteLater();
607
        _settingsItem = nullptr;
608
        _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
609
        _addMissionSettings(_visualItems, false /* addToCenter */);
610
        _initAllVisualItems();
611
        setDirty(true);
612
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
613 614 615
    }
}

616
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
617 618 619 620 621 622 623 624 625
{
    // 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)) {
626 627 628
        return false;
    }

629
    // Read complex items
630
    QList<SurveyComplexItem*> surveyItems;
631 632 633 634
    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];
635

636 637 638 639 640
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

641
        SurveyComplexItem* item = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems /* parent */);
Don Gagne's avatar
Don Gagne committed
642 643
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
644
            surveyItems.append(item);
645 646
        } else {
            return false;
647
        }
648
    }
649

650 651 652 653 654
    // 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
655
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
656

657
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
658 659 660 661
    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
662
        if (nextComplexItemIndex < surveyItems.count()) {
663
            SurveyComplexItem* complexItem = surveyItems[nextComplexItemIndex];
664 665 666 667 668 669 670 671 672 673 674 675 676 677

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

678 679 680 681 682
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
683
            const QJsonObject itemObject = itemValue.toObject();
684
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
Don Gagne's avatar
Don Gagne committed
685
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
686
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
687
                nextSequenceNumber = item->lastSequenceNumber() + 1;
688
                visualItems->append(item);
689 690 691 692
            } else {
                return false;
            }
        }
693
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
694 695

    if (json.contains(_jsonPlannedHomePositionKey)) {
696
        SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
697

Don Gagne's avatar
Don Gagne committed
698
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
699
            MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
700 701 702
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
703 704 705 706
        } else {
            return false;
        }
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
707
        _addMissionSettings(visualItems, true /* addToCenter */);
708 709 710 711 712
    }

    return true;
}

713
bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
714 715 716 717 718 719
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
720
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
721 722
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
723 724 725 726 727 728 729
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

730
    // Mission Settings
731
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
732

733 734
    if (_masterController->offline()) {
        // We only update if offline since if we are online we use the online vehicle settings
735
        appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType(static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt())));
736
        if (json.contains(_jsonVehicleTypeKey)) {
737
            appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType(static_cast<MAV_TYPE>(json[_jsonVehicleTypeKey].toInt())));
738
        }
739
    }
740
    if (json.contains(_jsonCruiseSpeedKey)) {
741
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
742 743
    }
    if (json.contains(_jsonHoverSpeedKey)) {
744
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
745 746
    }

747 748 749 750
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
751
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
752 753
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779
    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) {
780
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
781
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
782
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
783
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
784 785 786 787 788 789 790 791 792 793 794 795 796
                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();

797
            if (complexItemType == SurveyComplexItem::jsonComplexItemTypeValue) {
Don Gagne's avatar
Don Gagne committed
798
                qCDebug(MissionControllerLog) << "Loading Survey: nextSequenceNumber" << nextSequenceNumber;
799
                SurveyComplexItem* surveyItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
Don Gagne's avatar
Don Gagne committed
800 801 802 803 804 805
                if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(surveyItem);
806
            } else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
807
                qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
808
                FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
809 810 811 812 813 814
                if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(landingItem);
815 816
            } else if (complexItemType == StructureScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Structure Scan: nextSequenceNumber" << nextSequenceNumber;
817
                StructureScanComplexItem* structureItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
818 819 820 821 822 823
                if (!structureItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = structureItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Structure Scan load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(structureItem);
824 825
            } else if (complexItemType == CorridorScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Corridor Scan: nextSequenceNumber" << nextSequenceNumber;
826
                CorridorScanComplexItem* corridorItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
827 828 829 830 831 832
                if (!corridorItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = corridorItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Corridor Scan load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(corridorItem);
Valentin Platzgummer's avatar
Valentin Platzgummer committed
833 834 835 836 837 838 839 840 841
            } else if (complexItemType == CircularSurveyComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Circular Survey: nextSequenceNumber" << nextSequenceNumber;
                CircularSurveyComplexItem* circularSurvey = new CircularSurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
                if (!circularSurvey->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = circularSurvey->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Circular Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(circularSurvey);
842
            } else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
843
                qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
844
                MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
845 846 847 848 849 850
                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
851 852 853 854 855 856 857 858 859 860 861 862 863
            } 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);
864
            if (doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
865
                bool found = false;
866
                int findDoJumpId = static_cast<int>(doJumpItem->missionItem().param1());
Don Gagne's avatar
Don Gagne committed
867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887
                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;
}

888 889 890 891 892 893 894 895
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;
896 897 898 899 900 901
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
902 903

    if (fileVersion == 1) {
904
        return _loadJsonMissionFileV1(json, visualItems, errorString);
905
    } else {
906
        return _loadJsonMissionFileV2(json, visualItems, errorString);
907 908 909
    }
}

910
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
911
{
912 913
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
914 915 916 917 918 919 920 921 922

    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;
923
            plannedHomePositionInFile = true;
924 925 926
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
927
            plannedHomePositionInFile = false;
928 929 930 931
        }
    }

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

936
        while (!stream.atEnd()) {
937
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
938 939

            if (item->load(stream)) {
940 941 942 943 944 945
                if (firstItem && plannedHomePositionInFile) {
                    settingsItem->setCoordinate(item->coordinate());
                } else {
                    visualItems->append(item);
                }
                firstItem = false;
946
            } else {
947
                errorString = tr("The mission file is corrupted.");
948 949 950 951
                return false;
            }
        }
    } else {
952
        errorString = tr("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
953 954 955
        return false;
    }

956
    if (!plannedHomePositionInFile) {
957 958 959
        // 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));
960
            if (item && item->command() == MAV_CMD_DO_JUMP) {
961
                item->missionItem().setParam1(static_cast<int>(item->missionItem().param1()) + 1);
Don Gagne's avatar
Don Gagne committed
962 963
            }
        }
964 965 966
    }

    return true;
967 968
}

969
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
970
{
Don Gagne's avatar
Don Gagne committed
971 972 973
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
974
        _settingsItem = nullptr;
Don Gagne's avatar
Don Gagne committed
975 976
    }

977
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
978 979

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

983
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
984

Don Gagne's avatar
Don Gagne committed
985
    _initAllVisualItems();
986
}
987

988 989 990 991 992 993
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

994
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019
        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;
1020
    }
1021

1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034
    _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);
1035
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
1036 1037 1038 1039 1040 1041
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
1042
    return true;
1043 1044
}

1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056
bool MissionController::readyForSaveSend(void) const
{
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        if (!visualItem->readyForSave()) {
            return false;
        }
    }

    return true;
}

1057
bool MissionController::setTakeoffCommand(SimpleMissionItem &missionItem)
1058
{
1059
    if (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() || _controllerVehicle->multiRotor()) {
1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070
        MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
        if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) {
            missionItem.setCommand(takeoffCmd);
        }
    }
    else
       return false;

    return true;
}

1071
bool MissionController::setLandCommand(SimpleMissionItem &missionItem)
1072
{
1073 1074
    MAV_CMD landCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_LAND;
    if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(landCmd)) {
1075 1076 1077 1078 1079 1080 1081
        missionItem.setCommand(landCmd);
    } else
        return false;

    return true;
}

1082
void MissionController::save(QJsonObject& json)
1083
{
1084
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
1085

1086
    // Mission settings
1087

1088 1089 1090 1091 1092 1093 1094
    MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsItem";
        return;
    }
    QJsonValue coordinateValue;
    JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
1095 1096 1097 1098 1099
    json[_jsonPlannedHomePositionKey]   = coordinateValue;
    json[_jsonFirmwareTypeKey]          = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey]           = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey]           = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey]            = _controllerVehicle->defaultHoverSpeed();
1100

1101
    // Save the visual items
1102

1103 1104 1105
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1106

1107 1108
        visualItem->save(rgJsonMissionItems);
    }
1109

1110 1111 1112
    // Mission settings has a special case for end mission action
    if (settingsItem) {
        QList<MissionItem*> rgMissionItems;
1113

1114
        if (convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
1115 1116 1117 1118
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
1119
        }
1120 1121
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
1122 1123 1124
        }
    }

1125
    json[_jsonItemsKey] = rgJsonMissionItems;
1126 1127
}

1128
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
1129
{
Don Gagne's avatar
Don Gagne committed
1130
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
1131
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
1132 1133 1134 1135
    bool            distanceOk =    false;

    // Convert to fixed altitudes

1136
    distanceOk = true;
1137
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
1138 1139
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
1140
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
1141
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
1142 1143 1144
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
1145 1146 1147
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
1148
    } else {
Don Gagne's avatar
Don Gagne committed
1149
        *altDifference = 0.0;
1150
        *azimuth = 0.0;
1151
        *distance = 0.0;
1152 1153 1154
    }
}

1155
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
1156 1157 1158 1159 1160 1161 1162
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

1163
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
1164 1165
}

1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187
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;
    }
}

1188 1189
void MissionController::_recalcWaypointLines(void)
{
1190 1191 1192
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

1193
    bool homePositionValid = _settingsItem->coordinate().isValid();
1194

1195
    qCDebug(MissionControllerLog) << "_recalcWaypointLines homePositionValid" << homePositionValid;
1196

Nate Weibley's avatar
Nate Weibley committed
1197 1198
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
1199
    _waypointLines.clear();
1200
    _waypointPath.clear();
1201

1202 1203 1204 1205 1206 1207 1208 1209 1210
    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;
1211 1212 1213
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));

1214 1215 1216 1217 1218 1219
        // If we still haven't found the first coordinate item and we hit a takeoff command this means the mission starts from the ground.
        // Link the first item back to home to show that.
        if (firstCoordinateItem && item->isSimpleItem()) {
            MAV_CMD command = (MAV_CMD)qobject_cast<SimpleMissionItem*>(item)->command();
            if (command == MAV_CMD_NAV_TAKEOFF || command == MAV_CMD_NAV_VTOL_TAKEOFF) {
                linkStartToHome = true;
1220
            }
1221 1222
        }

1223 1224 1225
        if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
            firstCoordinateItem = false;
            if (lastCoordinateItem != _settingsItem || (homePositionValid && linkStartToHome)) {
1226
                if (!_flyView) {
1227 1228
                    VisualItemPair pair(lastCoordinateItem, item);
                    _addWaypointLineSegment(old_table, pair);
1229 1230
                }
            }
1231 1232
            _waypointPath.append(QVariant::fromValue(item->coordinate()));
            lastCoordinateItem = item;
1233 1234
        }
    }
1235 1236 1237 1238 1239 1240

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

    if (linkEndToHome && lastCoordinateItem != _settingsItem && homePositionValid) {
1241
        if (!_flyView) {
1242 1243 1244 1245 1246
            VisualItemPair pair(lastCoordinateItem, _settingsItem);
            _addWaypointLineSegment(old_table, pair);
        } else {
            _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
        }
1247
    }
1248 1249 1250 1251

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1252
        objs.reserve(_linesTable.count());
1253
        for(CoordinateVector *vect: _linesTable.values()) {
1254 1255 1256 1257 1258 1259 1260 1261 1262 1263
            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
1264
    _recalcMissionFlightStatus();
1265

1266 1267 1268 1269 1270 1271 1272 1273
    if (_waypointPath.count() == 0) {
        // MapPolyLine has a bug where if you can from a path which has elements to an empty path the line drawn
        // is not cleared from the map. This hack works around that since it causes the previous lines to be remove
        // as then doesn't draw anything on the map.
        _waypointPath.append(QVariant::fromValue(QGeoCoordinate(0, 0)));
        _waypointPath.append(QVariant::fromValue(QGeoCoordinate(0, 0)));
    }

1274
    emit waypointLinesChanged();
1275
    emit waypointPathChanged();
1276 1277
}

1278 1279 1280 1281 1282 1283
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);
1284 1285 1286
        // 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.
1287
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310
            _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);
}

1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337
/// 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
1338
void MissionController::_recalcMissionFlightStatus()
1339
{
1340
    if (!_visualItems->count()) {
1341
        return;
1342
    }
1343 1344 1345 1346

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

1347
    bool showHomePosition = _settingsItem->coordinate().isValid();
1348

DonLakeFlyer's avatar
DonLakeFlyer committed
1349
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1350

1351 1352 1353
    // 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.
1354

1355
    // No values for first item
1356
    lastCoordinateItem->setAltDifference(0.0);
1357
    lastCoordinateItem->setAzimuth(0.0);
1358
    lastCoordinateItem->setDistance(0.0);
1359

1360 1361
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1362 1363
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1364

1365
    _resetMissionFlightStatus();
1366

DonLakeFlyer's avatar
DonLakeFlyer committed
1367
    bool vtolInHover = true;
1368
    bool linkStartToHome = false;
1369 1370 1371 1372 1373 1374 1375 1376 1377 1378
    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();
        }
    }
1379

DonLakeFlyer's avatar
DonLakeFlyer committed
1380
    for (int i=0; i<_visualItems->count(); i++) {
1381
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1382 1383 1384
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1385 1386
        // Assume the worst
        item->setAzimuth(0.0);
1387
        item->setDistance(0.0);
1388

DonLakeFlyer's avatar
DonLakeFlyer committed
1389 1390 1391
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1392
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1393
                _missionFlightStatus.hoverSpeed = newSpeed;
1394
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1395 1396
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1397
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1398
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1399
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1400 1401
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1402
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1403 1404 1405 1406
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1407 1408 1409 1410 1411 1412 1413
        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
1414 1415 1416 1417 1418
        }

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

1421
        // Link back to home if first item is takeoff and we have home position
1422
        if (firstCoordinateItem && simpleItem && (simpleItem->command() == MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
1423
            if (showHomePosition) {
1424
                linkStartToHome = true;
1425 1426 1427 1428 1429 1430 1431
                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);
                }
1432 1433 1434 1435
            }
        }

        // Update VTOL state
1436
        if (simpleItem && _controllerVehicle->vtol()) {
1437
            switch (simpleItem->command()) {
1438
            case MAV_CMD_NAV_TAKEOFF:
1439 1440
                vtolInHover = false;
                break;
1441
            case MAV_CMD_NAV_VTOL_TAKEOFF:
DonLakeFlyer's avatar
DonLakeFlyer committed
1442 1443
                vtolInHover = true;
                break;
1444
            case MAV_CMD_NAV_LAND:
1445 1446
                vtolInHover = false;
                break;
1447
            case MAV_CMD_NAV_VTOL_LAND:
DonLakeFlyer's avatar
DonLakeFlyer committed
1448 1449
                vtolInHover = true;
                break;
1450
            case MAV_CMD_DO_VTOL_TRANSITION:
1451 1452 1453 1454 1455 1456
            {
                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;
1457 1458
                }
            }
1459 1460 1461
                break;
            default:
                break;
1462
            }
Don Gagne's avatar
Don Gagne committed
1463 1464
        }

1465
        _addTimeDistance(vtolInHover, 0, 0, item->additionalTimeDelay(), 0, -1);
1466

1467
        if (item->specifiesCoordinate()) {
1468 1469
            // Keep track of the min/max altitude for all waypoints so we can show altitudes as a percentage

1470
            double absoluteAltitude = item->coordinate().altitude();
1471
            if (item->coordinateHasRelativeAltitude()) {
1472 1473 1474 1475 1476
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1477 1478 1479 1480
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1481 1482 1483
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1484
                firstCoordinateItem = false;
1485 1486 1487 1488 1489 1490 1491

                // Update vehicle yaw assuming direction to next waypoint
                if (item != lastCoordinateItem) {
                    _missionFlightStatus.vehicleYaw = lastCoordinateItem->exitCoordinate().azimuthTo(item->coordinate());
                    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
                }

1492
                if (lastCoordinateItem != _settingsItem || linkStartToHome) {
1493 1494
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1495

1496
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1497 1498 1499
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1500

1501
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1502

DonLakeFlyer's avatar
DonLakeFlyer committed
1503 1504 1505
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1506
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1507
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1508

1509
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1510 1511
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1512
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1513

1514 1515
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1516
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1517
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1518 1519

                item->setMissionFlightStatus(_missionFlightStatus);
1520

1521 1522
                lastCoordinateItem = item;
            }
1523 1524
        }
    }
1525
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1526

1527 1528 1529 1530 1531 1532 1533 1534
    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();
1535
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1536 1537
    }

1538 1539 1540
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1541

DonLakeFlyer's avatar
DonLakeFlyer committed
1542 1543 1544 1545 1546 1547 1548
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1549 1550
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1551

1552 1553
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1554 1555
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1556 1557 1558

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1559
            if (item->coordinateHasRelativeAltitude()) {
1560 1561 1562 1563
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1564
                item->setTerrainPercent(qQNaN());
1565
                item->setTerrainCollision(false);
1566 1567
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1568 1569 1570 1571 1572 1573 1574
                double terrainAltitude = item->terrainAltitude();
                if (qIsNaN(terrainAltitude)) {
                    item->setTerrainPercent(qQNaN());
                    item->setTerrainCollision(false);
                } else {
                    item->setTerrainPercent((terrainAltitude - minAltSeen) / altRange);
                    item->setTerrainCollision(absoluteAltitude < terrainAltitude);
1575
                }
1576
            }
1577 1578
        }
    }
1579 1580

    _updateTimer.start(UPDATE_TIMEOUT);
1581 1582
}

1583 1584 1585
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1586 1587 1588 1589 1590
    if (_inRecalcSequence) {
        // Don't let this call recurse due to signalling
        return;
    }

1591 1592
    // Setup ascending sequence numbers for all visual items

1593
    _inRecalcSequence = true;
1594 1595 1596
    int sequenceNumber = 0;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1597 1598
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1599 1600
    }    
    _inRecalcSequence = false;
1601 1602
}

1603 1604 1605
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1606
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1607 1608 1609

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

1610 1611
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1612 1613 1614 1615 1616

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1617
        } else if (item->isSimpleItem()) {
1618 1619 1620 1621 1622
            currentParentItem->childItems()->append(item);
        }
    }
}

1623
void MissionController::_setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate)
1624
{
1625 1626
    QGeoCoordinate firstCoordinate;

1627 1628 1629 1630
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1631
    // Set the planned home position to be a delta from first coordinate
1632 1633 1634 1635
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

        if (item->specifiesCoordinate()) {
1636 1637
            firstCoordinate = item->coordinate();
            break;
1638 1639 1640
        }
    }

1641 1642 1643 1644
    // No item specifying a coordinate was found, in this case it we have a clickCoordinate use that
    if (!firstCoordinate.isValid()) {
        firstCoordinate = clickCoordinate;
    }
1645

1646 1647 1648 1649 1650 1651 1652 1653 1654
    if (firstCoordinate.isValid()) {
        QGeoCoordinate plannedHomeCoord = firstCoordinate.atDistanceAndAzimuth(30, 0);
        plannedHomeCoord.setAltitude(0);
        _settingsItem->setCoordinate(plannedHomeCoord);
    }
}

/// @param clickCoordinate The location of the user click when inserting a new item
void MissionController::_recalcAllWithClickCoordinate(QGeoCoordinate& clickCoordinate)
1655
{
1656
    if (!_flyView) {
1657
        _setPlannedHomePositionFromFirstCoordinate(clickCoordinate);
1658
    }
1659
    _recalcSequence();
1660 1661
    _recalcChildItems();
    _recalcWaypointLines();
1662
    _updateTimer.start(UPDATE_TIMEOUT);
1663 1664
}

1665 1666 1667 1668 1669 1670
void MissionController::_recalcAll(void)
{
    QGeoCoordinate emptyCoord;
    _recalcAllWithClickCoordinate(emptyCoord);
}

1671
/// Initializes a new set of mission items
1672
void MissionController::_initAllVisualItems(void)
1673
{
1674 1675
    // Setup home position at index 0

1676 1677 1678
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1679 1680
        return;
    }
1681
    if (!_flyView) {
1682 1683
        _settingsItem->setIsCurrentItem(true);
    }
1684

1685
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1686
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1687
    }
1688

1689 1690 1691
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1692

1693 1694 1695 1696
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1697

1698
    _recalcAll();
1699

1700
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1701 1702 1703
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1704
    emit containsItemsChanged(containsItems());
1705
    emit plannedHomePositionChanged(plannedHomePosition());
1706

1707
    setDirty(false);
1708 1709
}

1710
void MissionController::_deinitAllVisualItems(void)
1711
{
1712 1713 1714
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1715 1716
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1717 1718
    }

1719
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1720
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1721 1722
}

1723
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1724
{
1725
    setDirty(false);
1726

1727
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1728 1729
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1730 1731
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1732
    connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged,                this, &MissionController::_recalcMissionFlightStatus);
1733
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1734
    connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged,                 this, &MissionController::_recalcMissionFlightStatus);
1735
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1736

1737 1738 1739 1740 1741 1742 1743 1744
    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";
        }
1745 1746
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1747
        if (complexItem) {
1748
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
1749
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
1750 1751 1752
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1753
    }
1754 1755
}

1756
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1757
{
1758 1759
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1760 1761
}

1762
void MissionController::_itemCommandChanged(void)
1763
{
1764 1765
    _recalcChildItems();
    _recalcWaypointLines();
1766 1767
}

1768
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1769
{
1770 1771 1772 1773 1774 1775
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1776

1777 1778
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1779
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1780 1781
        return;
    }
1782

1783 1784
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1785 1786
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1787 1788 1789
    connect(_missionManager, &MissionManager::inProgressChanged,        this, &MissionController::_inProgressChanged);
    connect(_missionManager, &MissionManager::progressPct,              this, &MissionController::_progressPctChanged);
    connect(_missionManager, &MissionManager::currentIndexChanged,      this, &MissionController::_currentMissionIndexChanged);
1790 1791
    connect(_missionManager, &MissionManager::currentIndexChanged,      this, &MissionController::remainingDistanceChanged);
    connect(_missionManager, &MissionManager::currentIndexChanged,      this, &MissionController::remainingTimeChanged);
1792 1793
    connect(_missionManager, &MissionManager::lastCurrentIndexChanged,  this, &MissionController::resumeMissionIndexChanged);
    connect(_missionManager, &MissionManager::resumeMissionReady,       this, &MissionController::resumeMissionReady);
1794
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1795 1796 1797 1798
    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);
1799

1800 1801
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1802
    }
1803

1804
    emit complexMissionItemNamesChanged();
1805
    emit resumeMissionIndexChanged();
1806 1807
}

1808
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1809
{
1810
    if (_visualItems) {
1811 1812
        bool currentDirtyBit = dirty();

1813
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1814
        if (settingsItem) {
1815
            settingsItem->setHomePositionFromVehicle(homePosition);
1816
        } else {
1817
            qWarning() << "First item is not MissionSettingsItem";
1818
        }
1819 1820 1821 1822 1823 1824

        if (!currentDirtyBit) {
            // Don't let this trip the dirty bit. Otherwise plan will keep getting marked dirty if vehicle home
            // changes.
            _visualItems->setDirty(false);
        }
1825
    }
1826 1827 1828
}

void MissionController::_inProgressChanged(bool inProgress)
1829
{
1830
    emit syncInProgressChanged(inProgress);
1831
}
1832

1833
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1834
{
1835 1836
    bool        found = false;
    double      foundAltitude;
1837
    int         foundAltitudeMode;
1838

1839 1840 1841 1842 1843 1844
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1847 1848 1849
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1850 1851 1852
                if (simpleItem->specifiesAltitude()) {
                    foundAltitude = simpleItem->altitude()->rawValue().toDouble();
                    foundAltitudeMode = simpleItem->altitudeMode();
1853
                    found = true;
1854
                    break;
1855 1856
                }
            }
1857 1858 1859
        }
    }

1860
    if (found) {
1861
        *prevAltitude = foundAltitude;
1862
        *prevAltitudeMode = foundAltitudeMode;
1863 1864 1865
    }

    return found;
1866
}
1867 1868 1869 1870 1871 1872 1873 1874 1875 1876 1877 1878 1879

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

1880
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1881
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1882
{
1883
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
1884

Don Gagne's avatar
Don Gagne committed
1885 1886
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1887
    visualItems->insert(0, settingsItem);
1888

1889 1890 1891 1892 1893 1894 1895 1896 1897 1898 1899 1900 1901 1902 1903 1904 1905 1906 1907 1908 1909 1910 1911 1912 1913
    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;
                    }
1914 1915
                }
            }
1916

1917 1918 1919
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1920
        }
Don Gagne's avatar
Don Gagne committed
1921 1922
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1923 1924
    }
}
1925

1926
int MissionController::resumeMissionIndex(void) const
1927
{
1928

1929
    int resumeIndex = 0;
1930

1931
    if (_flyView) {
1932
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1933
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1934 1935
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1936 1937
        } else {
            resumeIndex = 0;
1938 1939 1940 1941 1942
        }
    }

    return resumeIndex;
}
1943

1944 1945
int MissionController::currentMissionIndex(void) const
{
1946
    if (!_flyView) {
1947 1948 1949 1950 1951 1952 1953 1954 1955 1956
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

1957
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1958
{
1959
    if (_flyView) {
1960
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1961 1962 1963
            sequenceNumber++;
        }

1964 1965
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1966 1967
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1968
        emit currentMissionIndexChanged(currentMissionIndex());
1969 1970
    }
}
1971

1972
bool MissionController::syncInProgress(void) const
1973
{
1974
    return _missionManager->inProgress();
1975 1976 1977 1978 1979 1980 1981 1982 1983 1984 1985 1986
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1987
    }
1988
}
1989

1990 1991
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1992 1993
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, vehicle);
1994

1995 1996 1997 1998 1999 2000
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

2001
        if (!_flyView) {
2002 2003 2004 2005 2006 2007
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
2008 2009 2010
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
2011
        if (simpleItem) {
2012 2013 2014 2015 2016
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
2017 2018 2019
        }
    }
}
2020 2021 2022 2023 2024 2025 2026 2027 2028 2029 2030 2031 2032

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
2033 2034 2035 2036 2037 2038 2039 2040
    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();
    }
2041
}
2042 2043 2044 2045 2046

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

2047
    complexItems.append(_circularSurveyMissionItemName);
2048
    complexItems.append(_surveyMissionItemName);
2049
    complexItems.append(patternCorridorScanName);
2050
    if (_controllerVehicle->fixedWing()) {
2051
        complexItems.append(patternFWLandingName);
2052
    }
2053
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
2054
        complexItems.append(patternStructureScanName);
2055
    }
2056

2057
    return qgcApp()->toolbox()->corePlugin()->complexMissionItemNames(_controllerVehicle, complexItems);
2058
}
2059

2060 2061
void MissionController::resumeMission(int resumeIndex)
{
2062
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
2063 2064
        resumeIndex--;
    }
2065
    _missionManager->generateResumeMission(resumeIndex);
2066
}
2067 2068 2069 2070 2071 2072 2073 2074 2075

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
2076 2077 2078 2079 2080 2081 2082 2083 2084 2085

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

2087 2088 2089 2090 2091 2092 2093
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
2094 2095 2096 2097 2098 2099

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
2100 2101 2102

bool MissionController::showPlanFromManagerVehicle (void)
{
2103
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
DonLakeFlyer's avatar
DonLakeFlyer committed
2104 2105
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
2106
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
2107 2108 2109 2110 2111 2112 2113 2114 2115 2116 2117 2118 2119 2120 2121 2122 2123 2124 2125
    } 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;
        }
    }
}

2126
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2127
{
2128
    // Fly view always reloads on send complete
2129
    if (!error && _flyView) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2130 2131 2132 2133
        showPlanFromManagerVehicle();
    }
}

2134
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2135
{
2136 2137 2138 2139
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2140
}
2141 2142 2143 2144 2145 2146

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

2147 2148 2149 2150 2151 2152 2153 2154 2155 2156 2157 2158 2159 2160 2161 2162 2163 2164 2165 2166 2167 2168 2169 2170 2171 2172 2173 2174 2175 2176 2177 2178 2179 2180 2181 2182 2183 2184 2185 2186 2187 2188 2189 2190 2191 2192 2193 2194 2195 2196 2197 2198 2199 2200 2201 2202 2203 2204 2205 2206 2207 2208 2209 2210 2211 2212 2213 2214 2215 2216 2217 2218 2219 2220 2221 2222 2223 2224 2225 2226 2227 2228 2229 2230 2231 2232 2233 2234 2235 2236 2237 2238 2239 2240 2241 2242 2243 2244 2245 2246 2247 2248 2249 2250 2251 2252 2253 2254 2255 2256 2257 2258 2259 2260 2261 2262 2263 2264 2265 2266 2267 2268 2269 2270 2271 2272 2273 2274 2275 2276 2277 2278 2279 2280 2281 2282 2283 2284 2285 2286 2287 2288 2289 2290 2291 2292 2293 2294 2295 2296 2297 2298 2299 2300 2301 2302 2303 2304 2305 2306 2307 2308 2309 2310 2311 2312 2313 2314 2315 2316 2317 2318 2319 2320 2321 2322
bool MissionController::remainingDistanceAndTime(double &remainingDistance, double &remainingTime, int missionIndex) const
{
    if (   _visualItems == nullptr
        || _visualItems->count() < 1
        || !_flyView
        || missionIndex < 1
        || _visualItems->count() < missionIndex) {
        return false;
    }

    remainingDistance = 0;
    remainingTime = 0;

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


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

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

    // No values for first item
    lastCoordinateItem->setAltDifference(0.0);
    lastCoordinateItem->setAzimuth(0.0);
    lastCoordinateItem->setDistance(0.0);

    const double homePositionAltitude = _settingsItem->coordinate().altitude();

    bool linkStartToHome    = false;
    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();
        }
    }

    // determine speed at waypoint with index currentMissionIdx-1
    double currentSpeed = _settingsItem->specifiedFlightSpeed();
    currentSpeed = !qIsNaN(currentSpeed) ? currentSpeed : 5;
    for (int i = 1; i < missionIndex-1; ++i) {
        SimpleMissionItem* simpleItem = _visualItems->value<SimpleMissionItem*>(i);

        if (simpleItem != nullptr) {
            double speed = simpleItem->specifiedFlightSpeed();
            if (!qIsNaN(speed))
                currentSpeed = speed;
        }
    }

    // iterate over mission items starting at currentMissionIdx-1 and determine time and distance
    for (int i=missionIndex-1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);

        // Assume the worst
        item->setAzimuth(0.0);
        item->setDistance(0.0);

        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
            currentSpeed = newSpeed;
        }

        // Link back to home if first item is takeoff and we have home position
        if (firstCoordinateItem && simpleItem && (simpleItem->command() == MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
            if (showHomePosition) {
                linkStartToHome = true;
                if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
                    // We have to special case takeoff, assuming vehicle takes off straight up to specified altitude

                    QGeoCoordinate itemCoordinate = item->exitCoordinate();
                    QGeoCoordinate settingsCoordinate = _settingsItem->coordinate();
                    if (item->exitCoordinateHasRelativeAltitude()) {
                        itemCoordinate.setAltitude(homePositionAltitude + settingsCoordinate.altitude());
                    }

                    double altDifference = settingsCoordinate.altitude() - itemCoordinate.altitude();

                    double takeoffTime = qAbs(altDifference) / _appSettings->offlineEditingAscentSpeed()->rawValue().toDouble();
                    remainingTime += takeoffTime;
                }
            }
        }

        remainingTime += item->additionalTimeDelay();

        if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
            firstCoordinateItem = false;

            if (lastCoordinateItem != _settingsItem || linkStartToHome) {
                // This is a subsequent waypoint or we are forcing the first waypoint back to home

                QGeoCoordinate  currentCoord =  item->coordinate();
                QGeoCoordinate  prevCoord =     lastCoordinateItem->exitCoordinate();

                if (item != _settingsItem && item->coordinateHasRelativeAltitude()) {
                    currentCoord.setAltitude(homePositionAltitude + currentCoord.altitude());
                }
                if (lastCoordinateItem != _settingsItem && lastCoordinateItem->exitCoordinateHasRelativeAltitude()) {
                    prevCoord.setAltitude(homePositionAltitude + prevCoord.altitude());
                }

                double distance = prevCoord.distanceTo(currentCoord);
                double time = distance / currentSpeed;

                remainingDistance += distance;
                remainingTime += time;
            }

            lastCoordinateItem = item;
        }
    }

    if (linkEndToHome && lastCoordinateItem != _settingsItem) {

        QGeoCoordinate  currentCoord =  lastCoordinateItem->coordinate();
        QGeoCoordinate  prevCoord =     _settingsItem->exitCoordinate();

        if (lastCoordinateItem != _settingsItem && lastCoordinateItem->coordinateHasRelativeAltitude()) {
            currentCoord.setAltitude(homePositionAltitude + currentCoord.altitude());
        }

        double altDifference = currentCoord.altitude() - prevCoord.altitude();
        double distance      = currentCoord.distanceTo(prevCoord);

        double time     = distance / currentSpeed;
        double landTime = qAbs(altDifference) / _appSettings->offlineEditingDescentSpeed()->rawValue().toDouble();

        remainingDistance   += distance;
        remainingTime       += time + landTime;
    }

    return true;
}

double MissionController::remainingDistance(int missionIndex) const
{
    double remainingDistance = 0, remainingTime = 0;
    if (remainingDistanceAndTime(remainingDistance, remainingTime, missionIndex))
        return remainingDistance;

    return -1;
}

double MissionController::remainingTime(int missionIndex) const
{
    double remainingDistance = 0, remainingTime = 0;
    if (remainingDistanceAndTime(remainingDistance, remainingTime, missionIndex))
        return remainingTime;

    return -1;
}

double MissionController::remainingDistance() const
{
    if (_missionManager != nullptr)
        return remainingDistance(_missionManager->currentIndex());

    return -1;
}

double MissionController::remainingTime() const
{
    if (_missionManager != nullptr)
        return remainingTime(_missionManager->currentIndex());

    return -1;
}

2323 2324 2325 2326 2327 2328 2329 2330
VisualMissionItem* MissionController::currentPlanViewItem(void) const
{
    return _currentPlanViewItem;
}

void MissionController::setCurrentPlanViewIndex(int sequenceNumber, bool force)
{
    if(_visualItems && (force || sequenceNumber != _currentPlanViewIndex)) {
2331
        _currentPlanViewItem  = nullptr;
2332 2333 2334 2335 2336 2337 2338 2339 2340 2341 2342 2343 2344 2345 2346
        _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();
    }
}
2347 2348 2349

void MissionController::_updateTimeout()
{
Gus Grubba's avatar
Gus Grubba committed
2350
    QGeoCoordinate firstCoordinate;
2351
    QGeoCoordinate takeoffCoordinate;
2352
    QGCGeoBoundingCube boundingCube;
2353 2354 2355 2356
    double north = 0.0;
    double south = 180.0;
    double east  = 0.0;
    double west  = 360.0;
2357 2358
    double minAlt = QGCGeoBoundingCube::MaxAlt;
    double maxAlt = QGCGeoBoundingCube::MinAlt;
2359 2360 2361 2362 2363 2364
    for (int i = 1; i < _visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        if(item->isSimpleItem()) {
            SimpleMissionItem* pSimpleItem = qobject_cast<SimpleMissionItem*>(item);
            if(pSimpleItem) {
                switch(pSimpleItem->command()) {
2365
                case MAV_CMD_NAV_TAKEOFF:
2366 2367 2368
                case MAV_CMD_NAV_WAYPOINT:
                case MAV_CMD_NAV_LAND:
                if(pSimpleItem->coordinate().isValid()) {
2369
                    if((MAV_CMD)pSimpleItem->command() == MAV_CMD_NAV_TAKEOFF) {
Gus Grubba's avatar
Gus Grubba committed
2370 2371 2372 2373
                        takeoffCoordinate = pSimpleItem->coordinate();
                    } else if(!firstCoordinate.isValid()) {
                        firstCoordinate = pSimpleItem->coordinate();
                    }
2374 2375
                    double lat = pSimpleItem->coordinate().latitude()  + 90.0;
                    double lon = pSimpleItem->coordinate().longitude() + 180.0;
2376
                    double alt = pSimpleItem->coordinate().altitude();
2377 2378 2379 2380
                    north  = fmax(north, lat);
                    south  = fmin(south, lat);
                    east   = fmax(east,  lon);
                    west   = fmin(west,  lon);
2381 2382
                    minAlt = fmin(minAlt, alt);
                    maxAlt = fmax(maxAlt, alt);
2383 2384 2385 2386 2387 2388 2389 2390 2391
                }
                break;
                default:
                    break;
                }
            }
        } else {
            ComplexMissionItem* pComplexItem = qobject_cast<ComplexMissionItem*>(item);
            if(pComplexItem) {
2392 2393
                QGCGeoBoundingCube bc = pComplexItem->boundingCube();
                if(bc.isValid()) {
Gus Grubba's avatar
Gus Grubba committed
2394 2395 2396
                    if(!firstCoordinate.isValid() && pComplexItem->coordinate().isValid()) {
                        firstCoordinate = pComplexItem->coordinate();
                    }
2397 2398 2399 2400 2401 2402
                    north  = fmax(north, bc.pointNW.latitude()  + 90.0);
                    south  = fmin(south, bc.pointSE.latitude()  + 90.0);
                    east   = fmax(east,  bc.pointNW.longitude() + 180.0);
                    west   = fmin(west,  bc.pointSE.longitude() + 180.0);
                    minAlt = fmin(minAlt, bc.pointNW.altitude());
                    maxAlt = fmax(maxAlt, bc.pointSE.altitude());
2403 2404 2405 2406
                }
            }
        }
    }
Gus Grubba's avatar
Gus Grubba committed
2407 2408 2409 2410 2411 2412 2413 2414 2415
    //-- Figure out where this thing is taking off from
    if(!takeoffCoordinate.isValid()) {
        if(firstCoordinate.isValid()) {
            takeoffCoordinate = firstCoordinate;
        } else {
            takeoffCoordinate = plannedHomePosition();
        }
    }
    //-- Build bounding "cube"
2416 2417 2418
    boundingCube = QGCGeoBoundingCube(
        QGeoCoordinate(north - 90.0, west - 180.0, minAlt),
        QGeoCoordinate(south - 90.0, east - 180.0, maxAlt));
2419 2420
    if(_travelBoundingCube != boundingCube || _takeoffCoordinate != takeoffCoordinate) {
        _takeoffCoordinate  = takeoffCoordinate;
2421
        _travelBoundingCube = boundingCube;
2422
        emit missionBoundingCubeChanged();
2423
        qCDebug(MissionControllerLog) << "Bounding cube:" << _travelBoundingCube.pointNW << _travelBoundingCube.pointSE;
2424 2425 2426 2427 2428 2429 2430
    }
}

void MissionController::_complexBoundingBoxChanged()
{
    _updateTimer.start(UPDATE_TIMEOUT);
}