MissionController.cc 97.6 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
#include "TakeoffMissionItem.h"
34

35 36
#define UPDATE_TIMEOUT 5000 ///< How often we check for bounding box changes

37 38
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

DonLakeFlyer's avatar
DonLakeFlyer committed
55 56 57 58
const QString MissionController::patternSurveyName          (QT_TRANSLATE_NOOP("MissionController", "Survey"));
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"));
59

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

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

84 85
}

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

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

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

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

129 130
}

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

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

void MissionController::_init(void)
{
141
    // We start with an empty mission
142
    _visualItems = new QmlObjectListModel(this);
143
    _addMissionSettings(_visualItems);
144
    _initAllVisualItems();
145 146
}

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

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

164 165 166
        _deinitAllVisualItems();
        _visualItems->deleteLater();
        _visualItems  = nullptr;
167
        _settingsItem = nullptr;
168 169
        _updateContainsItems(); // This will clear containsItems which will be set again below. This will re-pop Start Mission confirmation.

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

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

177
        MissionSettingsItem* settingsItem = _addMissionSettings(newControllerMissionItems);
178 179 180

        int i=0;
        if (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() && newMissionItems.count() != 0 && !_flyView) {
181
            // First item is fake home position
182 183
            MissionItem* fakeHomeItem = newMissionItems[0];
            if (fakeHomeItem->coordinate().latitude() != 0 || fakeHomeItem->coordinate().longitude() != 0) {
184
                settingsItem->setInitialHomePosition(fakeHomeItem->coordinate());
185
            }
186 187
            i = 1;
        }
188

189
        for (; i < newMissionItems.count(); i++) {
190
            const MissionItem* missionItem = newMissionItems[i];
191 192 193
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, *missionItem, this);
            if (TakeoffMissionItem::isTakeoffCommand(static_cast<MAV_CMD>(simpleItem->command()))) {
                // This needs to be a TakeoffMissionItem
194
                TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(*missionItem, _controllerVehicle, _flyView, settingsItem, this);
195 196 197 198
                simpleItem->deleteLater();
                simpleItem = takeoffItem;
            }
            newControllerMissionItems->append(simpleItem);
199 200 201
        }

        _visualItems = newControllerMissionItems;
202
        _settingsItem = settingsItem;
203

204
        MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
205

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

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

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

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

256 257 258 259 260
/// 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
261 262 263 264
    if (visualMissionItems->count() == 0) {
        return false;
    }

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

    return endActionSet;
}

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

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

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

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

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

    deleteParent->deleteLater();

326 327 328 329 330
    Kml kml;
    kml.points(coords);
    kml.save(document);
}

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

336
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
337

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

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

354
VisualMissionItem* MissionController::_insertSimpleMissionItemWorker(QGeoCoordinate coordinate, MAV_CMD command, int visualItemIndex, bool makeCurrentItem)
355
{
356
    int sequenceNumber = _nextSequenceNumber();
357
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
358
    newItem->setSequenceNumber(sequenceNumber);
359
    newItem->setCoordinate(coordinate);
360
    newItem->setCommand(command);
361
    _initVisualItem(newItem);
362 363 364 365 366 367 368 369

    if (newItem->specifiesAltitude()) {
        double  prevAltitude;
        int     prevAltitudeMode;

        if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltitudeMode)) {
            newItem->altitude()->setRawValue(prevAltitude);
            newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
370
        }
371
    }
372 373 374 375 376 377 378 379
    newItem->setMissionFlightStatus(_missionFlightStatus);
    if (visualItemIndex == -1) {
        _visualItems->append(newItem);
    } else {
        _visualItems->insert(visualItemIndex, newItem);
    }

    // We send the click coordinate through here to be able to set the planned home position from the user click location if needed
380
    _recalcAllWithCoordinate(coordinate);
381 382 383 384 385 386 387 388

    if (makeCurrentItem) {
        setCurrentPlanViewIndex(newItem->sequenceNumber(), true);
    }

    return newItem;
}

389 390 391 392 393 394

VisualMissionItem* MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem)
{
    return _insertSimpleMissionItemWorker(coordinate, MAV_CMD_NAV_WAYPOINT, visualItemIndex, makeCurrentItem);
}

395
VisualMissionItem* MissionController::insertTakeoffItem(QGeoCoordinate /*coordinate*/, int visualItemIndex, bool makeCurrentItem)
396 397
{
    int sequenceNumber = _nextSequenceNumber();
DonLakeFlyer's avatar
DonLakeFlyer committed
398
    TakeoffMissionItem * newItem = new TakeoffMissionItem(_controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF, _controllerVehicle, _flyView, _settingsItem, this);
399 400 401
    newItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(newItem);

402 403 404
    if (newItem->specifiesAltitude()) {
        double  prevAltitude;
        int     prevAltitudeMode;
405

Don Gagne's avatar
Don Gagne committed
406
        if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltitudeMode)) {
407
            newItem->altitude()->setRawValue(prevAltitude);
408
            newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
409
        }
410
    }
411
    newItem->setMissionFlightStatus(_missionFlightStatus);
412 413 414 415 416
    if (visualItemIndex == -1) {
        _visualItems->append(newItem);
    } else {
        _visualItems->insert(visualItemIndex, newItem);
    }
417

418
    _recalcAll();
419

420 421 422 423 424
    if (makeCurrentItem) {
        setCurrentPlanViewIndex(newItem->sequenceNumber(), true);
    }

    return newItem;
425 426
}

