MissionController.cc 93.3 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
}

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

90 91
}

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

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

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

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

135 136
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

228 229 230 231
void MissionController::_warnIfTerrainFrameUsed(void)
{
    for (int i=1; i<_visualItems->count(); i++) {
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(i));
232
        if (simpleItem && simpleItem->altitudeMode() == QGroundControlQmlGlobal::AltitudeModeTerrainFrame) {
233 234 235 236 237 238
            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;
        }
    }
}

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

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

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

    return endActionSet;
}

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

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

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

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

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

    deleteParent->deleteLater();

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

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

339
        convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
340

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

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

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

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

383 384
    // 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);
385

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

389 390 391 392 393 394 395 396 397
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)) {
398
            newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
399 400 401
            return -1; // can not add this takeoff command for this vehicle
        }
    }
402 403 404 405 406 407
    if (newItem->specifiesAltitude()) {        
        newItem->altitude()->setRawValue(missionItem.relativeAltitude());
        newItem->setAltitudeMode(QGroundControlQmlGlobal::AltitudeMode::AltitudeModeRelative);
    }
    newItem->setMissionFlightStatus(_missionFlightStatus);
    _visualItems->insert(i, newItem);
408

409 410 411 412 413 414 415 416 417 418 419 420 421 422
    return newItem->sequenceNumber();
}

int MissionController::insertSimpleMissionItem(SimpleMissionItem &missionItem, int i)
{
    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
423 424
        }
    }
Valentin Platzgummer's avatar
Valentin Platzgummer committed
425
    newItem->setMissionFlightStatus(_missionFlightStatus);
426 427 428 429 430
    _visualItems->insert(i, newItem);

    return newItem->sequenceNumber();
}

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

442 443
    double  prevAltitude;
    int     prevAltitudeMode;
444

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

    _recalcAll();

    return newItem->sequenceNumber();
}

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

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

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

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

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

    return _insertComplexMissionItemWorker(newItem, i);
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

    return true;
}

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

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

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

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

746 747 748 749
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
750
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
751 752
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
753 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
    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) {
779
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
780
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
781
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
782
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
783 784 785 786 787 788 789 790 791 792 793 794 795
                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();

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

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

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

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

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

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

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

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

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

    return true;
966 967
}

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

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

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

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

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

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

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

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

    _initLoadedVisualItems(loadedVisualItems);

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

1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055
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;
}

1056
bool MissionController::setTakeoffCommand(SimpleMissionItem &missionItem)
1057
{
1058
    if (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() || _controllerVehicle->multiRotor()) {
1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069
        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;
}

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

    return true;
}

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

1085
    // Mission settings
1086

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

1100
    // Save the visual items
1101

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

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

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

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

1124
    json[_jsonItemsKey] = rgJsonMissionItems;
1125 1126
}

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

    // Convert to fixed altitudes

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

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

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

    distanceOk = true;

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

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

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

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

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

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

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

1213 1214 1215 1216 1217 1218
        // 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;
1219
            }
1220 1221
        }

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

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

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

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

1265 1266 1267 1268 1269 1270 1271 1272
    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)));
    }

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

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

1310 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
/// 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
1337
void MissionController::_recalcMissionFlightStatus()
1338
{
1339
    if (!_visualItems->count()) {
1340
        return;
1341
    }
1342 1343 1344 1345

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

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

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

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

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

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

1364
    _resetMissionFlightStatus();
1365

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

                item->setMissionFlightStatus(_missionFlightStatus);
1519

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

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

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

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

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

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

    _updateTimer.start(UPDATE_TIMEOUT);
1580 1581
}

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

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

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

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

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

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

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

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

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

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

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

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

1645 1646 1647 1648 1649 1650 1651 1652 1653
    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)
1654
{
1655
    if (!_flyView) {
1656
        _setPlannedHomePositionFromFirstCoordinate(clickCoordinate);
1657
    }
1658
    _recalcSequence();
1659 1660
    _recalcChildItems();
    _recalcWaypointLines();
1661
    _updateTimer.start(UPDATE_TIMEOUT);
1662 1663
}

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

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

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

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

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

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

1697
    _recalcAll();
1698

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

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

1706
    setDirty(false);
1707 1708
}

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

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

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

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

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

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

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

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

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

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

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

1797 1798
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1799
    }
1800

1801
    emit complexMissionItemNamesChanged();
1802
    emit resumeMissionIndexChanged();
1803 1804
}

1805
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1806
{
1807
    if (_visualItems) {
1808 1809
        bool currentDirtyBit = dirty();

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

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

void MissionController::_inProgressChanged(bool inProgress)
1826
{
1827
    emit syncInProgressChanged(inProgress);
1828
}
1829

1830
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1831
{
1832 1833
    bool        found = false;
    double      foundAltitude;
1834
    int         foundAltitudeMode;
1835

1836 1837 1838 1839 1840 1841
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

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

1857
    if (found) {
1858
        *prevAltitude = foundAltitude;
1859
        *prevAltitudeMode = foundAltitudeMode;
1860 1861 1862
    }

    return found;
1863
}
1864 1865 1866 1867 1868 1869 1870 1871 1872 1873 1874 1875 1876

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

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

Don Gagne's avatar
Don Gagne committed
1882 1883
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1884
    visualItems->insert(0, settingsItem);
1885

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

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

1923
int MissionController::resumeMissionIndex(void) const
1924
{
1925

1926
    int resumeIndex = 0;
1927

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

    return resumeIndex;
}
1940

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

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

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

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

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1984
    }
1985
}
1986

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

