MissionController.cc 90.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 262 263
/// @return true: Mission end action was added to end of list
bool MissionController::_convertToMissionItems(QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
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 298
    _convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
    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
int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
{
    int sequenceNumber = _nextSequenceNumber();
392
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
393
    newItem->setSequenceNumber(sequenceNumber);
394
    newItem->setCommand((_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_DO_SET_ROI_LOCATION) ?
395 396
        MAV_CMD_DO_SET_ROI_LOCATION :
        MAV_CMD_DO_SET_ROI));
397
    _initVisualItem(newItem);
398
    newItem->setCoordinate(coordinate);
399

400 401
    double  prevAltitude;
    int     prevAltitudeMode;
402

403 404
    if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
        newItem->altitude()->setRawValue(prevAltitude);
405
        newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
406 407 408 409 410 411 412 413
    }
    _visualItems->insert(i, newItem);

    _recalcAll();

    return newItem->sequenceNumber();
}

414
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
415
{
416 417
    ComplexMissionItem* newItem;

418
    int sequenceNumber = _nextSequenceNumber();
419
    if (itemName == _surveyMissionItemName) {
420
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
421
        newItem->setCoordinate(mapCenterCoordinate);
422
    } else if (itemName == patternFWLandingName) {
423
        newItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, _visualItems /* parent */);
424
    } else if (itemName == patternStructureScanName) {
425
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
426
    } else if (itemName == patternCorridorScanName) {
427
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
428 429
    } else if (itemName == _circularSurveyMissionItemName) {
        newItem = new CircularSurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
430 431 432 433 434
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }

435 436 437
    return _insertComplexMissionItemWorker(newItem, i);
}

438
int MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int i)
439 440 441 442
{
    ComplexMissionItem* newItem;

    if (itemName == _surveyMissionItemName) {
443
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
444 445
    } else if (itemName == _circularSurveyMissionItemName) {
        newItem = new CircularSurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
446
    } else if (itemName == patternStructureScanName) {
447
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
448
    } else if (itemName == patternCorridorScanName) {
449
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
450 451 452 453 454 455 456 457 458 459 460 461 462
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return _nextSequenceNumber();
    }

    return _insertComplexMissionItemWorker(newItem, i);
}

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

463
    if (surveyStyleItem) {
464
        bool rollSupported  = false;
465
        bool pitchSupported = false;
466
        bool yawSupported   = false;
467 468 469

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

470 471
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
        CameraSection* cameraSection = settingsItem->cameraSection();
472

473
        // Set camera to photo mode (leave alone if user already specified)
474
        if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
475
            cameraSection->setSpecifyCameraMode(true);
476
            cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
477
        }
478

479
        // Point gimbal straight down
480
        if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
481 482 483
            // If the user already specified a gimbal angle leave it alone
            if (!cameraSection->specifyGimbal()) {
                cameraSection->setSpecifyGimbal(true);
484
                cameraSection->gimbalPitch()->setRawValue(-90.0);
485 486
            }
        }
487
    }
488

489 490
    complexItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(complexItem);
491

492 493 494 495 496
    if (i == -1) {
        _visualItems->append(complexItem);
    } else {
        _visualItems->insert(i, complexItem);
    }
497

498
    //-- Keep track of bounding box changes in complex items
499 500
    if(!complexItem->isSimpleItem()) {
        connect(complexItem, &ComplexMissionItem::boundingCubeChanged, this, &MissionController::_complexBoundingBoxChanged);
501
    }
502 503
    _recalcAll();

504
    return complexItem->sequenceNumber();
505 506
}

