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


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

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

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

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

43 44
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

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

const int   MissionController::_missionFileVersion =            2;
60

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

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

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

90 91
}

92 93 94 95 96 97 98 99 100
void MissionController::_resetMissionFlightStatus(void)
{
    _missionFlightStatus.totalDistance =        0.0;
    _missionFlightStatus.maxTelemetryDistance = 0.0;
    _missionFlightStatus.totalTime =            0.0;
    _missionFlightStatus.hoverTime =            0.0;
    _missionFlightStatus.cruiseTime =           0.0;
    _missionFlightStatus.hoverDistance =        0.0;
    _missionFlightStatus.cruiseDistance =       0.0;
101 102 103
    _missionFlightStatus.cruiseSpeed =          _controllerVehicle->defaultCruiseSpeed();
    _missionFlightStatus.hoverSpeed =           _controllerVehicle->defaultHoverSpeed();
    _missionFlightStatus.vehicleSpeed =         _controllerVehicle->multiRotor() || _managerVehicle->vtol() ? _missionFlightStatus.hoverSpeed : _missionFlightStatus.cruiseSpeed;
104
    _missionFlightStatus.vehicleYaw =           0.0;
105
    _missionFlightStatus.gimbalYaw =            std::numeric_limits<double>::quiet_NaN();
106
    _missionFlightStatus.gimbalPitch =          std::numeric_limits<double>::quiet_NaN();
107 108 109 110 111 112 113 114 115 116 117 118

    // Battery information

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

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

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

135 136
}

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

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

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

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

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

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

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

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

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

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

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

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

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

216
void MissionController::loadFromVehicle(void)
217
{
DonLakeFlyer's avatar
DonLakeFlyer committed
218 219 220 221 222 223 224 225
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::loadFromVehicle called while offline";
    } else if (syncInProgress()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::loadFromVehicle called while syncInProgress";
    } else {
        _itemsRequested = true;
        _managerVehicle->missionManager()->loadFromVehicle();
    }
226 227
}

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

239
void MissionController::sendToVehicle(void)
240
{
DonLakeFlyer's avatar
DonLakeFlyer committed
241 242 243 244 245
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::sendToVehicle called while offline";
    } else if (syncInProgress()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::sendToVehicle called while syncInProgress";
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
246
        qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
247
        _warnIfTerrainFrameUsed();
DonLakeFlyer's avatar
DonLakeFlyer committed
248 249 250 251 252 253 254 255 256
        if (_visualItems->count() == 1) {
            // This prevents us from sending a possibly bogus home position to the vehicle
            QmlObjectListModel emptyModel;
            sendItemsToVehicle(_managerVehicle, &emptyModel);
        } else {
            sendItemsToVehicle(_managerVehicle, _visualItems);
        }
        setDirty(false);
    }
Don Gagne's avatar
Don Gagne committed
257 258
}

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

268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283
    bool endActionSet = false;
    int lastSeqNum = 0;

    for (int i=0; i<visualMissionItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(visualMissionItems->get(i));

        lastSeqNum = visualItem->lastSequenceNumber();
        visualItem->appendMissionItems(rgMissionItems, missionItemParent);

        qCDebug(MissionControllerLog) << "_convertToMissionItems seqNum:lastSeqNum:command"
                                      << visualItem->sequenceNumber()
                                      << lastSeqNum
                                      << visualItem->commandName();
    }

    // Mission settings has a special case for end mission action
284
    MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
285 286 287 288 289 290 291
    if (settingsItem) {
        endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
    }

    return endActionSet;
}

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

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

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

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

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

    deleteParent->deleteLater();

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

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

339
        convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
340

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

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

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

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

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

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

389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416
int MissionController::insertSimpleMissionItem(const MissionItem &missionItem, int i)
{
    int sequenceNumber = _nextSequenceNumber();
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, missionItem, this);
    newItem->setSequenceNumber(sequenceNumber);
    newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
    _initVisualItem(newItem);
    MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
    if (newItem->command() ==  takeoffCmd) {
        if (!_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) {
            return -1; // can not add this takeoff command for this vehicle
        }
    }
    if (newItem->specifiesAltitude()) {
        double  prevAltitude;
        int     prevAltitudeMode;

        if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
            newItem->altitude()->setRawValue(prevAltitude);
            newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
        }
    }
    newItem->setMissionFlightStatus(_missionFlightStatus);
    _visualItems->insert(i, newItem);

    return newItem->sequenceNumber();
}