1992 1993 1994 1995 1996 1997
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

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

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

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
2030 2031 2032 2033 2034 2035 2036 2037
    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();
    }
2038
}
2039 2040 2041 2042 2043

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

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

2054
    return qgcApp()->toolbox()->corePlugin()->complexMissionItemNames(_controllerVehicle, complexItems);
2055
}
2056

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

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

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

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

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
2097 2098 2099

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

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

2131
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2132
{
2133 2134 2135 2136
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2137
}
2138 2139 2140 2141 2142 2143 2144 2145 2146 2147 2148 2149 2150 2151 2152 2153 2154 2155 2156 2157 2158 2159 2160 2161 2162 2163 2164 2165 2166 2167

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

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

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

void MissionController::_updateTimeout()
{
Gus Grubba's avatar
Gus Grubba committed
2171
    QGeoCoordinate firstCoordinate;
2172
    QGeoCoordinate takeoffCoordinate;
2173
    QGCGeoBoundingCube boundingCube;
2174 2175 2176 2177
    double north = 0.0;
    double south = 180.0;
    double east  = 0.0;
    double west  = 360.0;
2178 2179
    double minAlt = QGCGeoBoundingCube::MaxAlt;
    double maxAlt = QGCGeoBoundingCube::MinAlt;
2180 2181 2182 2183 2184 2185
    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()) {
2186
                case MAV_CMD_NAV_TAKEOFF:
2187 2188 2189
                case MAV_CMD_NAV_WAYPOINT:
                case MAV_CMD_NAV_LAND:
                if(pSimpleItem->coordinate().isValid()) {
2190
                    if((MAV_CMD)pSimpleItem->command() == MAV_CMD_NAV_TAKEOFF) {
Gus Grubba's avatar
Gus Grubba committed
2191 2192 2193 2194
                        takeoffCoordinate = pSimpleItem->coordinate();
                    } else if(!firstCoordinate.isValid()) {
                        firstCoordinate = pSimpleItem->coordinate();
                    }
2195 2196
                    double lat = pSimpleItem->coordinate().latitude()  + 90.0;
                    double lon = pSimpleItem->coordinate().longitude() + 180.0;
2197
                    double alt = pSimpleItem->coordinate().altitude();
2198 2199 2200 2201
                    north  = fmax(north, lat);
                    south  = fmin(south, lat);
                    east   = fmax(east,  lon);
                    west   = fmin(west,  lon);
2202 2203
                    minAlt = fmin(minAlt, alt);
                    maxAlt = fmax(maxAlt, alt);
2204 2205 2206 2207 2208 2209 2210 2211 2212
                }
                break;
                default:
                    break;
                }
            }
        } else {
            ComplexMissionItem* pComplexItem = qobject_cast<ComplexMissionItem*>(item);
            if(pComplexItem) {
2213 2214
                QGCGeoBoundingCube bc = pComplexItem->boundingCube();
                if(bc.isValid()) {
Gus Grubba's avatar
Gus Grubba committed
2215 2216 2217
                    if(!firstCoordinate.isValid() && pComplexItem->coordinate().isValid()) {
                        firstCoordinate = pComplexItem->coordinate();
                    }
2218 2219 2220 2221 2222 2223
                    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());
2224 2225 2226 2227
                }
            }
        }
    }
Gus Grubba's avatar
Gus Grubba committed
2228 2229 2230 2231 2232 2233 2234 2235 2236
    //-- Figure out where this thing is taking off from
    if(!takeoffCoordinate.isValid()) {
        if(firstCoordinate.isValid()) {
            takeoffCoordinate = firstCoordinate;
        } else {
            takeoffCoordinate = plannedHomePosition();
        }
    }
    //-- Build bounding "cube"
2237 2238 2239
    boundingCube = QGCGeoBoundingCube(
        QGeoCoordinate(north - 90.0, west - 180.0, minAlt),
        QGeoCoordinate(south - 90.0, east - 180.0, maxAlt));
2240 2241
    if(_travelBoundingCube != boundingCube || _takeoffCoordinate != takeoffCoordinate) {
        _takeoffCoordinate  = takeoffCoordinate;
2242
        _travelBoundingCube = boundingCube;
2243
        emit missionBoundingCubeChanged();
2244
        qCDebug(MissionControllerLog) << "Bounding cube:" << _travelBoundingCube.pointNW << _travelBoundingCube.pointSE;
2245 2246 2247 2248 2249 2250 2251
    }
}

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