MissionController.cc 93.2 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
#define UPDATE_TIMEOUT 5000 ///< How often we check for bounding box changes

36 37
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

38
const char* MissionController::_settingsGroup =                 "MissionController";
Don Gagne's avatar
Don Gagne committed
39 40
const char* MissionController::_jsonFileTypeValue =             "Mission";
const char* MissionController::_jsonItemsKey =                  "items";
41
const char* MissionController::_jsonPlannedHomePositionKey =    "plannedHomePosition";
Don Gagne's avatar
Don Gagne committed
42
const char* MissionController::_jsonFirmwareTypeKey =           "firmwareType";
43 44 45
const char* MissionController::_jsonVehicleTypeKey =            "vehicleType";
const char* MissionController::_jsonCruiseSpeedKey =            "cruiseSpeed";
const char* MissionController::_jsonHoverSpeedKey =             "hoverSpeed";
Don Gagne's avatar
Don Gagne committed
46 47 48 49 50 51 52
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;
53

54 55 56
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"));
57

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

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

83 84
}

85 86 87 88 89 90 91 92 93
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;
94 95 96
    _missionFlightStatus.cruiseSpeed =          _controllerVehicle->defaultCruiseSpeed();
    _missionFlightStatus.hoverSpeed =           _controllerVehicle->defaultHoverSpeed();
    _missionFlightStatus.vehicleSpeed =         _controllerVehicle->multiRotor() || _managerVehicle->vtol() ? _missionFlightStatus.hoverSpeed : _missionFlightStatus.cruiseSpeed;
97
    _missionFlightStatus.vehicleYaw =           0.0;
98
    _missionFlightStatus.gimbalYaw =            std::numeric_limits<double>::quiet_NaN();
99
    _missionFlightStatus.gimbalPitch =          std::numeric_limits<double>::quiet_NaN();
100 101 102 103 104 105 106 107 108 109 110 111

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

112 113 114
    _controllerVehicle->firmwarePlugin()->batteryConsumptionData(_controllerVehicle, _missionFlightStatus.mAhBattery, _missionFlightStatus.hoverAmps, _missionFlightStatus.cruiseAmps);
    if (_missionFlightStatus.mAhBattery != 0) {
        double batteryPercentRemainingAnnounce = qgcApp()->toolbox()->settingsManager()->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toDouble();
115
        _missionFlightStatus.ampMinutesAvailable = static_cast<double>(_missionFlightStatus.mAhBattery) / 1000.0 * 60.0 * ((100.0 - batteryPercentRemainingAnnounce) / 100.0);
116
    }
117 118 119 120 121 122 123 124 125 126 127

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

128 129
}

130
void MissionController::start(bool flyView)
131
{
132
    qCDebug(MissionControllerLog) << "start flyView" << flyView;
133

134
    PlanElementController::start(flyView);
135 136 137 138 139
    _init();
}

void MissionController::_init(void)
{
140
    // We start with an empty mission
141
    _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
142
    _addMissionSettings(_visualItems, false /* addToCenter */);
143
    _initAllVisualItems();
144 145
}

146
// Called when new mission items have completed downloading from Vehicle
147
void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllRequested)
148
{
149
    qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle flyView:count" << _flyView << _missionManager->missionItems().count();
150

DonLakeFlyer's avatar
DonLakeFlyer committed
151
    // Fly view always reloads on _loadComplete
152 153 154 155
    // Plan view only reloads if:
    //  - Load was specifically requested
    //  - There is no current Plan
    if (_flyView || removeAllRequested || _itemsRequested || isEmpty()) {
156
        // Fly Mode (accept if):
Don Gagne's avatar
Don Gagne committed
157
        //      - Always accepts new items from the vehicle so Fly view is kept up to date
158
        // Edit Mode (accept if):
159 160
        //      - 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
161
        //      - The initial automatic load from a vehicle completed and the current editor is empty
162

163
        QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
164
        const QList<MissionItem*>& newMissionItems = _missionManager->missionItems();
165 166
        qCDebug(MissionControllerLog) << "loading from vehicle: count"<< newMissionItems.count();

167 168 169
        _missionItemCount = newMissionItems.count();
        emit missionItemCountChanged(_missionItemCount);

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

186
        for (; i < newMissionItems.count(); i++) {
187
            const MissionItem* missionItem = newMissionItems[i];
188
            newControllerMissionItems->append(new SimpleMissionItem(_controllerVehicle, _flyView, *missionItem, this));
189 190 191
        }

        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
192
        _visualItems->deleteLater();
193 194
        _settingsItem = nullptr;
        _visualItems  = nullptr;
195
        _updateContainsItems(); // This will clear containsItems which will be set again below. This will re-pop Start Mission confirmation.
196 197
        _visualItems = newControllerMissionItems;

198
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
199
            _addMissionSettings(_visualItems, !_flyView && _visualItems->count() > 0 /* addToCenter */);
200 201
        }

202
        MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
203

204
        _initAllVisualItems();
205
        _updateContainsItems();
206
        emit newItemsFromVehicle();
207
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
208
    _itemsRequested = false;
209 210
}