427
VisualMissionItem* MissionController::insertLandItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem)
428
{
429 430 431 432
    if (_managerVehicle->fixedWing()) {
        FixedWingLandingComplexItem* fwLanding = qobject_cast<FixedWingLandingComplexItem*>(insertComplexMissionItem(MissionController::patternFWLandingName, coordinate, visualItemIndex, makeCurrentItem));
        fwLanding->setLoiterDragAngleOnly(true);
        return fwLanding;
433
    } else {
434
        return _insertSimpleMissionItemWorker(coordinate, MAV_CMD_NAV_RETURN_TO_LAUNCH, visualItemIndex, makeCurrentItem);
435
    }
436
}
437

438 439 440 441 442 443
VisualMissionItem* MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem)
{
    MAV_CMD command = _controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_DO_SET_ROI_LOCATION) ?
                MAV_CMD_DO_SET_ROI_LOCATION :
                MAV_CMD_DO_SET_ROI;
    return _insertSimpleMissionItemWorker(coordinate, command, visualItemIndex, makeCurrentItem);
444 445
}

446
VisualMissionItem* MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int visualItemIndex, bool makeCurrentItem)
447
{
448
    ComplexMissionItem* newItem = nullptr;
449

DonLakeFlyer's avatar
DonLakeFlyer committed
450
    if (itemName == patternSurveyName) {
451
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
452
        newItem->setCoordinate(mapCenterCoordinate);
453
    } else if (itemName == patternFWLandingName) {
454
        newItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, _visualItems /* parent */);
455
    } else if (itemName == patternStructureScanName) {
456
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
457
    } else if (itemName == patternCorridorScanName) {
458
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
459 460
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
461
        return nullptr;
462 463
    }

464
    _insertComplexMissionItemWorker(mapCenterCoordinate, newItem, visualItemIndex, makeCurrentItem);
465 466

    return newItem;
467 468
}

469
VisualMissionItem* MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int visualItemIndex, bool makeCurrentItem)
470
{
471
    ComplexMissionItem* newItem = nullptr;
472

DonLakeFlyer's avatar
DonLakeFlyer committed
473
    if (itemName == patternSurveyName) {
474
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
475
    } else if (itemName == patternStructureScanName) {
476
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
477
    } else if (itemName == patternCorridorScanName) {
478
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
479 480
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
481
        return nullptr;
482 483
    }

484
    _insertComplexMissionItemWorker(QGeoCoordinate(), newItem, visualItemIndex, makeCurrentItem);
485 486

    return newItem;
487 488
}

489
void MissionController::_insertComplexMissionItemWorker(const QGeoCoordinate& mapCenterCoordinate, ComplexMissionItem* complexItem, int visualItemIndex, bool makeCurrentItem)
490 491
{
    int sequenceNumber = _nextSequenceNumber();
492
    bool surveyStyleItem = qobject_cast<SurveyComplexItem*>(complexItem) ||
493 494
            qobject_cast<CorridorScanComplexItem*>(complexItem) ||
            qobject_cast<StructureScanComplexItem*>(complexItem);
495

496
    if (surveyStyleItem) {
497
        bool rollSupported  = false;
498
        bool pitchSupported = false;
499
        bool yawSupported   = false;
500 501 502

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

503 504
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
        CameraSection* cameraSection = settingsItem->cameraSection();
505

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

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

522
    complexItem->setSequenceNumber(sequenceNumber);
523
    complexItem->setWizardMode(true);
524
    _initVisualItem(complexItem);
525

Don Gagne's avatar
Don Gagne committed
526
    if (visualItemIndex == -1) {
527 528
        _visualItems->append(complexItem);
    } else {
Don Gagne's avatar
Don Gagne committed
529
        _visualItems->insert(visualItemIndex, complexItem);
530
    }
531

532
    //-- Keep track of bounding box changes in complex items
533 534
    if(!complexItem->isSimpleItem()) {
        connect(complexItem, &ComplexMissionItem::boundingCubeChanged, this, &MissionController::_complexBoundingBoxChanged);
535
    }
536
    _recalcAllWithCoordinate(mapCenterCoordinate);
537

538 539 540
    if (makeCurrentItem) {
        setCurrentPlanViewIndex(complexItem->sequenceNumber(), true);
    }
541 542
}

543 544
void MissionController::removeMissionItem(int index)
{
545 546 547 548 549
    if (index <= 0 || index >= _visualItems->count()) {
        qWarning() << "MissionController::removeMissionItem called with bad index - count:index" << _visualItems->count() << index;
        return;
    }

550
    bool removeSurveyStyle = _visualItems->value<SurveyComplexItem*>(index) || _visualItems->value<CorridorScanComplexItem*>(index);
551
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
552

553
    _deinitVisualItem(item);
554
    item->deleteLater();
555

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

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

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

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

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

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

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

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

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

643
    MissionSettingsItem* settingsItem = _addMissionSettings(visualItems);
644 645 646
    if (json.contains(_jsonPlannedHomePositionKey)) {
        SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
647
            settingsItem->setInitialHomePositionFromUser(item->coordinate());
648 649 650 651 652 653
            item->deleteLater();
        } else {
            return false;
        }
    }

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

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

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

Don Gagne's avatar
Don Gagne committed
680
            const QJsonObject itemObject = itemValue.toObject();
681
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
Don Gagne's avatar
Don Gagne committed
682
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
683 684
                if (TakeoffMissionItem::isTakeoffCommand(item->mavCommand())) {
                    // This needs to be a TakeoffMissionItem
685
                    TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, visualItems);
686 687 688 689
                    takeoffItem->load(itemObject, itemObject["id"].toInt(), errorString);
                    item->deleteLater();
                    item = takeoffItem;
                }
690
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
691
                nextSequenceNumber = item->lastSequenceNumber() + 1;
692
                visualItems->append(item);
693 694 695 696
            } else {
                return false;
            }
        }
697
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
698 699 700 701

    return true;
}

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

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

719
    // Mission Settings
720
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
721

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

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

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