417 418 419
int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
{
    int sequenceNumber = _nextSequenceNumber();
420
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
421
    newItem->setSequenceNumber(sequenceNumber);
422
    newItem->setCommand((_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_DO_SET_ROI_LOCATION) ?
423 424
        MAV_CMD_DO_SET_ROI_LOCATION :
        MAV_CMD_DO_SET_ROI));
425
    _initVisualItem(newItem);
426
    newItem->setCoordinate(coordinate);
427

428 429
    double  prevAltitude;
    int     prevAltitudeMode;
430

431 432
    if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
        newItem->altitude()->setRawValue(prevAltitude);
433
        newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
434 435 436 437 438 439 440 441
    }
    _visualItems->insert(i, newItem);

    _recalcAll();

    return newItem->sequenceNumber();
}

442
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
443
{
444 445
    ComplexMissionItem* newItem;

446
    int sequenceNumber = _nextSequenceNumber();
447
    if (itemName == _surveyMissionItemName) {
448
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
449
        newItem->setCoordinate(mapCenterCoordinate);
450
    } else if (itemName == patternFWLandingName) {
451
        newItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, _visualItems /* parent */);
452
    } else if (itemName == patternStructureScanName) {
453
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
454
    } else if (itemName == patternCorridorScanName) {
455
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
456 457
    } else if (itemName == _circularSurveyMissionItemName) {
        newItem = new CircularSurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
458 459 460 461 462
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }

463 464 465
    return _insertComplexMissionItemWorker(newItem, i);
}

466
int MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int i)
467 468 469 470
{
    ComplexMissionItem* newItem;

    if (itemName == _surveyMissionItemName) {
471
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
472 473
    } else if (itemName == _circularSurveyMissionItemName) {
        newItem = new CircularSurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
474
    } else if (itemName == patternStructureScanName) {
475
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
476
    } else if (itemName == patternCorridorScanName) {
477
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
478 479 480 481 482 483 484 485 486 487 488
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return _nextSequenceNumber();
    }

    return _insertComplexMissionItemWorker(newItem, i);
}

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

493
    if (surveyStyleItem) {
494
        bool rollSupported  = false;
495
        bool pitchSupported = false;
496
        bool yawSupported   = false;
497 498 499

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

500 501
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
        CameraSection* cameraSection = settingsItem->cameraSection();
502

503
        // Set camera to photo mode (leave alone if user already specified)
504
        if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
505
            cameraSection->setSpecifyCameraMode(true);
506
            cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
507
        }
508

509
        // Point gimbal straight down
510
        if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
511 512 513
            // If the user already specified a gimbal angle leave it alone
            if (!cameraSection->specifyGimbal()) {
                cameraSection->setSpecifyGimbal(true);
514
                cameraSection->gimbalPitch()->setRawValue(-90.0);
515 516
            }
        }
517
    }
518

519 520
    complexItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(complexItem);
521

522 523 524 525 526
    if (i == -1) {
        _visualItems->append(complexItem);
    } else {
        _visualItems->insert(i, complexItem);
    }
527

528
    //-- Keep track of bounding box changes in complex items
529 530
    if(!complexItem->isSimpleItem()) {
        connect(complexItem, &ComplexMissionItem::boundingCubeChanged, this, &MissionController::_complexBoundingBoxChanged);
531
    }
532 533
    _recalcAll();

534
    return complexItem->sequenceNumber();
535 536
}

537 538
void MissionController::removeMissionItem(int index)
{
539 540 541 542 543
    if (index <= 0 || index >= _visualItems->count()) {
        qWarning() << "MissionController::removeMissionItem called with bad index - count:index" << _visualItems->count() << index;
        return;
    }

544 545 546
    bool removeSurveyStyle =    _visualItems->value<SurveyComplexItem*>(index)
                             || _visualItems->value<CorridorScanComplexItem*>(index)
                             || _visualItems->value<CircularSurveyComplexItem*>(index);
547
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
548

549
    _deinitVisualItem(item);
550
    item->deleteLater();
551

552 553
    if (removeSurveyStyle) {
        // Determine if the mission still has another survey style item in it
554 555
        bool foundSurvey = false;
        for (int i=1; i<_visualItems->count(); i++) {
556 557 558
            if (    _visualItems->value<SurveyComplexItem*>(i)
                 || _visualItems->value<CorridorScanComplexItem*>(i)
                 || _visualItems->value<CircularSurveyComplexItem*>(i)) {
559 560 561 562 563
                foundSurvey = true;
                break;
            }
        }

564
        // If there is no longer a survey item in the mission remove added commands
565 566 567 568
        if (!foundSurvey) {
            bool rollSupported = false;
            bool pitchSupported = false;
            bool yawSupported = false;
569 570
            MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
            CameraSection* cameraSection = settingsItem->cameraSection();
571
            if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
572
                if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
573 574 575
                    cameraSection->setSpecifyGimbal(false);
                }
            }
576
            if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
577 578
                cameraSection->setSpecifyCameraMode(false);
            }