211
void MissionController::loadFromVehicle(void)
212
{
DonLakeFlyer's avatar
DonLakeFlyer committed
213 214 215 216 217 218 219 220
    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();
    }
221 222
}

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

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

254 255 256 257 258
/// Converts from visual items to MissionItems
///     @param missionItemParent QObject parent for newly allocated MissionItems
/// @return true: Mission end action was added to end of list
bool MissionController::_convertToMissionItems(QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
259 260 261 262
    if (visualMissionItems->count() == 0) {
        return false;
    }

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

    return endActionSet;
}

287 288
void MissionController::convertToKMLDocument(QDomDocument& document)
{
289 290
    QObject*            deleteParent = new QObject();
    QList<MissionItem*> rgMissionItems;
291

292 293
    _convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
    if (rgMissionItems.count() == 0) {
294 295
        return;
    }
296

297
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
298 299 300 301 302

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

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

    deleteParent->deleteLater();

324 325 326 327 328
    Kml kml;
    kml.points(coords);
    kml.save(document);
}

Don Gagne's avatar
Don Gagne committed
329 330 331
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
332
        QList<MissionItem*> rgMissionItems;
333

334
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
335

336
        // PlanManager takes control of MissionItems so no need to delete
337
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
338 339
    }
}
340

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

Don Gagne's avatar
Don Gagne committed
352
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int visualItemIndex)
353
{
354
    int sequenceNumber = _nextSequenceNumber();
355
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
356
    newItem->setSequenceNumber(sequenceNumber);
357
    newItem->setCoordinate(coordinate);
358
    newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
359
    _initVisualItem(newItem);
360
    if (_visualItems->count() == 1 && (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() || _controllerVehicle->multiRotor())) {
361
        MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
362
        if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) {
363 364
            newItem->setCommand(takeoffCmd);
        }
365
    }
366 367 368
    if (newItem->specifiesAltitude()) {
        double  prevAltitude;
        int     prevAltitudeMode;
369

Don Gagne's avatar
Don Gagne committed
370
        if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltitudeMode)) {
371
            newItem->altitude()->setRawValue(prevAltitude);
372
            newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
373
        }
374
    }
375
    newItem->setMissionFlightStatus(_missionFlightStatus);
Don Gagne's avatar
Don Gagne committed
376
    _visualItems->insert(visualItemIndex, newItem);
377

378 379
    // 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);
380

381
    return newItem->sequenceNumber();
382 383
}

Don Gagne's avatar
Don Gagne committed
384
int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int visualItemIndex)
385 386
{
    int sequenceNumber = _nextSequenceNumber();
387
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
388
    newItem->setSequenceNumber(sequenceNumber);
389
    newItem->setCommand((_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_DO_SET_ROI_LOCATION) ?
390 391
        MAV_CMD_DO_SET_ROI_LOCATION :
        MAV_CMD_DO_SET_ROI));
392
    _initVisualItem(newItem);
393
    newItem->setCoordinate(coordinate);
394

395 396
    double  prevAltitude;
    int     prevAltitudeMode;
397

Don Gagne's avatar
Don Gagne committed
398
    if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltitudeMode)) {
399
        newItem->altitude()->setRawValue(prevAltitude);
400
        newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
401
    }
Don Gagne's avatar
Don Gagne committed
402
    _visualItems->insert(visualItemIndex, newItem);
403 404 405 406 407 408

    _recalcAll();

    return newItem->sequenceNumber();
}