866 867 868 869 870 871 872 873
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;
874 875 876 877 878 879
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
880 881

    if (fileVersion == 1) {
882
        return _loadJsonMissionFileV1(json, visualItems, errorString);
883
    } else {
884
        return _loadJsonMissionFileV2(json, visualItems, errorString);
885 886 887
    }
}

888
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
889
{
890 891
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
892 893 894 895 896 897 898 899 900

    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;
901
            plannedHomePositionInFile = true;
902 903 904
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
905
            plannedHomePositionInFile = false;
906 907 908 909
        }
    }

    if (versionOk) {
910
        MissionSettingsItem* settingsItem = _addMissionSettings(visualItems);
911

912
        while (!stream.atEnd()) {
913
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
914
            if (item->load(stream)) {
915
                if (firstItem && plannedHomePositionInFile) {
916
                    settingsItem->setInitialHomePositionFromUser(item->coordinate());
917
                } else {
918 919
                    if (TakeoffMissionItem::isTakeoffCommand(static_cast<MAV_CMD>(item->command()))) {
                        // This needs to be a TakeoffMissionItem
920
                        TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, visualItems);
921 922 923 924
                        takeoffItem->load(stream);
                        item->deleteLater();
                        item = takeoffItem;
                    }
925 926 927
                    visualItems->append(item);
                }
                firstItem = false;
928
            } else {
929
                errorString = tr("The mission file is corrupted.");
930 931 932 933
                return false;
            }
        }
    } else {
934
        errorString = tr("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
935 936 937
        return false;
    }

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

    return true;
949 950
}

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

959
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
960 961

    if (_visualItems->count() == 0) {
962
        _addMissionSettings(_visualItems);
963 964
    } else {
        _settingsItem = _visualItems->value<MissionSettingsItem*>(0);
Don Gagne's avatar
Don Gagne committed
965 966
    }

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

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

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

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

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

    _initLoadedVisualItems(loadedVisualItems);

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

1029
int MissionController::readyForSaveState(void) const
1030 1031 1032
{
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
DonLakeFlyer's avatar
DonLakeFlyer committed
1033
        if (visualItem->readyForSaveState() != VisualMissionItem::ReadyForSave) {
1034
            return visualItem->readyForSaveState();
1035 1036 1037
        }
    }

1038
    return VisualMissionItem::ReadyForSave;
1039 1040
}

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

1045
    // Mission settings
1046

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

1060
    // Save the visual items
1061

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

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

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

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

1084
    json[_jsonItemsKey] = rgJsonMissionItems;
1085 1086
}

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

    // Convert to fixed altitudes

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

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

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

    distanceOk = true;

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

1125
CoordinateVector* MissionController::_addWaypointLineSegment(CoordVectHashTable& prevItemPairHashTable, VisualItemPair& pair)
1126
{
1127 1128
    CoordinateVector* coordVector = nullptr;

1129 1130
    if (prevItemPairHashTable.contains(pair)) {
        // Pair already exists and connected, just re-use
1131
        _linesTable[pair] = coordVector = prevItemPairHashTable.take(pair);
1132 1133
    } else {
        // Create a new segment and wire update notifiers
1134
        coordVector         = new CoordinateVector(pair.first->isSimpleItem() ? pair.first->coordinate() : pair.first->exitCoordinate(), pair.second->coordinate(), this);
1135 1136 1137 1138
        auto originNotifier = pair.first->isSimpleItem() ? &VisualMissionItem::coordinateChanged : &VisualMissionItem::exitCoordinateChanged;
        auto endNotifier    = &VisualMissionItem::coordinateChanged;

        // Use signals/slots to update the coordinate endpoints
1139 1140
        connect(pair.first,     originNotifier, coordVector, &CoordinateVector::setCoordinate1);
        connect(pair.second,    endNotifier,    coordVector, &CoordinateVector::setCoordinate2);
1141 1142 1143 1144

        // 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);
1145
        _linesTable[pair] = coordVector;
1146
    }
1147 1148

    return coordVector;
1149 1150
}

1151 1152
void MissionController::_recalcWaypointLines(void)
{
1153
    VisualItemPair      lastSegmentVisualItemPair;
1154 1155 1156 1157 1158 1159 1160
    int                 segmentCount =                  0;
    bool                firstCoordinateNotFound =       true;
    VisualMissionItem*  lastCoordinateItemBeforeRTL =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));
    bool                linkEndToHome =                 false;
    bool                linkStartToHome =               _managerVehicle->rover() ? true : false;
    bool                foundRTL =                      false;
    bool                 homePositionValid =            _settingsItem->coordinate().isValid();
1161

1162
    qCDebug(MissionControllerLog) << "_recalcWaypointLines homePositionValid" << homePositionValid;
1163

Nate Weibley's avatar
Nate Weibley committed
1164
    CoordVectHashTable old_table = _linesTable;
1165

Nate Weibley's avatar
Nate Weibley committed
1166
    _linesTable.clear();
1167
    _waypointPath.clear();
1168 1169 1170 1171 1172

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

    _waypointLines.clear();
1173
    _directionArrows.clear();
1174

1175
    // Grovel through the list of items keeping track of things needed to correctly draw waypoints lines
1176

1177
    for (int i=1; i<_visualItems->count(); i++) {
1178 1179
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1180

1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199
        if (simpleItem) {
            MAV_CMD command = simpleItem->mavCommand();
            switch (command) {
            case MAV_CMD_NAV_TAKEOFF:
            case MAV_CMD_NAV_VTOL_TAKEOFF:
                if (!linkEndToHome) {
                    // 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 (firstCoordinateNotFound) {
                        linkStartToHome = true;
                    }
                }
                break;
            case MAV_CMD_NAV_RETURN_TO_LAUNCH:
                linkEndToHome = true;
                foundRTL = true;
                break;
            default:
                break;
1200
            }
1201 1202
        }