579 580 581
        }
    }

582
    _recalcAll();
583
    setDirty(true);
584 585
}

586
void MissionController::removeAll(void)
587
{
588 589
    if (_visualItems) {
        _deinitAllVisualItems();
DonLakeFlyer's avatar
DonLakeFlyer committed
590
        _visualItems->clearAndDeleteContents();
Don Gagne's avatar
Don Gagne committed
591
        _visualItems->deleteLater();
592
        _settingsItem = nullptr;
593
        _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
594
        _addMissionSettings(_visualItems, false /* addToCenter */);
595
        _initAllVisualItems();
596
        setDirty(true);
597
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
598 599 600
    }
}

601
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
602 603 604 605 606 607 608 609 610
{
    // 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)) {
611 612 613
        return false;
    }

614
    // Read complex items
615
    QList<SurveyComplexItem*> surveyItems;
616 617 618 619
    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];
620

621 622 623 624 625
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

626
        SurveyComplexItem* item = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems /* parent */);
Don Gagne's avatar
Don Gagne committed
627 628
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
629
            surveyItems.append(item);
630 631
        } else {
            return false;
632
        }
633
    }
634

635 636 637 638 639
    // 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
640
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
641

642
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
643 644 645 646
    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
647
        if (nextComplexItemIndex < surveyItems.count()) {
648
            SurveyComplexItem* complexItem = surveyItems[nextComplexItemIndex];
649 650 651 652 653 654 655 656 657 658 659 660 661 662

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

663 664 665 666 667
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
668
            const QJsonObject itemObject = itemValue.toObject();
669
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
Don Gagne's avatar
Don Gagne committed
670
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
671
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
672
                nextSequenceNumber = item->lastSequenceNumber() + 1;
673
                visualItems->append(item);
674 675 676 677
            } else {
                return false;
            }
        }
678
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
679 680

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

Don Gagne's avatar
Don Gagne committed
683
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
684
            MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
685 686 687
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
688 689 690 691
        } else {
            return false;
        }
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
692
        _addMissionSettings(visualItems, true /* addToCenter */);
693 694 695 696 697
    }

    return true;
}

698
bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
699 700 701 702 703 704
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
705
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
706 707
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
708 709 710 711 712 713 714
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

715
    // Mission Settings
716
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
717

718 719
    if (_masterController->offline()) {
        // We only update if offline since if we are online we use the online vehicle settings
720
        appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType(static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt())));
721
        if (json.contains(_jsonVehicleTypeKey)) {
722
            appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType(static_cast<MAV_TYPE>(json[_jsonVehicleTypeKey].toInt())));
723
        }
724
    }
725
    if (json.contains(_jsonCruiseSpeedKey)) {
726
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
727 728
    }
    if (json.contains(_jsonHoverSpeedKey)) {
729
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
730 731
    }

732 733 734 735
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
736
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
737 738
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764
    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) {
765
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
766
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
767
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
768
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
769 770 771 772 773 774 775 776 777 778 779 780 781
                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();

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

873 874 875 876 877 878 879 880
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;
881 882 883 884 885 886
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
887 888

    if (fileVersion == 1) {
889
        return _loadJsonMissionFileV1(json, visualItems, errorString);
890
    } else {
891
        return _loadJsonMissionFileV2(json, visualItems, errorString);
892 893 894
    }
}

895
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
896
{
897 898
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
899 900 901 902 903 904 905 906 907

    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;
908
            plannedHomePositionInFile = true;
909 910 911
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
912
            plannedHomePositionInFile = false;
913 914 915 916
        }
    }

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

921
        while (!stream.atEnd()) {
922
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
923 924

            if (item->load(stream)) {
925 926 927 928 929 930
                if (firstItem && plannedHomePositionInFile) {
                    settingsItem->setCoordinate(item->coordinate());
                } else {
                    visualItems->append(item);
                }
                firstItem = false;
931
            } else {
932
                errorString = tr("The mission file is corrupted.");
933 934 935 936
                return false;
            }
        }
    } else {
937
        errorString = tr("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
938 939 940
        return false;
    }

941
    if (!plannedHomePositionInFile) {
942 943 944
        // 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));
945
            if (item && item->command() == MAV_CMD_DO_JUMP) {
946
                item->missionItem().setParam1(static_cast<int>(item->missionItem().param1()) + 1);
Don Gagne's avatar
Don Gagne committed
947 948
            }
        }
949 950 951
    }

    return true;