Don Gagne's avatar
Don Gagne committed
409
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int visualItemIndex)
410
{
411 412
    ComplexMissionItem* newItem;

413 414
    // If the ComplexMissionItem is inserted first, add a TakeOff SimpleMissionItem
    if (_visualItems->count() == 1 && (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() || _controllerVehicle->multiRotor())) {
415 416
        insertSimpleMissionItem(mapCenterCoordinate, visualItemIndex);
        visualItemIndex++;
417 418
    }

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

Don Gagne's avatar
Don Gagne committed
434
    return _insertComplexMissionItemWorker(newItem, visualItemIndex);
435 436
}

Don Gagne's avatar
Don Gagne committed
437
int MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int visualItemIndex)
438 439 440 441
{
    ComplexMissionItem* newItem;

    if (itemName == _surveyMissionItemName) {
442
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
443
    } else if (itemName == patternStructureScanName) {
444
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
445
    } else if (itemName == patternCorridorScanName) {
446
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
447 448 449 450 451
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return _nextSequenceNumber();
    }

Don Gagne's avatar
Don Gagne committed
452
    return _insertComplexMissionItemWorker(newItem, visualItemIndex);
453 454
}

Don Gagne's avatar
Don Gagne committed
455
int MissionController::_insertComplexMissionItemWorker(ComplexMissionItem* complexItem, int visualItemIndex)
456 457
{
    int sequenceNumber = _nextSequenceNumber();
458 459 460
    bool surveyStyleItem = qobject_cast<SurveyComplexItem*>(complexItem) ||
                            qobject_cast<CorridorScanComplexItem*>(complexItem) ||
                            qobject_cast<StructureScanComplexItem*>(complexItem);
461

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

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

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

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

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

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

Don Gagne's avatar
Don Gagne committed
491
    if (visualItemIndex == -1) {
492 493
        _visualItems->append(complexItem);
    } else {
Don Gagne's avatar
Don Gagne committed
494
        _visualItems->insert(visualItemIndex, complexItem);
495
    }
496

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

    return true;
}

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

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

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

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

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

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

829 830 831 832 833 834 835 836
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;
837 838 839 840 841 842
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
843 844

    if (fileVersion == 1) {
845
        return _loadJsonMissionFileV1(json, visualItems, errorString);
846
    } else {
847
        return _loadJsonMissionFileV2(json, visualItems, errorString);
848 849 850
    }
}

851
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
852
{
853 854
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
855 856 857 858 859 860 861 862 863

    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;
864
            plannedHomePositionInFile = true;
865 866 867
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
868
            plannedHomePositionInFile = false;
869 870 871 872
        }
    }

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

877
        while (!stream.atEnd()) {
878
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
879 880

            if (item->load(stream)) {
881 882 883 884 885 886
                if (firstItem && plannedHomePositionInFile) {
                    settingsItem->setCoordinate(item->coordinate());
                } else {
                    visualItems->append(item);
                }
                firstItem = false;
887
            } else {
888
                errorString = tr("The mission file is corrupted.");
889 890 891 892
                return false;
            }
        }
    } else {
893
        errorString = tr("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
894 895 896
        return false;
    }

897
    if (!plannedHomePositionInFile) {
898 899 900
        // 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));
901
            if (item && item->command() == MAV_CMD_DO_JUMP) {
902
                item->missionItem().setParam1(static_cast<int>(item->missionItem().param1()) + 1);
Don Gagne's avatar
Don Gagne committed
903 904
            }
        }
905 906 907
    }

    return true;
908 909
}

910
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
911
{
Don Gagne's avatar
Don Gagne committed
912 913 914
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
915
        _settingsItem = nullptr;
Don Gagne's avatar
Don Gagne committed
916 917
    }

918
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
919 920

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

924
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
925

Don Gagne's avatar
Don Gagne committed
926
    _initAllVisualItems();
927
}
928

929 930 931 932 933 934
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

935
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960
        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;
961
    }
962

963 964 965 966 967 968 969 970 971 972 973 974 975
    _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);
976
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
977 978 979 980 981 982
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
983
    return true;
984 985
}

986 987 988 989 990 991 992 993 994 995 996 997
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;
}