507 508
void MissionController::removeMissionItem(int index)
{
509 510 511 512 513
    if (index <= 0 || index >= _visualItems->count()) {
        qWarning() << "MissionController::removeMissionItem called with bad index - count:index" << _visualItems->count() << index;
        return;
    }

514
    bool removeSurveyStyle = _visualItems->value<SurveyComplexItem*>(index) || _visualItems->value<CorridorScanComplexItem*>(index);
515
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
516

517
    _deinitVisualItem(item);
518
    item->deleteLater();
519

520 521
    if (removeSurveyStyle) {
        // Determine if the mission still has another survey style item in it
522 523
        bool foundSurvey = false;
        for (int i=1; i<_visualItems->count(); i++) {
524
            if (_visualItems->value<SurveyComplexItem*>(i) || _visualItems->value<CorridorScanComplexItem*>(i)) {
525 526 527 528 529
                foundSurvey = true;
                break;
            }
        }

530
        // If there is no longer a survey item in the mission remove added commands
531 532 533 534
        if (!foundSurvey) {
            bool rollSupported = false;
            bool pitchSupported = false;
            bool yawSupported = false;
535 536
            MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
            CameraSection* cameraSection = settingsItem->cameraSection();
537
            if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
538
                if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
539 540 541
                    cameraSection->setSpecifyGimbal(false);
                }
            }
542
            if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
543 544
                cameraSection->setSpecifyCameraMode(false);
            }
545 546 547
        }
    }

548
    _recalcAll();
549
    setDirty(true);
550 551
}

552
void MissionController::removeAll(void)
553
{
554 555
    if (_visualItems) {
        _deinitAllVisualItems();
DonLakeFlyer's avatar
DonLakeFlyer committed
556
        _visualItems->clearAndDeleteContents();
Don Gagne's avatar
Don Gagne committed
557
        _visualItems->deleteLater();
558
        _settingsItem = nullptr;
559
        _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
560
        _addMissionSettings(_visualItems, false /* addToCenter */);
561
        _initAllVisualItems();
562
        setDirty(true);
563
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
564 565 566
    }
}

567
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
568 569 570 571 572 573 574 575 576
{
    // 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)) {
577 578 579
        return false;
    }

580
    // Read complex items
581
    QList<SurveyComplexItem*> surveyItems;
582 583 584 585
    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];
586

587 588 589 590 591
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

592
        SurveyComplexItem* item = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems /* parent */);
Don Gagne's avatar
Don Gagne committed
593 594
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
595
            surveyItems.append(item);
596 597
        } else {
            return false;
598
        }
599
    }
600

601 602 603 604 605
    // 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
606
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
607

608
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
609 610 611 612
    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
613
        if (nextComplexItemIndex < surveyItems.count()) {
614
            SurveyComplexItem* complexItem = surveyItems[nextComplexItemIndex];
615 616 617 618 619 620 621 622 623 624 625 626 627 628

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

629 630 631 632 633
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
634
            const QJsonObject itemObject = itemValue.toObject();
635
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
Don Gagne's avatar
Don Gagne committed
636
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
637
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
638
                nextSequenceNumber = item->lastSequenceNumber() + 1;
639
                visualItems->append(item);
640 641 642 643
            } else {
                return false;
            }
        }
644
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
645 646

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

Don Gagne's avatar
Don Gagne committed
649
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
650
            MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
651 652 653
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
654 655 656 657
        } else {
            return false;
        }
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
658
        _addMissionSettings(visualItems, true /* addToCenter */);
659 660 661 662 663
    }

    return true;
}

664
bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
665 666 667 668 669 670
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
671
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
672 673
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
674 675 676 677 678 679 680
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

681
    // Mission Settings
682
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
683

684 685
    if (_masterController->offline()) {
        // We only update if offline since if we are online we use the online vehicle settings
686
        appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType(static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt())));
687
        if (json.contains(_jsonVehicleTypeKey)) {
688
            appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType(static_cast<MAV_TYPE>(json[_jsonVehicleTypeKey].toInt())));
689
        }
690
    }
691
    if (json.contains(_jsonCruiseSpeedKey)) {
692
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
693 694
    }
    if (json.contains(_jsonHoverSpeedKey)) {
695
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
696 697
    }