952 953
}

954
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
955
{
Don Gagne's avatar
Don Gagne committed
956 957 958
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
959
        _settingsItem = nullptr;
Don Gagne's avatar
Don Gagne committed
960 961
    }

962
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
963 964

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

968
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
969

Don Gagne's avatar
Don Gagne committed
970
    _initAllVisualItems();
971
}
972

973 974 975 976 977 978
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

979
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004
        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;
1005
    }
1006

1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019
    _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);
1020
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
1021 1022 1023 1024 1025 1026
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
1027
    return true;
1028 1029
}

1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041
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;
}

1042
void MissionController::save(QJsonObject& json)
1043
{
1044
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
1045

1046
    // Mission settings
1047

1048 1049 1050 1051 1052 1053 1054
    MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsItem";
        return;
    }
    QJsonValue coordinateValue;
    JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
1055 1056 1057 1058 1059
    json[_jsonPlannedHomePositionKey]   = coordinateValue;
    json[_jsonFirmwareTypeKey]          = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey]           = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey]           = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey]            = _controllerVehicle->defaultHoverSpeed();
1060

1061
    // Save the visual items
1062

1063 1064 1065
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1066

1067 1068
        visualItem->save(rgJsonMissionItems);
    }
1069

1070 1071 1072
    // Mission settings has a special case for end mission action
    if (settingsItem) {
        QList<MissionItem*> rgMissionItems;
1073

1074
        if (convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
1075 1076 1077 1078
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
1079
        }
1080 1081
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
1082 1083 1084
        }
    }

1085
    json[_jsonItemsKey] = rgJsonMissionItems;
1086 1087
}

1088
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
1089
{
Don Gagne's avatar
Don Gagne committed
1090
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
1091
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
1092 1093 1094 1095
    bool            distanceOk =    false;

    // Convert to fixed altitudes

1096
    distanceOk = true;
1097
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
1098 1099
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
1100
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
1101
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
1102 1103 1104
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
1105 1106 1107
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
1108
    } else {
Don Gagne's avatar
Don Gagne committed
1109
        *altDifference = 0.0;
1110
        *azimuth = 0.0;
1111
        *distance = 0.0;
1112 1113 1114
    }
}

1115
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
1116 1117 1118 1119 1120 1121 1122
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

1123
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
1124 1125
}

1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147
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;
    }
}

1148 1149
void MissionController::_recalcWaypointLines(void)
{
1150 1151 1152
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

1153
    bool homePositionValid = _settingsItem->coordinate().isValid();
1154

1155
    qCDebug(MissionControllerLog) << "_recalcWaypointLines homePositionValid" << homePositionValid;
1156

Nate Weibley's avatar
Nate Weibley committed
1157 1158
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
1159
    _waypointLines.clear();
1160
    _waypointPath.clear();
1161

1162 1163 1164 1165 1166 1167 1168 1169 1170
    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;
1171 1172 1173
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));

1174 1175 1176 1177 1178 1179
        // 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;
1180
            }
1181 1182
        }

1183 1184 1185
        if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
            firstCoordinateItem = false;
            if (lastCoordinateItem != _settingsItem || (homePositionValid && linkStartToHome)) {
1186
                if (!_flyView) {
1187 1188
                    VisualItemPair pair(lastCoordinateItem, item);
                    _addWaypointLineSegment(old_table, pair);
1189 1190
                }
            }
1191 1192
            _waypointPath.append(QVariant::fromValue(item->coordinate()));
            lastCoordinateItem = item;
1193 1194
        }
    }
1195 1196 1197 1198 1199 1200

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

    if (linkEndToHome && lastCoordinateItem != _settingsItem && homePositionValid) {
1201
        if (!_flyView) {
1202 1203 1204 1205 1206
            VisualItemPair pair(lastCoordinateItem, _settingsItem);
            _addWaypointLineSegment(old_table, pair);
        } else {
            _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
        }
1207
    }
1208 1209 1210 1211

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1212
        objs.reserve(_linesTable.count());
1213
        for(CoordinateVector *vect: _linesTable.values()) {
1214 1215 1216 1217 1218 1219 1220 1221 1222 1223
            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
1224
    _recalcMissionFlightStatus();
1225

1226 1227 1228 1229 1230 1231 1232 1233
    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)));
    }

1234
    emit waypointLinesChanged();
1235
    emit waypointPathChanged();
1236 1237
}

1238 1239 1240 1241 1242 1243
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);
1244 1245 1246
        // 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.