998
void MissionController::save(QJsonObject& json)
999
{
1000
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
1001

1002
    // Mission settings
1003

1004 1005 1006 1007 1008 1009 1010
    MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsItem";
        return;
    }
    QJsonValue coordinateValue;
    JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
1011 1012 1013 1014 1015
    json[_jsonPlannedHomePositionKey]   = coordinateValue;
    json[_jsonFirmwareTypeKey]          = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey]           = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey]           = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey]            = _controllerVehicle->defaultHoverSpeed();
1016

1017
    // Save the visual items
1018

1019 1020 1021
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1022

1023 1024
        visualItem->save(rgJsonMissionItems);
    }
1025

1026 1027 1028
    // Mission settings has a special case for end mission action
    if (settingsItem) {
        QList<MissionItem*> rgMissionItems;
1029

1030 1031 1032 1033 1034
        if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
1035
        }
1036 1037
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
1038 1039 1040
        }
    }

1041
    json[_jsonItemsKey] = rgJsonMissionItems;
1042 1043
}

1044
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
1045
{
Don Gagne's avatar
Don Gagne committed
1046
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
1047
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
1048 1049 1050 1051
    bool            distanceOk =    false;

    // Convert to fixed altitudes

1052
    distanceOk = true;
1053
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
1054 1055
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
1056
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
1057
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
1058 1059 1060
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
1061 1062 1063
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
1064
    } else {
Don Gagne's avatar
Don Gagne committed
1065
        *altDifference = 0.0;
1066
        *azimuth = 0.0;
1067
        *distance = 0.0;
1068 1069 1070
    }
}

1071
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
1072 1073 1074 1075 1076 1077 1078
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

1079
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
1080 1081
}

1082
CoordinateVector* MissionController::_addWaypointLineSegment(CoordVectHashTable& prevItemPairHashTable, VisualItemPair& pair)
1083
{
1084 1085
    CoordinateVector* coordVector = nullptr;

1086 1087
    if (prevItemPairHashTable.contains(pair)) {
        // Pair already exists and connected, just re-use
1088
        _linesTable[pair] = coordVector = prevItemPairHashTable.take(pair);
1089 1090
    } else {
        // Create a new segment and wire update notifiers
1091
        coordVector         = new CoordinateVector(pair.first->isSimpleItem() ? pair.first->coordinate() : pair.first->exitCoordinate(), pair.second->coordinate(), this);
1092 1093 1094 1095
        auto originNotifier = pair.first->isSimpleItem() ? &VisualMissionItem::coordinateChanged : &VisualMissionItem::exitCoordinateChanged;
        auto endNotifier    = &VisualMissionItem::coordinateChanged;

        // Use signals/slots to update the coordinate endpoints
1096 1097
        connect(pair.first,     originNotifier, coordVector, &CoordinateVector::setCoordinate1);
        connect(pair.second,    endNotifier,    coordVector, &CoordinateVector::setCoordinate2);
1098 1099 1100 1101

        // 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);
1102
        _linesTable[pair] = coordVector;
1103
    }
1104 1105

    return coordVector;
1106 1107
}

1108 1109
void MissionController::_recalcWaypointLines(void)
{
1110
    int                 segmentCount = 0;
1111
    VisualItemPair      lastSegmentVisualItemPair;
1112 1113 1114
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

1115
    bool homePositionValid = _settingsItem->coordinate().isValid();
1116

1117
    qCDebug(MissionControllerLog) << "_recalcWaypointLines homePositionValid" << homePositionValid;
1118

Nate Weibley's avatar
Nate Weibley committed
1119
    CoordVectHashTable old_table = _linesTable;
1120

Nate Weibley's avatar
Nate Weibley committed
1121
    _linesTable.clear();
1122
    _waypointPath.clear();
1123 1124 1125 1126 1127

    _waypointLines.beginReset();
    _directionArrows.beginReset();

    _waypointLines.clear();
1128
    _directionArrows.clear();
1129

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

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

1151 1152
        if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
            if (lastCoordinateItem != _settingsItem || (homePositionValid && linkStartToHome)) {
1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164
                // Direction arrows are added to the first segment and every 5 segments in the middle.
                bool addDirectionArrow = false;
                if (firstCoordinateItem || !lastCoordinateItem->isSimpleItem() || !item->isSimpleItem()) {
                    addDirectionArrow = true;
                } else if (segmentCount > 5) {
                    segmentCount = 0;
                    addDirectionArrow = true;
                }
                segmentCount++;

                lastSegmentVisualItemPair =  VisualItemPair(lastCoordinateItem, item);
                if (!_flyView || addDirectionArrow) {
1165 1166 1167 1168
                    CoordinateVector* coordVector = _addWaypointLineSegment(old_table, lastSegmentVisualItemPair);
                    if (addDirectionArrow) {
                        _directionArrows.append(coordVector);
                    }
1169
                }
1170
            }
1171
            firstCoordinateItem = false;
1172 1173
            _waypointPath.append(QVariant::fromValue(item->coordinate()));
            lastCoordinateItem = item;
1174 1175
        }
    }