698 699 700 701
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
702
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
703 704
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730
    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) {
731
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
732
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
733
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
734
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
735 736 737 738 739 740 741 742 743 744 745 746 747
                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();

748
            if (complexItemType == SurveyComplexItem::jsonComplexItemTypeValue) {
Don Gagne's avatar
Don Gagne committed
749
                qCDebug(MissionControllerLog) << "Loading Survey: nextSequenceNumber" << nextSequenceNumber;
750
                SurveyComplexItem* surveyItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
Don Gagne's avatar
Don Gagne committed
751 752 753 754 755 756
                if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(surveyItem);
757
            } else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
758
                qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
759
                FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
760 761 762 763 764 765
                if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(landingItem);
766 767
            } else if (complexItemType == StructureScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Structure Scan: nextSequenceNumber" << nextSequenceNumber;
768
                StructureScanComplexItem* structureItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
769 770 771 772 773 774
                if (!structureItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = structureItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Structure Scan load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(structureItem);
775 776
            } else if (complexItemType == CorridorScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Corridor Scan: nextSequenceNumber" << nextSequenceNumber;
777
                CorridorScanComplexItem* corridorItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
778 779 780 781 782 783
                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
784 785 786 787 788 789 790 791 792
            } 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);
793
            } else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
794
                qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
795
                MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
796 797 798 799 800 801
                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
802 803 804 805 806 807 808 809 810 811 812 813 814
            } 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);
815
            if (doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
816
                bool found = false;
817
                int findDoJumpId = static_cast<int>(doJumpItem->missionItem().param1());
Don Gagne's avatar
Don Gagne committed
818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838
                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;
}

839 840 841 842 843 844 845 846
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;
847 848 849 850 851 852
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
853 854

    if (fileVersion == 1) {
855
        return _loadJsonMissionFileV1(json, visualItems, errorString);
856
    } else {
857
        return _loadJsonMissionFileV2(json, visualItems, errorString);
858 859 860
    }
}

861
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
862
{
863 864
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
865 866 867 868 869 870 871 872 873

    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;
874
            plannedHomePositionInFile = true;
875 876 877
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
878
            plannedHomePositionInFile = false;
879 880 881 882
        }
    }

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

887
        while (!stream.atEnd()) {
888
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
889 890

            if (item->load(stream)) {
891 892 893 894 895 896
                if (firstItem && plannedHomePositionInFile) {
                    settingsItem->setCoordinate(item->coordinate());
                } else {
                    visualItems->append(item);
                }
                firstItem = false;
897
            } else {
898
                errorString = tr("The mission file is corrupted.");
899 900 901 902
                return false;
            }
        }
    } else {
903
        errorString = tr("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
904 905 906
        return false;
    }

907
    if (!plannedHomePositionInFile) {
908 909 910
        // 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));
911
            if (item && item->command() == MAV_CMD_DO_JUMP) {
912
                item->missionItem().setParam1(static_cast<int>(item->missionItem().param1()) + 1);
Don Gagne's avatar
Don Gagne committed
913 914
            }
        }
915 916 917
    }

    return true;
918 919
}

920
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
921
{
Don Gagne's avatar
Don Gagne committed
922 923 924
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
925
        _settingsItem = nullptr;
Don Gagne's avatar
Don Gagne committed
926 927
    }

928
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
929 930

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

934
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
935

Don Gagne's avatar
Don Gagne committed
936
    _initAllVisualItems();
937
}
938

939 940 941 942 943 944
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

945
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970
        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;
971
    }
972

973 974 975 976 977 978 979 980 981 982 983 984 985
    _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);
986
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
987 988 989 990 991 992
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
993
    return true;
994 995
}

996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007
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;
}

1008
void MissionController::save(QJsonObject& json)
1009
{
1010
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
1011

1012
    // Mission settings
1013

1014 1015 1016 1017 1018 1019 1020
    MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsItem";
        return;
    }
    QJsonValue coordinateValue;
    JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
1021 1022 1023 1024 1025
    json[_jsonPlannedHomePositionKey]   = coordinateValue;
    json[_jsonFirmwareTypeKey]          = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey]           = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey]           = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey]            = _controllerVehicle->defaultHoverSpeed();
1026

1027
    // Save the visual items
1028

1029 1030 1031
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1032

1033 1034
        visualItem->save(rgJsonMissionItems);
    }
1035

1036 1037 1038
    // Mission settings has a special case for end mission action
    if (settingsItem) {
        QList<MissionItem*> rgMissionItems;
1039

1040 1041 1042 1043 1044
        if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
1045
        }
1046 1047
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
1048 1049 1050
        }
    }

1051
    json[_jsonItemsKey] = rgJsonMissionItems;
1052 1053
}