1247
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270
            _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);
}

1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297
/// 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
1298
void MissionController::_recalcMissionFlightStatus()
1299
{
1300
    if (!_visualItems->count()) {
1301
        return;
1302
    }
1303 1304 1305 1306

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

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1309
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1310

1311 1312 1313
    // 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.
1314

1315
    // No values for first item
1316
    lastCoordinateItem->setAltDifference(0.0);
1317
    lastCoordinateItem->setAzimuth(0.0);
1318
    lastCoordinateItem->setDistance(0.0);
1319

1320 1321
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1322 1323
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1324

1325
    _resetMissionFlightStatus();
1326

DonLakeFlyer's avatar
DonLakeFlyer committed
1327
    bool vtolInHover = true;
1328
    bool linkStartToHome = false;
1329 1330 1331 1332 1333 1334 1335 1336 1337 1338
    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();
        }
    }
1339

DonLakeFlyer's avatar
DonLakeFlyer committed
1340
    for (int i=0; i<_visualItems->count(); i++) {
1341
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1342 1343 1344
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1345 1346
        // Assume the worst
        item->setAzimuth(0.0);
1347
        item->setDistance(0.0);
1348

DonLakeFlyer's avatar
DonLakeFlyer committed
1349 1350 1351
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1352
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1353
                _missionFlightStatus.hoverSpeed = newSpeed;
1354
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1355 1356
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1357
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1358
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1359
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1360 1361
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1362
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1363 1364 1365 1366
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1367 1368 1369 1370 1371 1372 1373
        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
1374 1375 1376 1377 1378
        }

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

1381
        // Link back to home if first item is takeoff and we have home position
1382
        if (firstCoordinateItem && simpleItem && (simpleItem->command() == MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
1383
            if (showHomePosition) {
1384
                linkStartToHome = true;
1385 1386 1387 1388 1389 1390 1391
                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);
                }
1392 1393 1394 1395
            }
        }

        // Update VTOL state
1396
        if (simpleItem && _controllerVehicle->vtol()) {
1397
            switch (simpleItem->command()) {
1398
            case MAV_CMD_NAV_TAKEOFF:
1399 1400
                vtolInHover = false;
                break;
1401
            case MAV_CMD_NAV_VTOL_TAKEOFF:
DonLakeFlyer's avatar
DonLakeFlyer committed
1402 1403
                vtolInHover = true;
                break;
1404
            case MAV_CMD_NAV_LAND:
1405 1406
                vtolInHover = false;
                break;
1407
            case MAV_CMD_NAV_VTOL_LAND:
DonLakeFlyer's avatar
DonLakeFlyer committed
1408 1409
                vtolInHover = true;
                break;
1410
            case MAV_CMD_DO_VTOL_TRANSITION:
1411 1412 1413 1414 1415 1416
            {
                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;
1417 1418
                }
            }
1419 1420 1421
                break;
            default:
                break;
1422
            }
Don Gagne's avatar
Don Gagne committed
1423 1424
        }

1425
        _addTimeDistance(vtolInHover, 0, 0, item->additionalTimeDelay(), 0, -1);
1426

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

1430
            double absoluteAltitude = item->coordinate().altitude();
1431
            if (item->coordinateHasRelativeAltitude()) {
1432 1433 1434 1435 1436
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1437 1438 1439 1440
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1441 1442 1443
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1444
                firstCoordinateItem = false;
1445 1446 1447 1448 1449 1450 1451

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

1452
                if (lastCoordinateItem != _settingsItem || linkStartToHome) {
1453 1454
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1455

1456
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1457 1458 1459
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1460

1461
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1462

DonLakeFlyer's avatar
DonLakeFlyer committed
1463 1464 1465
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1466
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1467
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1468

1469
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1470 1471
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1472
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1473

1474 1475
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1476
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1477
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1478 1479

                item->setMissionFlightStatus(_missionFlightStatus);
1480

1481 1482
                lastCoordinateItem = item;
            }
1483 1484
        }
    }
1485
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1486

1487 1488 1489 1490 1491 1492 1493 1494
    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();
1495
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1496 1497
    }

1498 1499 1500
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1501

DonLakeFlyer's avatar
DonLakeFlyer committed
1502 1503 1504 1505 1506 1507 1508
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1509 1510
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1511