1176 1177 1178 1179 1180 1181

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

    if (linkEndToHome && lastCoordinateItem != _settingsItem && homePositionValid) {
1182 1183
        lastSegmentVisualItemPair =  VisualItemPair(lastCoordinateItem, _settingsItem);
        if (_flyView) {
1184 1185
            _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
        }
1186
        _addWaypointLineSegment(old_table, lastSegmentVisualItemPair);
1187
    }
1188

1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211
    // Add direction arrow to last segment
    if (lastSegmentVisualItemPair.first) {
        CoordinateVector* coordVector = nullptr;

        // The pair may not be in the hash, this can happen in the fly view where only segments with arrows on them are added to ahsh.
        // check for that first and add if needed

        if (_linesTable.contains(lastSegmentVisualItemPair)) {
            // Pair exists in the new table already just reuse it
             coordVector = _linesTable[lastSegmentVisualItemPair];
        } else if (old_table.contains(lastSegmentVisualItemPair)) {
            // Pair already exists in old table, pull from old to new and reuse
            _linesTable[lastSegmentVisualItemPair] = coordVector = old_table.take(lastSegmentVisualItemPair);
        } else {
            // Create a new segment. Since this is the fly view there is no need to wire change signals.
            coordVector = new CoordinateVector(lastSegmentVisualItemPair.first->isSimpleItem() ? lastSegmentVisualItemPair.first->coordinate() : lastSegmentVisualItemPair.first->exitCoordinate(), lastSegmentVisualItemPair.second->coordinate(), this);
            _linesTable[lastSegmentVisualItemPair] = coordVector;
        }

        _directionArrows.append(coordVector);
    }

    if (!_flyView) {
1212 1213
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1214
        objs.reserve(_linesTable.count());
1215
        for(CoordinateVector *vect: _linesTable.values()) {
1216 1217 1218 1219 1220 1221 1222
            objs.append(vect);
        }

        // We don't delete here because many links may still be valid
        _waypointLines.swapObjectList(objs);
    }

1223 1224 1225
    _waypointLines.endReset();
    _directionArrows.endReset();

1226 1227 1228
    // Anything left in the old table is an obsolete line object that can go
    qDeleteAll(old_table);

DonLakeFlyer's avatar
DonLakeFlyer committed
1229
    _recalcMissionFlightStatus();
1230

1231
    if (_waypointPath.count() == 0) {
1232
        // MapPolyLine has a bug where if you change from a path which has elements to an empty path the line drawn
1233 1234 1235 1236 1237 1238 1239
        // 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)));
    }

    emit waypointPathChanged();
1240 1241
}

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

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

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

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1313
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1314

1315 1316 1317
    // 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.
1318

1319
    // No values for first item
1320
    lastCoordinateItem->setAltDifference(0.0);
1321
    lastCoordinateItem->setAzimuth(0.0);
1322
    lastCoordinateItem->setDistance(0.0);
1323

1324 1325
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1326 1327
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1328

1329
    _resetMissionFlightStatus();
1330

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1344
    for (int i=0; i<_visualItems->count(); i++) {
1345
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1346 1347 1348
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1349 1350
        // Assume the worst
        item->setAzimuth(0.0);
1351
        item->setDistance(0.0);
1352

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

        // Look for gimbal change
1371 1372 1373 1374 1375 1376 1377
        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
1378 1379 1380 1381 1382
        }

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

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

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

1429
        _addTimeDistance(vtolInHover, 0, 0, item->additionalTimeDelay(), 0, -1);
1430

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

1434
            double absoluteAltitude = item->coordinate().altitude();