1054
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
1055
{
Don Gagne's avatar
Don Gagne committed
1056
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
1057
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
1058 1059 1060 1061
    bool            distanceOk =    false;

    // Convert to fixed altitudes

1062
    distanceOk = true;
1063
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
1064 1065
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
1066
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
1067
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
1068 1069 1070
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
1071 1072 1073
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
1074
    } else {
Don Gagne's avatar
Don Gagne committed
1075
        *altDifference = 0.0;
1076
        *azimuth = 0.0;
1077
        *distance = 0.0;
1078 1079 1080
    }
}

1081
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
1082 1083 1084 1085 1086 1087 1088
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

1089
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
1090 1091
}

1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113
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;
    }
}

1114 1115
void MissionController::_recalcWaypointLines(void)
{
1116 1117 1118
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

1119
    bool homePositionValid = _settingsItem->coordinate().isValid();
1120

1121
    qCDebug(MissionControllerLog) << "_recalcWaypointLines homePositionValid" << homePositionValid;
1122

Nate Weibley's avatar
Nate Weibley committed
1123 1124
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
1125
    _waypointLines.clear();
1126
    _waypointPath.clear();
1127

1128 1129 1130 1131 1132 1133 1134 1135 1136
    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;
1137 1138 1139
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));

1140 1141 1142 1143 1144 1145
        // 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;
1146
            }
1147 1148
        }

1149 1150 1151
        if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
            firstCoordinateItem = false;
            if (lastCoordinateItem != _settingsItem || (homePositionValid && linkStartToHome)) {
1152
                if (!_flyView) {
1153 1154
                    VisualItemPair pair(lastCoordinateItem, item);
                    _addWaypointLineSegment(old_table, pair);
1155 1156
                }
            }
1157 1158
            _waypointPath.append(QVariant::fromValue(item->coordinate()));
            lastCoordinateItem = item;
1159 1160
        }
    }
1161 1162 1163 1164 1165 1166

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

    if (linkEndToHome && lastCoordinateItem != _settingsItem && homePositionValid) {
1167
        if (!_flyView) {
1168 1169 1170 1171 1172
            VisualItemPair pair(lastCoordinateItem, _settingsItem);
            _addWaypointLineSegment(old_table, pair);
        } else {
            _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
        }
1173
    }
1174 1175 1176 1177

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1178
        objs.reserve(_linesTable.count());
1179
        for(CoordinateVector *vect: _linesTable.values()) {
1180 1181 1182 1183 1184 1185 1186 1187 1188 1189
            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
1190
    _recalcMissionFlightStatus();
1191

1192 1193 1194 1195 1196 1197 1198 1199
    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)));
    }

1200
    emit waypointLinesChanged();
1201
    emit waypointPathChanged();
1202 1203
}

1204 1205 1206 1207 1208 1209
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);
1210 1211 1212
        // 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.
1213
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236
            _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);
}

1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263
/// 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
1264
void MissionController::_recalcMissionFlightStatus()
1265
{
1266
    if (!_visualItems->count()) {
1267
        return;
1268
    }
1269 1270 1271 1272

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

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1275
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1276

1277 1278 1279
    // 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.
1280

1281
    // No values for first item
1282
    lastCoordinateItem->setAltDifference(0.0);
1283
    lastCoordinateItem->setAzimuth(0.0);
1284
    lastCoordinateItem->setDistance(0.0);
1285

1286 1287
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1288 1289
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1290

1291
    _resetMissionFlightStatus();
1292

DonLakeFlyer's avatar
DonLakeFlyer committed
1293
    bool vtolInHover = true;
1294
    bool linkStartToHome = false;
1295 1296 1297 1298 1299 1300 1301 1302 1303 1304
    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();
        }
    }
1305

DonLakeFlyer's avatar
DonLakeFlyer committed
1306
    for (int i=0; i<_visualItems->count(); i++) {
1307
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1308 1309 1310
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1311 1312
        // Assume the worst
        item->setAzimuth(0.0);
1313
        item->setDistance(0.0);
1314

DonLakeFlyer's avatar
DonLakeFlyer committed
1315 1316 1317
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1318
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1319
                _missionFlightStatus.hoverSpeed = newSpeed;
1320
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1321 1322
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1323
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1324
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1325
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1326 1327
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1328
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1329 1330 1331 1332
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1333 1334 1335 1336 1337 1338 1339
        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
1340 1341 1342 1343 1344
        }

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