1203 1204 1205 1206 1207 1208 1209
        // No need to add waypoint segments after an RTL.
        if (foundRTL) {
            break;
        }

        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (lastCoordinateItemBeforeRTL != _settingsItem || (homePositionValid && linkStartToHome)) {
1210 1211
                // Direction arrows are added to the first segment and every 5 segments in the middle.
                bool addDirectionArrow = false;
1212
                if (firstCoordinateNotFound || !lastCoordinateItemBeforeRTL->isSimpleItem() || !visualItem->isSimpleItem()) {
1213 1214 1215 1216 1217 1218 1219
                    addDirectionArrow = true;
                } else if (segmentCount > 5) {
                    segmentCount = 0;
                    addDirectionArrow = true;
                }
                segmentCount++;

1220
                lastSegmentVisualItemPair =  VisualItemPair(lastCoordinateItemBeforeRTL, visualItem);
1221
                if (!_flyView || addDirectionArrow) {
1222 1223 1224 1225
                    CoordinateVector* coordVector = _addWaypointLineSegment(old_table, lastSegmentVisualItemPair);
                    if (addDirectionArrow) {
                        _directionArrows.append(coordVector);
                    }
1226
                }
1227
            }
1228 1229 1230
            firstCoordinateNotFound = false;
            _waypointPath.append(QVariant::fromValue(visualItem->coordinate()));
            lastCoordinateItemBeforeRTL = visualItem;
1231 1232
        }
    }
1233 1234 1235 1236 1237

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

1238 1239
    if (linkEndToHome && lastCoordinateItemBeforeRTL != _settingsItem && homePositionValid) {
        lastSegmentVisualItemPair =  VisualItemPair(lastCoordinateItemBeforeRTL, _settingsItem);
1240
        if (_flyView) {
1241 1242
            _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
        }
1243
        _addWaypointLineSegment(old_table, lastSegmentVisualItemPair);
1244
    }
1245

1246 1247 1248 1249 1250 1251 1252 1253 1254
    // 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
1255
            coordVector = _linesTable[lastSegmentVisualItemPair];
1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268
        } 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) {
1269 1270
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1271
        objs.reserve(_linesTable.count());
1272
        for(CoordinateVector *vect: _linesTable.values()) {
1273 1274 1275 1276 1277 1278 1279
            objs.append(vect);
        }

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

1280 1281 1282
    _waypointLines.endReset();
    _directionArrows.endReset();

1283 1284 1285
    // Anything left in the old table is an obsolete line object that can go
    qDeleteAll(old_table);

DonLakeFlyer's avatar
DonLakeFlyer committed
1286
    _recalcMissionFlightStatus();
1287

1288
    if (_waypointPath.count() == 0) {
1289
        // MapPolyLine has a bug where if you change from a path which has elements to an empty path the line drawn
1290 1291 1292 1293 1294 1295 1296
        // 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();
1297 1298
}

1299 1300 1301 1302 1303 1304
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);
1305 1306 1307
        // 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.
1308
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331
            _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);
}

1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358
/// 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
1359
void MissionController::_recalcMissionFlightStatus()
1360
{
1361
    if (!_visualItems->count()) {
1362
        return;
1363
    }
1364

1365 1366
    bool                firstCoordinateItem =           true;
    VisualMissionItem*  lastCoordinateItemBeforeRTL =   qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1367

1368
    bool homePositionValid = _settingsItem->coordinate().isValid();
1369

DonLakeFlyer's avatar
DonLakeFlyer committed
1370
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1371

1372 1373 1374
    // 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.
1375

1376
    // No values for first item
1377 1378 1379
    lastCoordinateItemBeforeRTL->setAltDifference(0.0);
    lastCoordinateItemBeforeRTL->setAzimuth(0.0);
    lastCoordinateItemBeforeRTL->setDistance(0.0);
1380

1381 1382
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1383 1384
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1385

1386
    _resetMissionFlightStatus();
1387

DonLakeFlyer's avatar
DonLakeFlyer committed
1388
    bool vtolInHover = true;
1389
    bool linkStartToHome = false;
1390
    bool foundRTL = false;
1391

DonLakeFlyer's avatar
DonLakeFlyer committed
1392
    for (int i=0; i<_visualItems->count(); i++) {
1393 1394 1395 1396 1397 1398 1399
        VisualMissionItem*  item =          qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        SimpleMissionItem*  simpleItem =    qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem =   qobject_cast<ComplexMissionItem*>(item);

        if (simpleItem && simpleItem->mavCommand() == MAV_CMD_NAV_RETURN_TO_LAUNCH) {
            foundRTL = true;
        }
1400

1401 1402
        // Assume the worst
        item->setAzimuth(0.0);
1403
        item->setDistance(0.0);
1404

DonLakeFlyer's avatar
DonLakeFlyer committed
1405 1406 1407
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1408
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1409
                _missionFlightStatus.hoverSpeed = newSpeed;
1410
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1411 1412
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1413
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1414
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1415
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1416 1417
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1418
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1419 1420 1421
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436
        // ROI commands cancel out previous gimbal yaw/pitch
        if (simpleItem) {
            switch (simpleItem->command()) {
            case MAV_CMD_NAV_ROI:
            case MAV_CMD_DO_SET_ROI_LOCATION:
            case MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET:
                _missionFlightStatus.gimbalYaw = std::numeric_limits<double>::quiet_NaN();
                _missionFlightStatus.gimbalPitch = std::numeric_limits<double>::quiet_NaN();
                break;
            default:
                break;
            }
        }

        // Look for specific gimbal changes
1437 1438 1439 1440 1441 1442 1443
        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
1444 1445 1446 1447 1448
        }

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

1451 1452 1453 1454 1455
        if (foundRTL) {
            // No more vehicle distances after RTL
            continue;
        }

1456
        // Link back to home if first item is takeoff and we have home position
1457 1458
        if (firstCoordinateItem && simpleItem && (simpleItem->mavCommand() == MAV_CMD_NAV_TAKEOFF || simpleItem->mavCommand() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
            if (homePositionValid) {
1459
                linkStartToHome = true;
1460 1461 1462 1463 1464 1465 1466
                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);
                }
1467 1468 1469 1470
            }
        }

        // Update VTOL state