1435
            if (item->coordinateHasRelativeAltitude()) {
1436 1437 1438 1439 1440
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1441 1442 1443 1444
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1445 1446 1447
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1448
                firstCoordinateItem = false;
1449 1450 1451 1452 1453 1454 1455

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

1456
                if (lastCoordinateItem != _settingsItem || linkStartToHome) {
1457 1458
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1459

1460
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1461 1462 1463
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1464

1465
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1466

DonLakeFlyer's avatar
DonLakeFlyer committed
1467 1468 1469
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1470
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1471
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1472

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

1478 1479
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1480
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1481
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1482 1483

                item->setMissionFlightStatus(_missionFlightStatus);
1484

1485 1486
                lastCoordinateItem = item;
            }
1487 1488
        }
    }
1489
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1490

1491 1492 1493 1494 1495 1496 1497 1498
    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();
1499
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1500 1501
    }

1502 1503 1504
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1505

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

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

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

    _updateTimer.start(UPDATE_TIMEOUT);
1545 1546
}

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

1555 1556
    // Setup ascending sequence numbers for all visual items

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

1567 1568 1569
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1570
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1571 1572 1573

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

1574 1575
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1576 1577 1578 1579 1580

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1581
        } else if (item->isSimpleItem()) {
1582 1583 1584 1585 1586
            currentParentItem->childItems()->append(item);
        }
    }
}

1587
void MissionController::_setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate)
1588
{
1589 1590
    QGeoCoordinate firstCoordinate;

1591 1592 1593 1594
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

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

        if (item->specifiesCoordinate()) {
1600 1601
            firstCoordinate = item->coordinate();
            break;
1602 1603 1604
        }
    }

1605 1606 1607 1608
    // No item specifying a coordinate was found, in this case it we have a clickCoordinate use that
    if (!firstCoordinate.isValid()) {
        firstCoordinate = clickCoordinate;
    }
1609

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

1629 1630 1631 1632 1633 1634
void MissionController::_recalcAll(void)
{
    QGeoCoordinate emptyCoord;
    _recalcAllWithClickCoordinate(emptyCoord);
}

1635
/// Initializes a new set of mission items
1636
void MissionController::_initAllVisualItems(void)
1637
{
1638 1639
    // Setup home position at index 0

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

1649
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1650
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1651
    }
1652

1653 1654 1655
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1656

1657 1658 1659 1660
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1661

1662
    _recalcAll();
1663

1664
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1665 1666 1667
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1668
    emit containsItemsChanged(containsItems());
1669
    emit plannedHomePositionChanged(plannedHomePosition());
1670

1671
    setDirty(false);
1672 1673
}

1674
void MissionController::_deinitAllVisualItems(void)
1675
{
1676 1677 1678
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1679 1680
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1681 1682
    }

1683
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1684
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1685 1686
}

1687
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1688
{
1689
    setDirty(false);
1690

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

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

1720
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1721
{
1722
    // Disconnect all signals
1723
    disconnect(visualItem, nullptr, nullptr, nullptr);
1724 1725
}

1726
void MissionController::_itemCommandChanged(void)
1727
{
1728 1729
    _recalcChildItems();
    _recalcWaypointLines();
1730 1731
}

1732
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1733
{
1734 1735 1736
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
1737 1738
        _managerVehicle = nullptr;
        _missionManager = nullptr;
1739
    }
1740

1741 1742
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1743
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1744 1745
        return;
    }
1746

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

1762 1763
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1764
    }
1765

1766
    emit complexMissionItemNamesChanged();
1767
    emit resumeMissionIndexChanged();
1768 1769
}