1347
        // Link back to home if first item is takeoff and we have home position
1348
        if (firstCoordinateItem && simpleItem && (simpleItem->command() == MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
1349
            if (showHomePosition) {
1350
                linkStartToHome = true;
1351 1352 1353 1354 1355 1356 1357
                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);
                }
1358 1359 1360 1361
            }
        }

        // Update VTOL state
1362
        if (simpleItem && _controllerVehicle->vtol()) {
1363
            switch (simpleItem->command()) {
1364
            case MAV_CMD_NAV_TAKEOFF:
1365 1366
                vtolInHover = false;
                break;
1367
            case MAV_CMD_NAV_VTOL_TAKEOFF:
DonLakeFlyer's avatar
DonLakeFlyer committed
1368 1369
                vtolInHover = true;
                break;
1370
            case MAV_CMD_NAV_LAND:
1371 1372
                vtolInHover = false;
                break;
1373
            case MAV_CMD_NAV_VTOL_LAND:
DonLakeFlyer's avatar
DonLakeFlyer committed
1374 1375
                vtolInHover = true;
                break;
1376
            case MAV_CMD_DO_VTOL_TRANSITION:
1377 1378 1379 1380 1381 1382
            {
                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;
1383 1384
                }
            }
1385 1386 1387
                break;
            default:
                break;
1388
            }
Don Gagne's avatar
Don Gagne committed
1389 1390
        }

1391
        _addTimeDistance(vtolInHover, 0, 0, item->additionalTimeDelay(), 0, -1);
1392

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

1396
            double absoluteAltitude = item->coordinate().altitude();
1397
            if (item->coordinateHasRelativeAltitude()) {
1398 1399 1400 1401 1402
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1403 1404 1405 1406
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1407 1408 1409
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1410
                firstCoordinateItem = false;
1411 1412 1413 1414 1415 1416 1417

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

1418
                if (lastCoordinateItem != _settingsItem || linkStartToHome) {
1419 1420
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1421

1422
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1423 1424 1425
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1426

1427
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1428

DonLakeFlyer's avatar
DonLakeFlyer committed
1429 1430 1431
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1432
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1433
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1434

1435
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1436 1437
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1438
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1439

1440 1441
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1442
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1443
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1444 1445

                item->setMissionFlightStatus(_missionFlightStatus);
1446

1447 1448
                lastCoordinateItem = item;
            }
1449 1450
        }
    }
1451
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1452

1453 1454 1455 1456 1457 1458 1459 1460
    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();
1461
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1462 1463
    }

1464 1465 1466
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1467

DonLakeFlyer's avatar
DonLakeFlyer committed
1468 1469 1470 1471 1472 1473 1474
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1475 1476
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1477

1478 1479
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1480 1481
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1482 1483 1484

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1485
            if (item->coordinateHasRelativeAltitude()) {
1486 1487 1488 1489
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1490
                item->setTerrainPercent(qQNaN());
1491
                item->setTerrainCollision(false);
1492 1493
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1494 1495 1496 1497 1498 1499 1500
                double terrainAltitude = item->terrainAltitude();
                if (qIsNaN(terrainAltitude)) {
                    item->setTerrainPercent(qQNaN());
                    item->setTerrainCollision(false);
                } else {
                    item->setTerrainPercent((terrainAltitude - minAltSeen) / altRange);
                    item->setTerrainCollision(absoluteAltitude < terrainAltitude);
1501
                }
1502
            }
1503 1504
        }
    }
1505 1506

    _updateTimer.start(UPDATE_TIMEOUT);
1507 1508
}

1509 1510 1511
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1512 1513 1514 1515 1516
    if (_inRecalcSequence) {
        // Don't let this call recurse due to signalling
        return;
    }

1517 1518
    // Setup ascending sequence numbers for all visual items

1519
    _inRecalcSequence = true;
1520 1521 1522
    int sequenceNumber = 0;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1523 1524
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1525 1526
    }    
    _inRecalcSequence = false;
1527 1528
}

1529 1530 1531
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1532
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1533 1534 1535

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