1471
        if (simpleItem && _controllerVehicle->vtol()) {
1472
            switch (simpleItem->command()) {
1473
            case MAV_CMD_NAV_TAKEOFF:
1474 1475
                vtolInHover = false;
                break;
1476
            case MAV_CMD_NAV_VTOL_TAKEOFF:
DonLakeFlyer's avatar
DonLakeFlyer committed
1477 1478
                vtolInHover = true;
                break;
1479
            case MAV_CMD_NAV_LAND:
1480 1481
                vtolInHover = false;
                break;
1482
            case MAV_CMD_NAV_VTOL_LAND:
DonLakeFlyer's avatar
DonLakeFlyer committed
1483 1484
                vtolInHover = true;
                break;
1485
            case MAV_CMD_DO_VTOL_TRANSITION:
1486 1487 1488 1489 1490 1491
            {
                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;
1492 1493
                }
            }
1494 1495 1496
                break;
            default:
                break;
1497
            }
Don Gagne's avatar
Don Gagne committed
1498 1499
        }

1500
        _addTimeDistance(vtolInHover, 0, 0, item->additionalTimeDelay(), 0, -1);
1501

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

1505
            double absoluteAltitude = item->coordinate().altitude();
1506
            if (item->coordinateHasRelativeAltitude()) {
1507 1508 1509 1510 1511
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1512 1513 1514 1515
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1516 1517 1518
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1519
                firstCoordinateItem = false;
1520 1521

                // Update vehicle yaw assuming direction to next waypoint
1522 1523 1524
                if (item != lastCoordinateItemBeforeRTL) {
                    _missionFlightStatus.vehicleYaw = lastCoordinateItemBeforeRTL->exitCoordinate().azimuthTo(item->coordinate());
                    lastCoordinateItemBeforeRTL->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1525 1526
                }

1527
                if (lastCoordinateItemBeforeRTL != _settingsItem || linkStartToHome) {
1528 1529
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1530

1531
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItemBeforeRTL, &azimuth, &distance, &altDifference);
1532 1533 1534
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1535

1536
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1537

DonLakeFlyer's avatar
DonLakeFlyer committed
1538 1539 1540
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1541
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1542
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1543

1544
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1545 1546
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1547
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1548

1549 1550
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1551
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1552
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1553 1554

                item->setMissionFlightStatus(_missionFlightStatus);
1555

1556
                lastCoordinateItemBeforeRTL = item;
1557
            }
1558 1559
        }
    }
1560
    lastCoordinateItemBeforeRTL->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1561

1562 1563
    // Add the information for the final segment back to home
    if (foundRTL && lastCoordinateItemBeforeRTL != _settingsItem && homePositionValid) {
1564
        double azimuth, distance, altDifference;
1565
        _calcPrevWaypointValues(homePositionAltitude, lastCoordinateItemBeforeRTL, _settingsItem, &azimuth, &distance, &altDifference);
1566 1567 1568 1569 1570

        // Calculate time/distance
        double hoverTime = distance / _missionFlightStatus.hoverSpeed;
        double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
        double landTime = qAbs(altDifference) / _appSettings->offlineEditingDescentSpeed()->rawValue().toDouble();
1571
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1572 1573
    }

1574 1575 1576
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1577

DonLakeFlyer's avatar
DonLakeFlyer committed
1578 1579 1580 1581 1582 1583 1584
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1585 1586
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1587

1588 1589
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1590 1591
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1592 1593 1594

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1595
            if (item->coordinateHasRelativeAltitude()) {
1596 1597 1598 1599
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1600
                item->setTerrainPercent(qQNaN());
1601
                item->setTerrainCollision(false);
1602 1603
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1604 1605 1606 1607 1608 1609 1610
                double terrainAltitude = item->terrainAltitude();
                if (qIsNaN(terrainAltitude)) {
                    item->setTerrainPercent(qQNaN());
                    item->setTerrainCollision(false);
                } else {
                    item->setTerrainPercent((terrainAltitude - minAltSeen) / altRange);
                    item->setTerrainCollision(absoluteAltitude < terrainAltitude);
1611
                }
1612
            }
1613 1614
        }
    }
1615 1616

    _updateTimer.start(UPDATE_TIMEOUT);
1617 1618
}

1619 1620 1621
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1622 1623 1624 1625 1626
    if (_inRecalcSequence) {
        // Don't let this call recurse due to signalling
        return;
    }

1627 1628
    // Setup ascending sequence numbers for all visual items

1629
    _inRecalcSequence = true;
1630 1631 1632
    int sequenceNumber = 0;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1633 1634
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1635
    }
1636
    _inRecalcSequence = false;
1637 1638
}

1639 1640 1641
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1642
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1643 1644 1645

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

1646 1647
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1648 1649 1650 1651 1652

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1653
        } else if (item->isSimpleItem()) {
1654 1655 1656 1657 1658
            currentParentItem->childItems()->append(item);
        }
    }
}

1659
void MissionController::_setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate)
1660
{
1661
    bool foundFirstCoordinate = false;
1662 1663
    QGeoCoordinate firstCoordinate;

1664 1665 1666 1667
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1668
    // Set the planned home position to be a delta from first coordinate
1669 1670 1671
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

1672 1673
        if (item->specifiesCoordinate() && item->coordinate().isValid()) {
            foundFirstCoordinate = true;
1674 1675
            firstCoordinate = item->coordinate();
            break;
1676 1677 1678
        }
    }