1770
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1771
{
1772
    if (_visualItems) {
1773 1774
        bool currentDirtyBit = dirty();

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

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

void MissionController::_inProgressChanged(bool inProgress)
1791
{
1792
    emit syncInProgressChanged(inProgress);
1793
}
1794

1795
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1796
{
1797 1798
    bool        found = false;
    double      foundAltitude;
1799
    int         foundAltitudeMode;
1800

1801 1802 1803 1804 1805 1806
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

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

1822
    if (found) {
1823
        *prevAltitude = foundAltitude;
1824
        *prevAltitudeMode = foundAltitudeMode;
1825 1826 1827
    }

    return found;
1828
}
1829 1830 1831 1832 1833 1834 1835 1836 1837 1838 1839 1840 1841

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

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

Don Gagne's avatar
Don Gagne committed
1847 1848
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1849
    visualItems->insert(0, settingsItem);
1850

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

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

1888
int MissionController::resumeMissionIndex(void) const
1889
{
1890

1891
    int resumeIndex = 0;
1892

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

    return resumeIndex;
}
1905

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

1919
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1920
{
1921
    if (_flyView) {
1922
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1923 1924 1925
            sequenceNumber++;
        }

1926 1927
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1928 1929
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1930
        emit currentMissionIndexChanged(currentMissionIndex());
1931 1932
    }
}
1933

1934
bool MissionController::syncInProgress(void) const
1935
{
1936
    return _missionManager->inProgress();
1937 1938 1939 1940 1941 1942 1943 1944 1945 1946 1947 1948
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1949
    }
1950
}
1951

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

1957 1958 1959 1960 1961 1962
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1963
        if (!_flyView) {
1964 1965 1966 1967 1968 1969
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
1970 1971 1972
        }

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

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
1995 1996 1997 1998 1999 2000 2001 2002
    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();
    }
2003
}
2004 2005 2006 2007 2008 2009

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

    complexItems.append(_surveyMissionItemName);
2010
    complexItems.append(patternCorridorScanName);
2011
    if (_controllerVehicle->fixedWing()) {
2012
        complexItems.append(patternFWLandingName);
2013
    }
2014
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
2015
        complexItems.append(patternStructureScanName);
2016
    }
2017

2018
    return qgcApp()->toolbox()->corePlugin()->complexMissionItemNames(_controllerVehicle, complexItems);
2019
}
2020

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

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

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

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

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
2061 2062 2063

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

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

2095
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2096
{
2097 2098 2099 2100
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2101
}
2102 2103 2104 2105 2106 2107 2108 2109 2110 2111 2112 2113 2114

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

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

void MissionController::setCurrentPlanViewIndex(int sequenceNumber, bool force)
{
2115
    qDebug() << "setCurrentPlanViewIndex" << sequenceNumber << force << _currentPlanViewIndex;
2116
    if(_visualItems && (force || sequenceNumber != _currentPlanViewIndex)) {
2117
        _splitSegment = nullptr;
2118
        _currentPlanViewItem  = nullptr;
2119 2120 2121 2122 2123 2124 2125
        _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;
2126 2127 2128 2129 2130 2131 2132 2133 2134 2135 2136 2137 2138

                if (pVI->specifiesCoordinate() && !pVI->isStandaloneCoordinate()) {
                    // Determine split segment used to display line split editing ui.
                    for (int j=i-1; j>0; j--) {
                        VisualMissionItem* pPrev = qobject_cast<VisualMissionItem*>(_visualItems->get(j));
                        if (pPrev->specifiesCoordinate() && !pPrev->isStandaloneCoordinate()) {
                            VisualItemPair splitPair(pPrev, pVI);
                            if (_linesTable.contains(splitPair)) {
                                _splitSegment = _linesTable[splitPair];
                            }
                        }
                    }
                }
2139 2140 2141 2142 2143 2144
            } else {
                pVI->setIsCurrentItem(false);
            }
        }
        emit currentPlanViewIndexChanged();
        emit currentPlanViewItemChanged();
2145
        emit splitSegmentChanged();
2146 2147
    }
}
2148 2149 2150

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

void MissionController::_complexBoundingBoxChanged()
{
    _updateTimer.start(UPDATE_TIMEOUT);
}
2232 2233 2234 2235 2236

bool MissionController::isEmpty(void) const
{
    return _visualItems->count() <= 1;
}
Don Gagne's avatar
Don Gagne committed
2237 2238 2239 2240 2241 2242 2243 2244 2245 2246 2247 2248 2249

int MissionController::visualItemIndexFromSequenceNumber(int sequenceNumber) const
{
    for (int i=0; i<_visualItems->count(); i++) {
        const VisualMissionItem* vi = _visualItems->value<VisualMissionItem*>(i);
        if (vi->sequenceNumber() == sequenceNumber) {
            return i;
        }
    }

    qWarning() << "MissionController::getVisualItemIndex visual item not found";
    return 0;
}