1536 1537
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1538 1539 1540 1541 1542

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1543
        } else if (item->isSimpleItem()) {
1544 1545 1546 1547 1548
            currentParentItem->childItems()->append(item);
        }
    }
}

1549
void MissionController::_setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate)
1550
{
1551 1552
    QGeoCoordinate firstCoordinate;

1553 1554 1555 1556
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1557
    // Set the planned home position to be a delta from first coordinate
1558 1559 1560 1561
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

        if (item->specifiesCoordinate()) {
1562 1563
            firstCoordinate = item->coordinate();
            break;
1564 1565 1566
        }
    }

1567 1568 1569 1570
    // No item specifying a coordinate was found, in this case it we have a clickCoordinate use that
    if (!firstCoordinate.isValid()) {
        firstCoordinate = clickCoordinate;
    }
1571

1572 1573 1574 1575 1576 1577 1578 1579 1580
    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)
1581
{
1582
    if (!_flyView) {
1583
        _setPlannedHomePositionFromFirstCoordinate(clickCoordinate);
1584
    }
1585
    _recalcSequence();
1586 1587
    _recalcChildItems();
    _recalcWaypointLines();
1588
    _updateTimer.start(UPDATE_TIMEOUT);
1589 1590
}

1591 1592 1593 1594 1595 1596
void MissionController::_recalcAll(void)
{
    QGeoCoordinate emptyCoord;
    _recalcAllWithClickCoordinate(emptyCoord);
}

1597
/// Initializes a new set of mission items
1598
void MissionController::_initAllVisualItems(void)
1599
{
1600 1601
    // Setup home position at index 0

1602 1603 1604
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1605 1606
        return;
    }
1607
    if (!_flyView) {
1608 1609
        _settingsItem->setIsCurrentItem(true);
    }
1610

1611
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1612
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1613
    }
1614

1615 1616 1617
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1618

1619 1620 1621 1622
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1623

1624
    _recalcAll();
1625

1626
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1627 1628 1629
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1630
    emit containsItemsChanged(containsItems());
1631
    emit plannedHomePositionChanged(plannedHomePosition());
1632

1633
    setDirty(false);
1634 1635
}

1636
void MissionController::_deinitAllVisualItems(void)
1637
{
1638 1639 1640
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1641 1642
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1643 1644
    }

1645
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1646
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1647 1648
}

1649
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1650
{
1651
    setDirty(false);
1652

1653
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1654 1655
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1656 1657
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1658
    connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged,                this, &MissionController::_recalcMissionFlightStatus);
1659
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1660
    connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged,                 this, &MissionController::_recalcMissionFlightStatus);
1661
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1662

1663 1664 1665 1666 1667 1668 1669 1670
    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";
        }
1671 1672
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1673
        if (complexItem) {
1674
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
1675
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
1676 1677 1678
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1679
    }
1680 1681
}

1682
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1683
{
1684 1685
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1686 1687
}

1688
void MissionController::_itemCommandChanged(void)
1689
{
1690 1691
    _recalcChildItems();
    _recalcWaypointLines();
1692 1693
}

1694
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1695
{
1696 1697 1698 1699 1700 1701
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1702

1703 1704
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1705
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1706 1707
        return;
    }
1708

1709 1710
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1711 1712
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1713 1714 1715 1716 1717
    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);
1718
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1719 1720 1721 1722
    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);
1723

1724 1725
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1726
    }
1727

1728
    emit complexMissionItemNamesChanged();
1729
    emit resumeMissionIndexChanged();
1730 1731
}

1732
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1733
{
1734
    if (_visualItems) {
1735 1736
        bool currentDirtyBit = dirty();

1737
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1738
        if (settingsItem) {
1739
            settingsItem->setHomePositionFromVehicle(homePosition);
1740
        } else {
1741
            qWarning() << "First item is not MissionSettingsItem";
1742
        }
1743 1744 1745 1746 1747 1748

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

void MissionController::_inProgressChanged(bool inProgress)
1753
{
1754
    emit syncInProgressChanged(inProgress);
1755
}
1756

1757
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1758
{
1759 1760
    bool        found = false;
    double      foundAltitude;
1761
    int         foundAltitudeMode;
1762

1763 1764 1765 1766 1767 1768
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1771 1772 1773
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1774 1775 1776
                if (simpleItem->specifiesAltitude()) {
                    foundAltitude = simpleItem->altitude()->rawValue().toDouble();
                    foundAltitudeMode = simpleItem->altitudeMode();
1777
                    found = true;
1778
                    break;
1779 1780
                }
            }
1781 1782 1783
        }
    }