1512 1513
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1514 1515
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1516 1517 1518

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1519
            if (item->coordinateHasRelativeAltitude()) {
1520 1521 1522 1523
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1524
                item->setTerrainPercent(qQNaN());
1525
                item->setTerrainCollision(false);
1526 1527
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1528 1529 1530 1531 1532 1533 1534
                double terrainAltitude = item->terrainAltitude();
                if (qIsNaN(terrainAltitude)) {
                    item->setTerrainPercent(qQNaN());
                    item->setTerrainCollision(false);
                } else {
                    item->setTerrainPercent((terrainAltitude - minAltSeen) / altRange);
                    item->setTerrainCollision(absoluteAltitude < terrainAltitude);
1535
                }
1536
            }
1537 1538
        }
    }
1539 1540

    _updateTimer.start(UPDATE_TIMEOUT);
1541 1542
}

1543 1544 1545
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1546 1547 1548 1549 1550
    if (_inRecalcSequence) {
        // Don't let this call recurse due to signalling
        return;
    }

1551 1552
    // Setup ascending sequence numbers for all visual items

1553
    _inRecalcSequence = true;
1554 1555 1556
    int sequenceNumber = 0;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1557 1558
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1559 1560
    }    
    _inRecalcSequence = false;
1561 1562
}

1563 1564 1565
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1566
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1567 1568 1569

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

1570 1571
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1572 1573 1574 1575 1576

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1577
        } else if (item->isSimpleItem()) {
1578 1579 1580 1581 1582
            currentParentItem->childItems()->append(item);
        }
    }
}

1583
void MissionController::_setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate)
1584
{
1585 1586
    QGeoCoordinate firstCoordinate;

1587 1588 1589 1590
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1591
    // Set the planned home position to be a delta from first coordinate
1592 1593 1594 1595
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

        if (item->specifiesCoordinate()) {
1596 1597
            firstCoordinate = item->coordinate();
            break;
1598 1599 1600
        }
    }

1601 1602 1603 1604
    // No item specifying a coordinate was found, in this case it we have a clickCoordinate use that
    if (!firstCoordinate.isValid()) {
        firstCoordinate = clickCoordinate;
    }
1605

1606 1607 1608 1609 1610 1611 1612 1613 1614
    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)
1615
{
1616
    if (!_flyView) {
1617
        _setPlannedHomePositionFromFirstCoordinate(clickCoordinate);
1618
    }
1619
    _recalcSequence();
1620 1621
    _recalcChildItems();
    _recalcWaypointLines();
1622
    _updateTimer.start(UPDATE_TIMEOUT);
1623 1624
}

1625 1626 1627 1628 1629 1630
void MissionController::_recalcAll(void)
{
    QGeoCoordinate emptyCoord;
    _recalcAllWithClickCoordinate(emptyCoord);
}

1631
/// Initializes a new set of mission items
1632
void MissionController::_initAllVisualItems(void)
1633
{
1634 1635
    // Setup home position at index 0

1636 1637 1638
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1639 1640
        return;
    }
1641
    if (!_flyView) {
1642 1643
        _settingsItem->setIsCurrentItem(true);
    }
1644

1645
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1646
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1647
    }
1648

1649 1650 1651
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1652

1653 1654 1655 1656
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1657

1658
    _recalcAll();
1659

1660
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1661 1662 1663
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1664
    emit containsItemsChanged(containsItems());
1665
    emit plannedHomePositionChanged(plannedHomePosition());
1666

1667
    setDirty(false);
1668 1669
}

1670
void MissionController::_deinitAllVisualItems(void)
1671
{
1672 1673 1674
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1675 1676
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1677 1678
    }

1679
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1680
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1681 1682
}

1683
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1684
{
1685
    setDirty(false);
1686

1687
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1688 1689
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1690 1691
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1692
    connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged,                this, &MissionController::_recalcMissionFlightStatus);
1693
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1694
    connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged,                 this, &MissionController::_recalcMissionFlightStatus);
1695
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1696

1697 1698 1699 1700 1701 1702 1703 1704
    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";
        }
1705 1706
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1707
        if (complexItem) {
1708
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
1709
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
1710 1711 1712
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1713
    }
1714 1715
}

1716
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1717
{
1718 1719
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1720 1721
}

1722
void MissionController::_itemCommandChanged(void)
1723
{
1724 1725
    _recalcChildItems();
    _recalcWaypointLines();
1726 1727
}

1728
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1729
{
1730 1731 1732 1733 1734 1735
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1736

1737 1738
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1739
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1740 1741
        return;
    }
1742

1743 1744
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1745 1746
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1747 1748 1749 1750 1751
    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);
1752
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1753 1754 1755 1756
    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);
1757

1758 1759
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1760
    }
1761

1762
    emit complexMissionItemNamesChanged();
1763
    emit resumeMissionIndexChanged();