1679
    // No item specifying a coordinate was found, in this case it we have a clickCoordinate use that
1680
    if (!foundFirstCoordinate) {
1681 1682
        firstCoordinate = clickCoordinate;
    }
1683

1684 1685 1686
    if (firstCoordinate.isValid()) {
        QGeoCoordinate plannedHomeCoord = firstCoordinate.atDistanceAndAzimuth(30, 0);
        plannedHomeCoord.setAltitude(0);
1687
        _settingsItem->setInitialHomePositionFromUser(plannedHomeCoord);
1688 1689 1690
    }
}

1691
void MissionController::_recalcAllWithCoordinate(const QGeoCoordinate& coordinate)
1692
{
1693
    if (!_flyView) {
1694
        _setPlannedHomePositionFromFirstCoordinate(coordinate);
1695
    }
1696
    _recalcSequence();
1697 1698
    _recalcChildItems();
    _recalcWaypointLines();
1699
    _updateTimer.start(UPDATE_TIMEOUT);
1700 1701
}

1702 1703 1704
void MissionController::_recalcAll(void)
{
    QGeoCoordinate emptyCoord;
1705
    _recalcAllWithCoordinate(emptyCoord);
1706 1707
}

1708
/// Initializes a new set of mission items
1709
void MissionController::_initAllVisualItems(void)
1710
{
1711 1712
    // Setup home position at index 0

1713
    if (!_settingsItem) {
1714 1715 1716 1717 1718
        _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
        if (!_settingsItem) {
            qWarning() << "First item not MissionSettingsItem";
            return;
        }
1719
    }
1720

1721 1722
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1723

1724 1725 1726 1727
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1728

1729
    _recalcAll();
1730

1731
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1732 1733 1734
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1735
    emit containsItemsChanged(containsItems());
1736
    emit plannedHomePositionChanged(plannedHomePosition());
1737

1738 1739 1740 1741
    if (!_flyView) {
        setCurrentPlanViewIndex(0, true);
    }

1742
    setDirty(false);
1743 1744
}

1745
void MissionController::_deinitAllVisualItems(void)
1746
{
1747 1748 1749
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1750 1751
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1752 1753
    }

1754
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1755
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1756 1757
}

1758
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1759
{
1760
    setDirty(false);
1761

1762
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1763 1764
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1765 1766
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1767
    connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged,                this, &MissionController::_recalcMissionFlightStatus);
1768
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1769
    connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged,                 this, &MissionController::_recalcMissionFlightStatus);
1770
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1771

1772 1773 1774 1775 1776 1777 1778 1779
    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";
        }
1780 1781
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1782
        if (complexItem) {
1783
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
1784
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
1785 1786 1787
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1788
    }
1789 1790
}

1791
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1792
{
1793
    // Disconnect all signals
1794
    disconnect(visualItem, nullptr, nullptr, nullptr);
1795 1796
}

1797
void MissionController::_itemCommandChanged(void)
1798
{
1799 1800
    _recalcChildItems();
    _recalcWaypointLines();
1801 1802
}

1803
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1804
{
1805 1806 1807
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
1808 1809
        _managerVehicle = nullptr;
        _missionManager = nullptr;
1810
    }
1811

1812 1813
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1814
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1815 1816
        return;
    }
1817

1818 1819
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1820 1821
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1822 1823 1824 1825 1826
    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);
1827
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1828 1829 1830
    connect(_managerVehicle, &Vehicle::defaultCruiseSpeedChanged,       this, &MissionController::_recalcMissionFlightStatus);
    connect(_managerVehicle, &Vehicle::defaultHoverSpeedChanged,        this, &MissionController::_recalcMissionFlightStatus);
    connect(_managerVehicle, &Vehicle::vehicleTypeChanged,              this, &MissionController::complexMissionItemNamesChanged);
1831

1832
    emit complexMissionItemNamesChanged();
1833
    emit resumeMissionIndexChanged();
1834 1835 1836
}

void MissionController::_inProgressChanged(bool inProgress)
1837
{
1838
    emit syncInProgressChanged(inProgress);
1839
}
1840

1841
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1842
{
1843
    bool        found = false;
1844
    double      foundAltitude = 0;
1845
    int         foundAltitudeMode = QGroundControlQmlGlobal::AltitudeModeNone;
1846

1847 1848 1849 1850 1851 1852
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1855 1856 1857
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1858 1859 1860
                if (simpleItem->specifiesAltitude()) {
                    foundAltitude = simpleItem->altitude()->rawValue().toDouble();
                    foundAltitudeMode = simpleItem->altitudeMode();
1861
                    found = true;
1862
                    break;
1863 1864
                }
            }
1865 1866 1867
        }
    }

1868
    if (found) {
1869
        *prevAltitude = foundAltitude;
1870
        *prevAltitudeMode = foundAltitudeMode;
1871 1872 1873
    }

    return found;
1874
}
1875 1876 1877 1878 1879 1880 1881 1882 1883 1884 1885 1886 1887

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

1888
/// Add the Mission Settings complex item to the front of the items
1889
MissionSettingsItem* MissionController::_addMissionSettings(QmlObjectListModel* visualItems)
1890
{
1891 1892
    qCDebug(MissionControllerLog) << "_addMissionSettings";

1893
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_managerVehicle, _flyView, visualItems);
1894
    visualItems->insert(0, settingsItem);
1895

1896 1897 1898 1899 1900
    if (visualItems == _visualItems) {
        _settingsItem = settingsItem;
    }

    return settingsItem;
1901
}
Don Gagne's avatar
Don Gagne committed
1902