1784
    if (found) {
1785
        *prevAltitude = foundAltitude;
1786
        *prevAltitudeMode = foundAltitudeMode;
1787 1788 1789
    }

    return found;
1790
}
1791 1792 1793 1794 1795 1796 1797 1798 1799 1800 1801 1802 1803

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

1804
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1805
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1806
{
1807
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
1808

Don Gagne's avatar
Don Gagne committed
1809 1810
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1811
    visualItems->insert(0, settingsItem);
1812

1813 1814 1815 1816 1817 1818 1819 1820 1821 1822 1823 1824 1825 1826 1827 1828 1829 1830 1831 1832 1833 1834 1835 1836 1837
    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;
                    }
1838 1839
                }
            }
1840

1841 1842 1843
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1844
        }
Don Gagne's avatar
Don Gagne committed
1845 1846
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1847 1848
    }
}
1849

1850
int MissionController::resumeMissionIndex(void) const
1851
{
1852

1853
    int resumeIndex = 0;
1854

1855
    if (_flyView) {
1856
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1857
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1858 1859
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1860 1861
        } else {
            resumeIndex = 0;
1862 1863 1864 1865 1866
        }
    }

    return resumeIndex;
}
1867

1868 1869
int MissionController::currentMissionIndex(void) const
{
1870
    if (!_flyView) {
1871 1872 1873 1874 1875 1876 1877 1878 1879 1880
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

1881
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1882
{
1883
    if (_flyView) {
1884
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1885 1886 1887
            sequenceNumber++;
        }

1888 1889
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1890 1891
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1892
        emit currentMissionIndexChanged(currentMissionIndex());
1893 1894
    }
}
1895

1896
bool MissionController::syncInProgress(void) const
1897
{
1898
    return _missionManager->inProgress();
1899 1900 1901 1902 1903 1904 1905 1906 1907 1908 1909 1910
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1911
    }
1912
}
1913

1914 1915
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1916 1917
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, vehicle);
1918

1919 1920 1921 1922 1923 1924
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1925
        if (!_flyView) {
1926 1927 1928 1929 1930 1931
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
1932 1933 1934
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1935
        if (simpleItem) {
1936 1937 1938 1939 1940
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
1941 1942 1943
        }
    }
}
1944 1945 1946 1947 1948 1949 1950 1951 1952 1953 1954 1955 1956

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
1957 1958 1959 1960 1961 1962 1963 1964
    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();
    }
1965
}
1966 1967 1968 1969 1970

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

1971
    complexItems.append(_circularSurveyMissionItemName);
1972
    complexItems.append(_surveyMissionItemName);
1973
    complexItems.append(patternCorridorScanName);
1974
    if (_controllerVehicle->fixedWing()) {
1975
        complexItems.append(patternFWLandingName);
1976
    }
1977
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
1978
        complexItems.append(patternStructureScanName);
1979
    }
1980

1981
    return qgcApp()->toolbox()->corePlugin()->complexMissionItemNames(_controllerVehicle, complexItems);
1982
}
1983

1984 1985
void MissionController::resumeMission(int resumeIndex)
{
1986
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1987 1988
        resumeIndex--;
    }
1989
    _missionManager->generateResumeMission(resumeIndex);
1990
}
1991 1992 1993 1994 1995 1996 1997 1998 1999

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
2000 2001 2002 2003 2004 2005 2006 2007 2008 2009

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

2011 2012 2013 2014 2015 2016 2017
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
2018 2019 2020 2021 2022 2023

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
2024 2025 2026

bool MissionController::showPlanFromManagerVehicle (void)
{
2027
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
DonLakeFlyer's avatar
DonLakeFlyer committed
2028 2029
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
2030
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
2031 2032 2033 2034 2035 2036 2037 2038 2039 2040 2041 2042 2043 2044 2045 2046 2047 2048 2049
    } 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;
        }
    }
}