1764 1765
}

1766
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1767
{
1768
    if (_visualItems) {
1769 1770
        bool currentDirtyBit = dirty();

1771
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1772
        if (settingsItem) {
1773
            settingsItem->setHomePositionFromVehicle(homePosition);
1774
        } else {
1775
            qWarning() << "First item is not MissionSettingsItem";
1776
        }
1777 1778 1779 1780 1781 1782

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

void MissionController::_inProgressChanged(bool inProgress)
1787
{
1788
    emit syncInProgressChanged(inProgress);
1789
}
1790

1791
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1792
{
1793 1794
    bool        found = false;
    double      foundAltitude;
1795
    int         foundAltitudeMode;
1796

1797 1798 1799 1800 1801 1802
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1805 1806 1807
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1808 1809 1810
                if (simpleItem->specifiesAltitude()) {
                    foundAltitude = simpleItem->altitude()->rawValue().toDouble();
                    foundAltitudeMode = simpleItem->altitudeMode();
1811
                    found = true;
1812
                    break;
1813 1814
                }
            }
1815 1816 1817
        }
    }

1818
    if (found) {
1819
        *prevAltitude = foundAltitude;
1820
        *prevAltitudeMode = foundAltitudeMode;
1821 1822 1823
    }

    return found;
1824
}
1825 1826 1827 1828 1829 1830 1831 1832 1833 1834 1835 1836 1837

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

1838
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1839
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1840
{
1841
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
1842

Don Gagne's avatar
Don Gagne committed
1843 1844
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1845
    visualItems->insert(0, settingsItem);
1846

1847 1848 1849 1850 1851 1852 1853 1854 1855 1856 1857 1858 1859 1860 1861 1862 1863 1864 1865 1866 1867 1868 1869 1870 1871
    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;
                    }
1872 1873
                }
            }
1874

1875 1876 1877
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1878
        }
Don Gagne's avatar
Don Gagne committed
1879 1880
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1881 1882
    }
}
1883

1884
int MissionController::resumeMissionIndex(void) const
1885
{
1886

1887
    int resumeIndex = 0;
1888

1889
    if (_flyView) {
1890
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1891
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1892 1893
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1894 1895
        } else {
            resumeIndex = 0;
1896 1897 1898 1899 1900
        }
    }

    return resumeIndex;
}
1901

1902 1903
int MissionController::currentMissionIndex(void) const
{
1904
    if (!_flyView) {
1905 1906 1907 1908 1909 1910 1911 1912 1913 1914
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

1915
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1916
{
1917
    if (_flyView) {
1918
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1919 1920 1921
            sequenceNumber++;
        }

1922 1923
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1924 1925
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1926
        emit currentMissionIndexChanged(currentMissionIndex());
1927 1928
    }
}
1929

1930
bool MissionController::syncInProgress(void) const
1931
{
1932
    return _missionManager->inProgress();
1933 1934 1935 1936 1937 1938 1939 1940 1941 1942 1943 1944
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1945
    }
1946
}
1947

1948 1949
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1950 1951
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, vehicle);
1952

1953 1954 1955 1956 1957 1958
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1959
        if (!_flyView) {
1960 1961 1962 1963 1964 1965
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
1966 1967 1968
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1969
        if (simpleItem) {
1970 1971 1972 1973 1974
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
1975 1976 1977
        }
    }
}
1978 1979 1980 1981 1982 1983 1984 1985 1986 1987 1988 1989 1990

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
1991 1992 1993 1994 1995 1996 1997 1998
    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();
    }
1999
}
2000 2001 2002 2003 2004

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

2005
    complexItems.append(_circularSurveyMissionItemName);
2006
    complexItems.append(_surveyMissionItemName);
2007
    complexItems.append(patternCorridorScanName);
2008
    if (_controllerVehicle->fixedWing()) {
2009
        complexItems.append(patternFWLandingName);
2010
    }
2011
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
2012
        complexItems.append(patternStructureScanName);
2013
    }
2014

2015
    return qgcApp()->toolbox()->corePlugin()->complexMissionItemNames(_controllerVehicle, complexItems);
2016
}
2017

2018 2019
void MissionController::resumeMission(int resumeIndex)
{
2020
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
2021 2022
        resumeIndex--;
    }
2023
    _missionManager->generateResumeMission(resumeIndex);
2024
}
2025 2026 2027 2028 2029 2030 2031 2032 2033

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
2034 2035 2036 2037 2038 2039 2040 2041 2042 2043

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

2045 2046 2047 2048 2049 2050 2051
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
2052 2053 2054 2055 2056 2057

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
2058 2059 2060