1903 1904 1905
void MissionController::_centerHomePositionOnMissionItems(QmlObjectListModel *visualItems)
{
    qCDebug(MissionControllerLog) << "_centerHomePositionOnMissionItems";
1906

1907 1908 1909 1910 1911 1912 1913 1914 1915 1916 1917 1918 1919 1920 1921 1922 1923 1924 1925 1926 1927 1928 1929
    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;
1930 1931
                }
            }
1932
        }
1933

1934 1935
        if (firstCoordSet) {
            _settingsItem->setInitialHomePositionFromUser(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
1936 1937 1938
        }
    }
}
1939

1940
int MissionController::resumeMissionIndex(void) const
1941
{
1942

1943
    int resumeIndex = 0;
1944

1945
    if (_flyView) {
1946
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1947
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1948 1949
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1950 1951
        } else {
            resumeIndex = 0;
1952 1953 1954 1955 1956
        }
    }

    return resumeIndex;
}
1957

1958 1959
int MissionController::currentMissionIndex(void) const
{
1960
    if (!_flyView) {
1961 1962 1963 1964 1965 1966 1967 1968 1969 1970
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

1971
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1972
{
1973
    if (_flyView) {
1974
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1975 1976 1977
            sequenceNumber++;
        }

1978 1979
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1980 1981
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1982
        emit currentMissionIndexChanged(currentMissionIndex());
1983 1984
    }
}
1985

1986
bool MissionController::syncInProgress(void) const
1987
{
1988
    return _missionManager->inProgress();
1989 1990 1991 1992 1993 1994 1995 1996 1997 1998 1999 2000
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
2001
    }
2002
}
2003

2004 2005
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
2006 2007
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, vehicle);
2008

2009 2010 2011 2012 2013 2014
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

2015
        if (!_flyView) {
2016 2017 2018 2019 2020 2021
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
2022 2023 2024
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
2025
        if (simpleItem) {
2026 2027 2028 2029 2030
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
2031 2032 2033
        }
    }
}
2034 2035 2036 2037 2038 2039 2040 2041 2042 2043 2044 2045 2046

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
2047 2048 2049 2050 2051 2052 2053 2054
    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();
    }
2055
}
2056 2057 2058 2059 2060

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

DonLakeFlyer's avatar
DonLakeFlyer committed
2061
    complexItems.append(patternSurveyName);
2062
    complexItems.append(patternCorridorScanName);
2063
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
2064
        complexItems.append(patternStructureScanName);
2065
    }
2066

2067
    return qgcApp()->toolbox()->corePlugin()->complexMissionItemNames(_controllerVehicle, complexItems);
2068
}
2069

2070 2071
void MissionController::resumeMission(int resumeIndex)
{
2072
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
2073 2074
        resumeIndex--;
    }
2075
    _missionManager->generateResumeMission(resumeIndex);
2076
}
2077 2078 2079 2080 2081 2082 2083 2084 2085

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
2086 2087 2088 2089 2090 2091 2092 2093 2094 2095

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

2097 2098 2099 2100 2101 2102 2103
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
2104 2105 2106 2107 2108 2109

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
2110 2111 2112

bool MissionController::showPlanFromManagerVehicle (void)
{
2113
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
DonLakeFlyer's avatar
DonLakeFlyer committed
2114 2115
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
2116
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
2117 2118 2119 2120 2121 2122 2123 2124 2125 2126 2127 2128 2129 2130 2131 2132 2133 2134 2135
    } 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;
        }
    }
}

2136
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2137
{
2138
    // Fly view always reloads on send complete
2139
    if (!error && _flyView) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2140 2141 2142 2143
        showPlanFromManagerVehicle();
    }
}

2144
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2145
{
2146 2147 2148 2149
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2150
}
2151 2152 2153 2154 2155 2156 2157 2158 2159 2160 2161 2162 2163

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

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

void MissionController::setCurrentPlanViewIndex(int sequenceNumber, bool force)
{
2164
    if (_visualItems && (force || sequenceNumber != _currentPlanViewIndex)) {
2165 2166 2167
        bool    foundLand =     false;
        int     takeoffIndex =  -1;
        int     landIndex =     -1;
2168

2169 2170 2171 2172 2173 2174
        _splitSegment =                 nullptr;
        _currentPlanViewItem  =         nullptr;
        _currentPlanViewIndex =         -1;
        _isInsertTakeoffValid =         true;
        _isInsertLandValid =            true;
        _flyThroughCommandsAllowed =    true;
2175

2176 2177
        for (int i = 0; i < _visualItems->count(); i++) {
            VisualMissionItem* pVI = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
2178 2179 2180 2181 2182 2183 2184 2185 2186

            if (sequenceNumber != 0 && pVI->sequenceNumber() <= sequenceNumber) {
                if (pVI->specifiesCoordinate() && !pVI->isStandaloneCoordinate()) {
                    // Coordinate based flight commands prior to where the takeoff would be inserted
                    _isInsertTakeoffValid = false;
                }
            }

            if (qobject_cast<TakeoffMissionItem*>(pVI)) {
2187
                takeoffIndex = i;
2188 2189 2190
                _isInsertTakeoffValid = false;
            }

2191 2192 2193 2194 2195 2196 2197 2198 2199
            if (!foundLand) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(pVI);
                if (simpleItem) {
                    switch (simpleItem->mavCommand()) {
                    case MAV_CMD_NAV_LAND:
                    case MAV_CMD_NAV_VTOL_LAND:
                    case MAV_CMD_DO_LAND_START:
                    case MAV_CMD_NAV_RETURN_TO_LAUNCH:
                        foundLand = true;
2200
                        landIndex = i;
2201 2202 2203 2204 2205 2206 2207 2208
                        break;
                    default:
                        break;
                    }
                } else {
                    FixedWingLandingComplexItem* fwLanding = qobject_cast<FixedWingLandingComplexItem*>(pVI);
                    if (fwLanding) {
                        foundLand = true;
2209
                        landIndex = i;
2210 2211 2212 2213
                    }
                }
            }

2214
            if (pVI->sequenceNumber() == sequenceNumber) {
2215 2216 2217
                pVI->setIsCurrentItem(true);
                _currentPlanViewItem  = pVI;
                _currentPlanViewIndex = sequenceNumber;
2218 2219 2220 2221 2222 2223 2224 2225 2226 2227 2228 2229 2230

                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];
                            }
                        }
                    }
                }