2050
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2051
{
2052
    // Fly view always reloads on send complete
2053
    if (!error && _flyView) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2054 2055 2056 2057
        showPlanFromManagerVehicle();
    }
}

2058
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2059
{
2060 2061 2062 2063
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2064
}
2065 2066 2067 2068 2069 2070 2071 2072 2073 2074 2075 2076 2077 2078 2079 2080 2081 2082 2083 2084 2085 2086 2087 2088 2089 2090 2091 2092 2093 2094

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

void MissionController::_updateTimeout()
{
Gus Grubba's avatar
Gus Grubba committed
2098
    QGeoCoordinate firstCoordinate;
2099
    QGeoCoordinate takeoffCoordinate;
2100
    QGCGeoBoundingCube boundingCube;
2101 2102 2103 2104
    double north = 0.0;
    double south = 180.0;
    double east  = 0.0;
    double west  = 360.0;
2105 2106
    double minAlt = QGCGeoBoundingCube::MaxAlt;
    double maxAlt = QGCGeoBoundingCube::MinAlt;
2107 2108 2109 2110 2111 2112
    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()) {
2113
                case MAV_CMD_NAV_TAKEOFF:
2114 2115 2116
                case MAV_CMD_NAV_WAYPOINT:
                case MAV_CMD_NAV_LAND:
                if(pSimpleItem->coordinate().isValid()) {
2117
                    if((MAV_CMD)pSimpleItem->command() == MAV_CMD_NAV_TAKEOFF) {
Gus Grubba's avatar
Gus Grubba committed
2118 2119 2120 2121
                        takeoffCoordinate = pSimpleItem->coordinate();
                    } else if(!firstCoordinate.isValid()) {
                        firstCoordinate = pSimpleItem->coordinate();
                    }
2122 2123
                    double lat = pSimpleItem->coordinate().latitude()  + 90.0;
                    double lon = pSimpleItem->coordinate().longitude() + 180.0;
2124
                    double alt = pSimpleItem->coordinate().altitude();
2125 2126 2127 2128
                    north  = fmax(north, lat);
                    south  = fmin(south, lat);
                    east   = fmax(east,  lon);
                    west   = fmin(west,  lon);
2129 2130
                    minAlt = fmin(minAlt, alt);
                    maxAlt = fmax(maxAlt, alt);
2131 2132 2133 2134 2135 2136 2137 2138 2139
                }
                break;
                default:
                    break;
                }
            }
        } else {
            ComplexMissionItem* pComplexItem = qobject_cast<ComplexMissionItem*>(item);
            if(pComplexItem) {
2140 2141
                QGCGeoBoundingCube bc = pComplexItem->boundingCube();
                if(bc.isValid()) {
Gus Grubba's avatar
Gus Grubba committed
2142 2143 2144
                    if(!firstCoordinate.isValid() && pComplexItem->coordinate().isValid()) {
                        firstCoordinate = pComplexItem->coordinate();
                    }
2145 2146 2147 2148 2149 2150
                    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());
2151 2152 2153 2154
                }
            }
        }
    }
Gus Grubba's avatar
Gus Grubba committed
2155 2156 2157 2158 2159 2160 2161 2162 2163
    //-- Figure out where this thing is taking off from
    if(!takeoffCoordinate.isValid()) {
        if(firstCoordinate.isValid()) {
            takeoffCoordinate = firstCoordinate;
        } else {
            takeoffCoordinate = plannedHomePosition();
        }
    }
    //-- Build bounding "cube"
2164 2165 2166
    boundingCube = QGCGeoBoundingCube(
        QGeoCoordinate(north - 90.0, west - 180.0, minAlt),
        QGeoCoordinate(south - 90.0, east - 180.0, maxAlt));
2167 2168
    if(_travelBoundingCube != boundingCube || _takeoffCoordinate != takeoffCoordinate) {
        _takeoffCoordinate  = takeoffCoordinate;
2169
        _travelBoundingCube = boundingCube;
2170
        emit missionBoundingCubeChanged();
2171
        qCDebug(MissionControllerLog) << "Bounding cube:" << _travelBoundingCube.pointNW << _travelBoundingCube.pointSE;
2172 2173 2174 2175 2176 2177 2178
    }
}

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