bool MissionController::showPlanFromManagerVehicle (void)
{
2061
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
DonLakeFlyer's avatar
DonLakeFlyer committed
2062 2063
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
2064
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
2065 2066 2067 2068 2069 2070 2071 2072 2073 2074 2075 2076 2077 2078 2079 2080 2081 2082 2083
    } 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;
        }
    }
}

2084
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2085
{
2086
    // Fly view always reloads on send complete
2087
    if (!error && _flyView) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2088 2089 2090 2091
        showPlanFromManagerVehicle();
    }
}

2092
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2093
{
2094 2095 2096 2097
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2098
}
2099 2100 2101 2102 2103 2104 2105 2106 2107 2108 2109 2110 2111 2112 2113 2114 2115 2116 2117 2118 2119 2120 2121 2122 2123 2124 2125 2126 2127 2128

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

void MissionController::_updateTimeout()
{
Gus Grubba's avatar
Gus Grubba committed
2132
    QGeoCoordinate firstCoordinate;
2133
    QGeoCoordinate takeoffCoordinate;
2134
    QGCGeoBoundingCube boundingCube;
2135 2136 2137 2138
    double north = 0.0;
    double south = 180.0;
    double east  = 0.0;
    double west  = 360.0;
2139 2140
    double minAlt = QGCGeoBoundingCube::MaxAlt;
    double maxAlt = QGCGeoBoundingCube::MinAlt;
2141 2142 2143 2144 2145 2146
    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()) {
2147
                case MAV_CMD_NAV_TAKEOFF:
2148 2149 2150
                case MAV_CMD_NAV_WAYPOINT:
                case MAV_CMD_NAV_LAND:
                if(pSimpleItem->coordinate().isValid()) {
2151
                    if((MAV_CMD)pSimpleItem->command() == MAV_CMD_NAV_TAKEOFF) {
Gus Grubba's avatar
Gus Grubba committed
2152 2153 2154 2155
                        takeoffCoordinate = pSimpleItem->coordinate();
                    } else if(!firstCoordinate.isValid()) {
                        firstCoordinate = pSimpleItem->coordinate();
                    }
2156 2157
                    double lat = pSimpleItem->coordinate().latitude()  + 90.0;
                    double lon = pSimpleItem->coordinate().longitude() + 180.0;
2158
                    double alt = pSimpleItem->coordinate().altitude();
2159 2160 2161 2162
                    north  = fmax(north, lat);
                    south  = fmin(south, lat);
                    east   = fmax(east,  lon);
                    west   = fmin(west,  lon);
2163 2164
                    minAlt = fmin(minAlt, alt);
                    maxAlt = fmax(maxAlt, alt);
2165 2166 2167 2168 2169 2170 2171 2172 2173
                }
                break;
                default:
                    break;
                }
            }
        } else {
            ComplexMissionItem* pComplexItem = qobject_cast<ComplexMissionItem*>(item);
            if(pComplexItem) {
2174 2175
                QGCGeoBoundingCube bc = pComplexItem->boundingCube();
                if(bc.isValid()) {
Gus Grubba's avatar
Gus Grubba committed
2176 2177 2178
                    if(!firstCoordinate.isValid() && pComplexItem->coordinate().isValid()) {
                        firstCoordinate = pComplexItem->coordinate();
                    }
2179 2180 2181 2182 2183 2184
                    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());
2185 2186 2187 2188
                }
            }
        }
    }
Gus Grubba's avatar
Gus Grubba committed
2189 2190 2191 2192 2193 2194 2195 2196 2197
    //-- Figure out where this thing is taking off from
    if(!takeoffCoordinate.isValid()) {
        if(firstCoordinate.isValid()) {
            takeoffCoordinate = firstCoordinate;
        } else {
            takeoffCoordinate = plannedHomePosition();
        }
    }
    //-- Build bounding "cube"
2198 2199 2200
    boundingCube = QGCGeoBoundingCube(
        QGeoCoordinate(north - 90.0, west - 180.0, minAlt),
        QGeoCoordinate(south - 90.0, east - 180.0, maxAlt));
2201 2202
    if(_travelBoundingCube != boundingCube || _takeoffCoordinate != takeoffCoordinate) {
        _takeoffCoordinate  = takeoffCoordinate;
2203
        _travelBoundingCube = boundingCube;
2204
        emit missionBoundingCubeChanged();
2205
        qCDebug(MissionControllerLog) << "Bounding cube:" << _travelBoundingCube.pointNW << _travelBoundingCube.pointSE;
2206 2207 2208 2209 2210 2211 2212
    }
}

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