2231 2232 2233 2234
            } else {
                pVI->setIsCurrentItem(false);
            }
        }
2235

2236 2237 2238 2239 2240 2241 2242 2243 2244 2245 2246 2247
        if (takeoffIndex != -1) {
            // Takeoff item was found which means mission starts from ground
            if (sequenceNumber < takeoffIndex) {
                // Land is only valid after the takeoff item.
                _isInsertLandValid = false;
                // Fly through commands are not allowed prior to the takeoff command
                _flyThroughCommandsAllowed = false;
            }
        }

        if (foundLand) {
            // Can't have more than one land sequence
2248
            _isInsertLandValid = false;
2249 2250 2251 2252
            if (sequenceNumber >= landIndex) {
                // Can't have fly through commands after a land item
                _flyThroughCommandsAllowed = false;
            }
2253 2254
        }

2255 2256
        emit currentPlanViewIndexChanged();
        emit currentPlanViewItemChanged();
2257
        emit splitSegmentChanged();
2258
        emit isInsertTakeoffValidChanged();
2259
        emit isInsertLandValidChanged();
2260
        emit flyThroughCommandsAllowedChanged();
2261 2262
    }
}
2263 2264 2265

void MissionController::_updateTimeout()
{
Gus Grubba's avatar
Gus Grubba committed
2266
    QGeoCoordinate firstCoordinate;
2267
    QGeoCoordinate takeoffCoordinate;
2268
    QGCGeoBoundingCube boundingCube;
2269 2270 2271 2272
    double north = 0.0;
    double south = 180.0;
    double east  = 0.0;
    double west  = 360.0;
2273 2274
    double minAlt = QGCGeoBoundingCube::MaxAlt;
    double maxAlt = QGCGeoBoundingCube::MinAlt;
2275 2276 2277 2278 2279 2280
    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()) {
2281
                case MAV_CMD_NAV_TAKEOFF:
2282 2283
                case MAV_CMD_NAV_WAYPOINT:
                case MAV_CMD_NAV_LAND:
2284 2285 2286 2287 2288 2289 2290 2291 2292 2293 2294 2295 2296 2297 2298
                    if(pSimpleItem->coordinate().isValid()) {
                        if((MAV_CMD)pSimpleItem->command() == MAV_CMD_NAV_TAKEOFF) {
                            takeoffCoordinate = pSimpleItem->coordinate();
                        } else if(!firstCoordinate.isValid()) {
                            firstCoordinate = pSimpleItem->coordinate();
                        }
                        double lat = pSimpleItem->coordinate().latitude()  + 90.0;
                        double lon = pSimpleItem->coordinate().longitude() + 180.0;
                        double alt = pSimpleItem->coordinate().altitude();
                        north  = fmax(north, lat);
                        south  = fmin(south, lat);
                        east   = fmax(east,  lon);
                        west   = fmin(west,  lon);
                        minAlt = fmin(minAlt, alt);
                        maxAlt = fmax(maxAlt, alt);
Gus Grubba's avatar
Gus Grubba committed
2299
                    }
2300
                    break;
2301 2302 2303 2304 2305 2306 2307
                default:
                    break;
                }
            }
        } else {
            ComplexMissionItem* pComplexItem = qobject_cast<ComplexMissionItem*>(item);
            if(pComplexItem) {
2308 2309
                QGCGeoBoundingCube bc = pComplexItem->boundingCube();
                if(bc.isValid()) {
Gus Grubba's avatar
Gus Grubba committed
2310 2311 2312
                    if(!firstCoordinate.isValid() && pComplexItem->coordinate().isValid()) {
                        firstCoordinate = pComplexItem->coordinate();
                    }
2313 2314 2315 2316 2317 2318
                    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());
2319 2320 2321 2322
                }
            }
        }
    }
Gus Grubba's avatar
Gus Grubba committed
2323 2324 2325 2326 2327 2328 2329 2330 2331
    //-- Figure out where this thing is taking off from
    if(!takeoffCoordinate.isValid()) {
        if(firstCoordinate.isValid()) {
            takeoffCoordinate = firstCoordinate;
        } else {
            takeoffCoordinate = plannedHomePosition();
        }
    }
    //-- Build bounding "cube"
2332
    boundingCube = QGCGeoBoundingCube(
2333 2334
                QGeoCoordinate(north - 90.0, west - 180.0, minAlt),
                QGeoCoordinate(south - 90.0, east - 180.0, maxAlt));
2335 2336
    if(_travelBoundingCube != boundingCube || _takeoffCoordinate != takeoffCoordinate) {
        _takeoffCoordinate  = takeoffCoordinate;
2337
        _travelBoundingCube = boundingCube;
2338
        emit missionBoundingCubeChanged();
2339
        qCDebug(MissionControllerLog) << "Bounding cube:" << _travelBoundingCube.pointNW << _travelBoundingCube.pointSE;
2340 2341 2342 2343 2344 2345 2346
    }
}

void MissionController::_complexBoundingBoxChanged()
{
    _updateTimer.start(UPDATE_TIMEOUT);
}
2347 2348 2349 2350 2351

bool MissionController::isEmpty(void) const
{
    return _visualItems->count() <= 1;
}
Don Gagne's avatar
Don Gagne committed
2352 2353 2354 2355 2356 2357 2358 2359 2360 2361 2362 2363 2364

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