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

10
#include "MissionCommandUIInfo.h"
11 12 13
#include "MissionController.h"
#include "MultiVehicleManager.h"
#include "MissionManager.h"
14
#include "FlightPathSegment.h"
15
#include "FirmwarePlugin.h"
16
#include "QGCApplication.h"
17
#include "SimpleMissionItem.h"
18
#include "SurveyComplexItem.h"
19
#include "FixedWingLandingComplexItem.h"
20
#include "VTOLLandingComplexItem.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 "KMLPlanDomDocument.h"
32
#include "QGCCorePlugin.h"
33
#include "TakeoffMissionItem.h"
34
#include "PlanViewSettings.h"
35

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

38 39
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

56
MissionController::MissionController(PlanMasterController* masterController, QObject *parent)
57 58 59 60 61 62 63
    : PlanElementController (masterController, parent)
    , _controllerVehicle    (masterController->controllerVehicle())
    , _managerVehicle       (masterController->managerVehicle())
    , _missionManager       (masterController->managerVehicle()->missionManager())
    , _visualItems          (new QmlObjectListModel(this))
    , _planViewSettings     (qgcApp()->toolbox()->settingsManager()->planViewSettings())
    , _appSettings          (qgcApp()->toolbox()->settingsManager()->appSettings())
64
{
65
    _resetMissionFlightStatus();
66

67 68
    _updateTimer.setSingleShot(true);
    connect(&_updateTimer, &QTimer::timeout, this, &MissionController::_updateTimeout);
69 70

    connect(_planViewSettings->takeoffItemNotRequired(), &Fact::rawValueChanged, this, &MissionController::_takeoffItemNotRequiredChanged);
71 72 73 74 75 76 77 78 79

    connect(this, &MissionController::missionDistanceChanged,  this, &MissionController::recalcTerrainProfile);

    // The follow is used to compress multiple recalc calls in a row to into a single call.
    connect(this, &MissionController::_recalcMissionFlightStatusSignal, this, &MissionController::_recalcMissionFlightStatus,   Qt::QueuedConnection);
    connect(this, &MissionController::_recalcFlightPathSegmentsSignal,  this, &MissionController::_recalcFlightPathSegments,    Qt::QueuedConnection);
    qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(&MissionController::_recalcMissionFlightStatusSignal));
    qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(&MissionController::_recalcFlightPathSegmentsSignal));
    qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(&MissionController::recalcTerrainProfile));
80 81 82 83
}

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

85 86
}

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

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

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

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

130 131
}

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

136 137 138
    _managerVehicleChanged(_managerVehicle);
    connect(_masterController, &PlanMasterController::managerVehicleChanged, this, &MissionController::_managerVehicleChanged);

139
    PlanElementController::start(flyView);
140 141 142 143 144
    _init();
}

void MissionController::_init(void)
{
145
    // We start with an empty mission
146
    _addMissionSettings(_visualItems);
147
    _initAllVisualItems();
148 149
}

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

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

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

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

177 178 179
        _missionItemCount = newMissionItems.count();
        emit missionItemCountChanged(_missionItemCount);

180
        MissionSettingsItem* settingsItem = _addMissionSettings(newControllerMissionItems);
181 182

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

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

        _visualItems = newControllerMissionItems;
205
        _settingsItem = settingsItem;
206

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

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

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

228
void MissionController::sendToVehicle(void)
229
{
DonLakeFlyer's avatar
DonLakeFlyer committed
230 231 232 233 234
    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
235
        qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
DonLakeFlyer's avatar
DonLakeFlyer committed
236 237 238 239 240 241 242 243 244
        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
245 246
}

247 248 249 250 251
/// 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
252 253 254 255
    if (visualMissionItems->count() == 0) {
        return false;
    }

256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271
    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
272
    MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
273 274 275 276 277 278 279
    if (settingsItem) {
        endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
    }

    return endActionSet;
}

280
void MissionController::addMissionToKML(KMLPlanDomDocument& planKML)
281
{
282 283
    QObject*            deleteParent = new QObject();
    QList<MissionItem*> rgMissionItems;
284

285
    _convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
286
    planKML.addMission(_controllerVehicle, _visualItems, rgMissionItems);
287
    deleteParent->deleteLater();
288 289
}

Don Gagne's avatar
Don Gagne committed
290 291 292
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
293
        QList<MissionItem*> rgMissionItems;
294

295
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
296

297
        // PlanManager takes control of MissionItems so no need to delete
298
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
299 300
    }
}
301

302 303 304 305 306 307
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
308 309
        VisualMissionItem* lastItem = _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1);
        return lastItem->lastSequenceNumber() + 1;
310 311 312
    }
}

313
VisualMissionItem* MissionController::_insertSimpleMissionItemWorker(QGeoCoordinate coordinate, MAV_CMD command, int visualItemIndex, bool makeCurrentItem)
314
{
315
    int sequenceNumber = _nextSequenceNumber();
316
    SimpleMissionItem * newItem = new SimpleMissionItem(_masterController, _flyView, false /* forLoad */, this);
317
    newItem->setSequenceNumber(sequenceNumber);
318
    newItem->setCoordinate(coordinate);
319
    newItem->setCommand(command);
320
    _initVisualItem(newItem);
321 322

    if (newItem->specifiesAltitude()) {
323 324 325 326 327 328 329 330 331
        const MissionCommandUIInfo* uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, command);
        if (!uiInfo->isLandCommand()) {
            double  prevAltitude;
            int     prevAltitudeMode;

            if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltitudeMode)) {
                newItem->altitude()->setRawValue(prevAltitude);
                newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
            }
332
        }
333
    }
334 335 336 337 338 339 340 341
    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
342
    _recalcAllWithCoordinate(coordinate);
343 344

    if (makeCurrentItem) {
345
        setCurrentPlanViewSeqNum(newItem->sequenceNumber(), true);
346 347 348 349 350
    }

    return newItem;
}

351 352 353 354 355 356

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

357
VisualMissionItem* MissionController::insertTakeoffItem(QGeoCoordinate /*coordinate*/, int visualItemIndex, bool makeCurrentItem)
358 359
{
    int sequenceNumber = _nextSequenceNumber();
360
    TakeoffMissionItem * newItem = new TakeoffMissionItem(_controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF, _masterController, _flyView, _settingsItem, this);
361 362 363
    newItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(newItem);

364 365 366
    if (newItem->specifiesAltitude()) {
        double  prevAltitude;
        int     prevAltitudeMode;
367

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

380
    _recalcAll();
381

382
    if (makeCurrentItem) {
383
        setCurrentPlanViewSeqNum(newItem->sequenceNumber(), true);
384 385 386
    }

    return newItem;
387 388
}

389
VisualMissionItem* MissionController::insertLandItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem)
390
{
391
    if (_managerVehicle->fixedWing()) {
392
        FixedWingLandingComplexItem* fwLanding = qobject_cast<FixedWingLandingComplexItem*>(insertComplexMissionItem(FixedWingLandingComplexItem::name, coordinate, visualItemIndex, makeCurrentItem));
393
        return fwLanding;
394
    } else if (_managerVehicle->vtol()) {
395
        VTOLLandingComplexItem* vtolLanding = qobject_cast<VTOLLandingComplexItem*>(insertComplexMissionItem(VTOLLandingComplexItem::name, coordinate, visualItemIndex, makeCurrentItem));
396
        return vtolLanding;
397
    } else {
398
        return _insertSimpleMissionItemWorker(coordinate, _managerVehicle->vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_RETURN_TO_LAUNCH, visualItemIndex, makeCurrentItem);
399
    }
400
}
401

402 403
VisualMissionItem* MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem)
{
404 405 406 407 408 409
    SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_insertSimpleMissionItemWorker(coordinate, MAV_CMD_DO_SET_ROI_LOCATION, visualItemIndex, makeCurrentItem));

    if (!_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_DO_SET_ROI_LOCATION)) {
        simpleItem->setCommand(MAV_CMD_DO_SET_ROI)  ;
        simpleItem->missionItem().setParam1(MAV_ROI_LOCATION);
    }
410
    _recalcROISpecialVisuals();
411 412 413 414 415 416 417 418 419 420 421
    return simpleItem;
}

VisualMissionItem* MissionController::insertCancelROIMissionItem(int visualItemIndex, bool makeCurrentItem)
{
    SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_insertSimpleMissionItemWorker(QGeoCoordinate(), MAV_CMD_DO_SET_ROI_NONE, visualItemIndex, makeCurrentItem));

    if (!_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_DO_SET_ROI_NONE)) {
        simpleItem->setCommand(MAV_CMD_DO_SET_ROI)  ;
        simpleItem->missionItem().setParam1(MAV_ROI_NONE);
    }
422
    _recalcROISpecialVisuals();
423
    return simpleItem;
424 425
}

426
VisualMissionItem* MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int visualItemIndex, bool makeCurrentItem)
427
{
428
    ComplexMissionItem* newItem = nullptr;
429

430
    if (itemName == SurveyComplexItem::name) {
431
        newItem = new SurveyComplexItem(_masterController, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
432
        newItem->setCoordinate(mapCenterCoordinate);
433
    } else if (itemName == FixedWingLandingComplexItem::name) {
434
        newItem = new FixedWingLandingComplexItem(_masterController, _flyView, _visualItems /* parent */);
435
    } else if (itemName == VTOLLandingComplexItem::name) {
436
        newItem = new VTOLLandingComplexItem(_masterController, _flyView, _visualItems /* parent */);
437
    } else if (itemName == StructureScanComplexItem::name) {
438
        newItem = new StructureScanComplexItem(_masterController, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
439
    } else if (itemName == CorridorScanComplexItem::name) {
440
        newItem = new CorridorScanComplexItem(_masterController, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
441 442
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
443
        return nullptr;
444 445
    }

446
    _insertComplexMissionItemWorker(mapCenterCoordinate, newItem, visualItemIndex, makeCurrentItem);
447 448

    return newItem;
449 450
}

451
VisualMissionItem* MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int visualItemIndex, bool makeCurrentItem)
452
{
453
    ComplexMissionItem* newItem = nullptr;
454

455
    if (itemName == SurveyComplexItem::name) {
456
        newItem = new SurveyComplexItem(_masterController, _flyView, file, _visualItems);
457
    } else if (itemName == StructureScanComplexItem::name) {
458
        newItem = new StructureScanComplexItem(_masterController, _flyView, file, _visualItems);
459
    } else if (itemName == CorridorScanComplexItem::name) {
460
        newItem = new CorridorScanComplexItem(_masterController, _flyView, file, _visualItems);
461 462
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
463
        return nullptr;
464 465
    }

466
    _insertComplexMissionItemWorker(QGeoCoordinate(), newItem, visualItemIndex, makeCurrentItem);
467 468

    return newItem;
469 470
}

471
void MissionController::_insertComplexMissionItemWorker(const QGeoCoordinate& mapCenterCoordinate, ComplexMissionItem* complexItem, int visualItemIndex, bool makeCurrentItem)
472 473
{
    int sequenceNumber = _nextSequenceNumber();
474
    bool surveyStyleItem = qobject_cast<SurveyComplexItem*>(complexItem) ||
475 476
            qobject_cast<CorridorScanComplexItem*>(complexItem) ||
            qobject_cast<StructureScanComplexItem*>(complexItem);
477

478
    if (surveyStyleItem) {
479
        bool rollSupported  = false;
480
        bool pitchSupported = false;
481
        bool yawSupported   = false;
482 483 484

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

485 486
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
        CameraSection* cameraSection = settingsItem->cameraSection();
487

488
        // Set camera to photo mode (leave alone if user already specified)
489
        if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
490
            cameraSection->setSpecifyCameraMode(true);
491
            cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
492
        }
493

494
        // Point gimbal straight down
495
        if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
496 497 498
            // If the user already specified a gimbal angle leave it alone
            if (!cameraSection->specifyGimbal()) {
                cameraSection->setSpecifyGimbal(true);
499
                cameraSection->gimbalPitch()->setRawValue(-90.0);
500 501
            }
        }
502
    }
503

504
    complexItem->setSequenceNumber(sequenceNumber);
505
    complexItem->setWizardMode(true);
506
    _initVisualItem(complexItem);
507

Don Gagne's avatar
Don Gagne committed
508
    if (visualItemIndex == -1) {
509 510
        _visualItems->append(complexItem);
    } else {
Don Gagne's avatar
Don Gagne committed
511
        _visualItems->insert(visualItemIndex, complexItem);
512
    }
513

514
    //-- Keep track of bounding box changes in complex items
515 516
    if(!complexItem->isSimpleItem()) {
        connect(complexItem, &ComplexMissionItem::boundingCubeChanged, this, &MissionController::_complexBoundingBoxChanged);
517
    }
518
    _recalcAllWithCoordinate(mapCenterCoordinate);
519

520
    if (makeCurrentItem) {
521
        setCurrentPlanViewSeqNum(complexItem->sequenceNumber(), true);
522
    }
523 524
}

525
void MissionController::removeVisualItem(int viIndex)
526
{
527
    if (viIndex <= 0 || viIndex >= _visualItems->count()) {
528
        qWarning() << "MissionController::removeVisualItem called with bad index - count:index" << _visualItems->count() << viIndex;
529 530 531
        return;
    }

532 533
    bool removeSurveyStyle = _visualItems->value<SurveyComplexItem*>(viIndex) || _visualItems->value<CorridorScanComplexItem*>(viIndex);
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(viIndex));
534

535
    _deinitVisualItem(item);
536
    item->deleteLater();
537

538 539
    if (removeSurveyStyle) {
        // Determine if the mission still has another survey style item in it
540 541
        bool foundSurvey = false;
        for (int i=1; i<_visualItems->count(); i++) {
542
            if (_visualItems->value<SurveyComplexItem*>(i) || _visualItems->value<CorridorScanComplexItem*>(i)) {
543 544 545 546 547
                foundSurvey = true;
                break;
            }
        }

548
        // If there is no longer a survey item in the mission remove added commands
549 550 551 552
        if (!foundSurvey) {
            bool rollSupported = false;
            bool pitchSupported = false;
            bool yawSupported = false;
553
            CameraSection* cameraSection = _settingsItem->cameraSection();
554
            if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
555
                if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
556 557 558
                    cameraSection->setSpecifyGimbal(false);
                }
            }
559
            if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
560 561
                cameraSection->setSpecifyCameraMode(false);
            }
562 563 564
        }
    }

565
    _recalcAll();
566 567 568 569 570 571 572 573 574 575

    // Adjust current item
    int newVIIndex;
    if (viIndex >= _visualItems->count()) {
        newVIIndex = _visualItems->count() - 1;
    } else {
        newVIIndex = viIndex;
    }
    setCurrentPlanViewSeqNum(_visualItems->value<VisualMissionItem*>(newVIIndex)->sequenceNumber(), true);

576
    setDirty(true);
577 578
}

579
void MissionController::removeAll(void)
580
{
581 582
    if (_visualItems) {
        _deinitAllVisualItems();
DonLakeFlyer's avatar
DonLakeFlyer committed
583
        _visualItems->clearAndDeleteContents();
Don Gagne's avatar
Don Gagne committed
584
        _visualItems->deleteLater();
585
        _settingsItem = nullptr;
586
        _visualItems = new QmlObjectListModel(this);
587
        _addMissionSettings(_visualItems);
588
        _initAllVisualItems();
589
        setDirty(true);
590
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
591 592 593
    }
}

594
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
595 596 597 598 599 600 601 602 603
{
    // 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)) {
604 605 606
        return false;
    }

607
    // Read complex items
608
    QList<SurveyComplexItem*> surveyItems;
609 610 611 612
    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];
613

614 615 616 617 618
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

619
        SurveyComplexItem* item = new SurveyComplexItem(_masterController, _flyView, QString() /* kmlFile */, visualItems /* parent */);
Don Gagne's avatar
Don Gagne committed
620 621
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
622
            surveyItems.append(item);
623 624
        } else {
            return false;
625
        }
626
    }
627

628 629 630 631 632
    // 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
633
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
634

635
    MissionSettingsItem* settingsItem = _addMissionSettings(visualItems);
636
    if (json.contains(_jsonPlannedHomePositionKey)) {
637
        SimpleMissionItem* item = new SimpleMissionItem(_masterController, _flyView, true /* forLoad */, visualItems);
638
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
639
            settingsItem->setInitialHomePositionFromUser(item->coordinate());
640 641 642 643 644 645
            item->deleteLater();
        } else {
            return false;
        }
    }

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

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

667 668 669 670 671
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

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

    return true;
}

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

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

711
    // Mission Settings
712
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
713

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

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

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

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

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

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

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

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

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

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

    return true;
950 951
}

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

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

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

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

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

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

979
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004
        errorString = errorMessage.arg(errorStr);
        return false;
    }
    _initLoadedVisualItems(loadedVisualItems);

    return true;
}

bool MissionController::loadJsonFile(QFile& file, QString& errorString)
{
    QString         errorStr;
    QString         errorMessage = tr("Mission: %1");
    QJsonDocument   jsonDoc;
    QByteArray      bytes = file.readAll();

    if (!JsonHelper::isJsonFile(bytes, jsonDoc, errorStr)) {
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    QJsonObject json = jsonDoc.object();
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);
    if (!_loadItemsFromJson(json, loadedVisualItems, errorStr)) {
        errorString = errorMessage.arg(errorStr);
        return false;
1005
    }
1006

1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019
    _initLoadedVisualItems(loadedVisualItems);

    return true;
}

bool MissionController::loadTextFile(QFile& file, QString& errorString)
{
    QString     errorStr;
    QString     errorMessage = tr("Mission: %1");
    QByteArray  bytes = file.readAll();
    QTextStream stream(bytes);

    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);
1020
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
1021 1022 1023 1024 1025 1026
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

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

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

1039
    return VisualMissionItem::ReadyForSave;
1040 1041
}

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

1046
    // Mission settings
1047

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

1061
    // Save the visual items
1062

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

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

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

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

1085
    json[_jsonItemsKey] = rgJsonMissionItems;
1086 1087
}

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

    // Convert to fixed altitudes

1095 1096 1097
    *altDifference = currentItem->amslEntryAlt() - prevItem->amslExitAlt();
    *distance = prevCoord.distanceTo(currentCoord);
    *azimuth = prevCoord.azimuthTo(currentCoord);
1098 1099
}

1100
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
1101 1102 1103 1104 1105 1106 1107
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

1108
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
1109 1110
}

1111
FlightPathSegment* MissionController::_createFlightPathSegmentWorker(VisualItemPair& pair)
1112
{
1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123
    QGeoCoordinate      coord1 =            pair.first->isSimpleItem() ? pair.first->coordinate() : pair.first->exitCoordinate();
    QGeoCoordinate      coord2 =            pair.second->coordinate();
    double              coord1Alt =         pair.first->isSimpleItem() ? pair.first->amslEntryAlt() : pair.first->amslExitAlt();
    double              coord2Alt =         pair.second->amslEntryAlt();

    FlightPathSegment*  segment =           new FlightPathSegment(coord1, coord1Alt, coord2, coord2Alt, !_flyView /* queryTerrainData */,  this);

    auto                coord1Notifier =    pair.first->isSimpleItem() ? &VisualMissionItem::coordinateChanged : &VisualMissionItem::exitCoordinateChanged;
    auto                coord2Notifier =    &VisualMissionItem::coordinateChanged;
    auto                coord1AltNotifier = pair.first->isSimpleItem() ? &VisualMissionItem::amslEntryAltChanged : &VisualMissionItem::amslExitAltChanged;
    auto                coord2AltNotifier = &VisualMissionItem::amslEntryAltChanged;
1124

1125 1126 1127 1128
    connect(pair.first,  coord1Notifier,                                segment,    &FlightPathSegment::setCoordinate1);
    connect(pair.second, coord2Notifier,                                segment,    &FlightPathSegment::setCoordinate2);
    connect(pair.first,  coord1AltNotifier,                             segment,    &FlightPathSegment::setCoord1AMSLAlt);
    connect(pair.second, coord2AltNotifier,                             segment,    &FlightPathSegment::setCoord2AMSLAlt);
1129

1130
    connect(pair.second, &VisualMissionItem::coordinateChanged,         this,       &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
1131

1132 1133 1134 1135 1136
    connect(segment,    &FlightPathSegment::totalDistanceChanged,       this,       &MissionController::recalcTerrainProfile,             Qt::QueuedConnection);
    connect(segment,    &FlightPathSegment::coord1AMSLAltChanged,       this,       &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
    connect(segment,    &FlightPathSegment::coord2AMSLAltChanged,       this,       &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
    connect(segment,    &FlightPathSegment::amslTerrainHeightsChanged,  this,       &MissionController::recalcTerrainProfile,             Qt::QueuedConnection);
    connect(segment,    &FlightPathSegment::terrainCollisionChanged,    this,       &MissionController::recalcTerrainProfile,             Qt::QueuedConnection);
1137

1138
    return segment;
1139 1140
}

1141
FlightPathSegment* MissionController::_addFlightPathSegment(FlightPathSegmentHashTable& prevItemPairHashTable, VisualItemPair& pair)
1142
{
1143
    FlightPathSegment* segment = nullptr;
1144

1145 1146
    if (prevItemPairHashTable.contains(pair)) {
        // Pair already exists and connected, just re-use
1147
        _flightPathSegmentHashTable[pair] = segment = prevItemPairHashTable.take(pair);
1148
    } else {
1149 1150
        segment = _createFlightPathSegmentWorker(pair);
        _flightPathSegmentHashTable[pair] = segment;
1151
    }
1152

1153 1154 1155
    _simpleFlightPathSegments.append(segment);

    return segment;
1156 1157
}

1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182
void MissionController::_recalcROISpecialVisuals(void)
{
    return;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));
    bool                roiActive =             false;

    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem*  visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        SimpleMissionItem*  simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
        VisualItemPair      viPair;

        if (simpleItem) {
            if (roiActive) {
                if (_isROICancelItem(simpleItem)) {
                    roiActive = false;
                }
            } else {
                if (_isROIBeginItem(simpleItem)) {
                    roiActive = true;
                }
            }
        }

        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            viPair = VisualItemPair(lastCoordinateItem, visualItem);
1183 1184
            if (_flightPathSegmentHashTable.contains(viPair)) {
                _flightPathSegmentHashTable[viPair]->setSpecialVisual(roiActive);
1185 1186 1187 1188 1189 1190
            }
            lastCoordinateItem = visualItem;
        }
    }
}

1191
void MissionController::_recalcFlightPathSegments(void)
1192
{
1193
    VisualItemPair      lastSegmentVisualItemPair;
1194 1195 1196 1197 1198 1199 1200 1201 1202
    int                 segmentCount =              0;
    bool                firstCoordinateNotFound =   true;
    VisualMissionItem*  lastFlyThroughVI =          qobject_cast<VisualMissionItem*>(_visualItems->get(0));
    bool                linkEndToHome =             false;
    bool                linkStartToHome =           _managerVehicle->rover() ? true : false;
    bool                foundRTL =                  false;
    bool                homePositionValid =         _settingsItem->coordinate().isValid();
    bool                roiActive =                 false;
    bool                previousItemIsIncomplete =  false;
1203

1204
    qCDebug(MissionControllerLog) << "_recalcFlightPathSegments homePositionValid" << homePositionValid;
1205

1206
    FlightPathSegmentHashTable oldSegmentTable = _flightPathSegmentHashTable;
1207

1208
    _missionContainsVTOLTakeoff = false;
1209
    _flightPathSegmentHashTable.clear();
1210
    _waypointPath.clear();
1211

1212 1213 1214 1215
    // Note: Although visual support _incompleteComplexItemLines is still in the codebase. The support for populating the list is not.
    // This is due to the initial implementation being buggy and incomplete with respect to correctly generating the line set.
    // So for now we leave the code for displaying them in, but none are ever added until we have time to implement the correct support.

1216
    _simpleFlightPathSegments.beginReset();
1217
    _directionArrows.beginReset();
1218
    _incompleteComplexItemLines.beginReset();
1219

1220
    _simpleFlightPathSegments.clear();
1221
    _directionArrows.clear();
1222
    _incompleteComplexItemLines.clearAndDeleteContents();
1223

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

1226
    for (int i=1; i<_visualItems->count(); i++) {
1227 1228 1229
        VisualMissionItem*  visualItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        SimpleMissionItem*  simpleItem =    qobject_cast<SimpleMissionItem*>(visualItem);
        ComplexMissionItem* complexItem =   qobject_cast<ComplexMissionItem*>(visualItem);
1230

1231 1232
        visualItem->setSimpleFlighPathSegment(nullptr);

1233
        if (simpleItem) {
1234 1235 1236 1237 1238 1239 1240 1241 1242 1243
            if (roiActive) {
                if (_isROICancelItem(simpleItem)) {
                    roiActive = false;
                }
            } else {
                if (_isROIBeginItem(simpleItem)) {
                    roiActive = true;
                }
            }

1244 1245 1246 1247
            MAV_CMD command = simpleItem->mavCommand();
            switch (command) {
            case MAV_CMD_NAV_TAKEOFF:
            case MAV_CMD_NAV_VTOL_TAKEOFF:
1248
                _missionContainsVTOLTakeoff = command == MAV_CMD_NAV_VTOL_TAKEOFF;
1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262
                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;
1263
            }
1264 1265
        }

1266 1267 1268 1269 1270 1271
        // No need to add waypoint segments after an RTL.
        if (foundRTL) {
            break;
        }

        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
1272
            // Incomplete items are complex items which are waiting for the user to complete setup before there visuals can become valid.
1273 1274
            // They may not yet have valid entry/exit coordinates associated with them while in the incomplete state.
            // For examples a Survey item which has no polygon set yet.
1275
            if (complexItem && complexItem->isIncomplete()) {
1276 1277 1278 1279 1280 1281
                // We don't link lines from a valid item to an incomplete item
                previousItemIsIncomplete = true;
            } else if (previousItemIsIncomplete) {
                // We also don't link lines from an incomplete item to a valid item.
                previousItemIsIncomplete = false;
                firstCoordinateNotFound = false;
1282
                lastFlyThroughVI = visualItem;
1283
            } else {
1284
                if (lastFlyThroughVI != _settingsItem || (homePositionValid && linkStartToHome)) {
1285
                    bool addDirectionArrow = false;
1286 1287 1288 1289
                    if (i != 1) {
                        // Direction arrows are added to the second segment and every 5 segments thereafter.
                        // The reason for start with second segment is to prevent an arrow being added in between the home position
                        // and a takeoff item which may be right over each other. In that case the arrow points in a random direction.
1290
                        if (firstCoordinateNotFound || !lastFlyThroughVI->isSimpleItem() || !visualItem->isSimpleItem()) {
1291 1292 1293 1294 1295 1296
                            addDirectionArrow = true;
                        } else if (segmentCount > 5) {
                            segmentCount = 0;
                            addDirectionArrow = true;
                        }
                        segmentCount++;
1297 1298
                    }

1299
                    lastSegmentVisualItemPair =  VisualItemPair(lastFlyThroughVI, visualItem);
1300
                    if (!_flyView || addDirectionArrow) {
1301 1302
                        FlightPathSegment* segment = _addFlightPathSegment(oldSegmentTable, lastSegmentVisualItemPair);
                        segment->setSpecialVisual(roiActive);
1303
                        if (addDirectionArrow) {
1304
                            _directionArrows.append(segment);
1305
                        }
1306
                        lastFlyThroughVI->setSimpleFlighPathSegment(segment);
1307
                    }
1308
                }
1309 1310
                firstCoordinateNotFound = false;
                _waypointPath.append(QVariant::fromValue(visualItem->coordinate()));
1311
                lastFlyThroughVI = visualItem;
1312 1313 1314
            }
        }
    }
1315 1316 1317 1318 1319

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

1320 1321
    if (linkEndToHome && lastFlyThroughVI != _settingsItem && homePositionValid) {
        lastSegmentVisualItemPair = VisualItemPair(lastFlyThroughVI, _settingsItem);
1322
        if (_flyView) {
1323 1324
            _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
        }
1325 1326 1327
        FlightPathSegment* segment = _addFlightPathSegment(oldSegmentTable, lastSegmentVisualItemPair);
        segment->setSpecialVisual(roiActive);
        lastFlyThroughVI->setSimpleFlighPathSegment(segment);
1328
    }
1329

1330 1331
    // Add direction arrow to last segment
    if (lastSegmentVisualItemPair.first) {
1332
        FlightPathSegment* coordVector = nullptr;
1333

1334
        // 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 hash.
1335 1336
        // check for that first and add if needed

1337
        if (_flightPathSegmentHashTable.contains(lastSegmentVisualItemPair)) {
1338
            // Pair exists in the new table already just reuse it
1339 1340
            coordVector = _flightPathSegmentHashTable[lastSegmentVisualItemPair];
        } else if (oldSegmentTable.contains(lastSegmentVisualItemPair)) {
1341
            // Pair already exists in old table, pull from old to new and reuse
1342
            _flightPathSegmentHashTable[lastSegmentVisualItemPair] = coordVector = oldSegmentTable.take(lastSegmentVisualItemPair);
1343 1344
        } else {
            // Create a new segment. Since this is the fly view there is no need to wire change signals.
1345 1346 1347 1348 1349 1350 1351
            coordVector = new FlightPathSegment(lastSegmentVisualItemPair.first->isSimpleItem() ? lastSegmentVisualItemPair.first->coordinate() : lastSegmentVisualItemPair.first->exitCoordinate(),
                                                lastSegmentVisualItemPair.first->isSimpleItem() ? lastSegmentVisualItemPair.first->amslEntryAlt() : lastSegmentVisualItemPair.first->amslExitAlt(),
                                                lastSegmentVisualItemPair.second->coordinate(),
                                                lastSegmentVisualItemPair.second->amslEntryAlt(),
                                                !_flyView /* queryTerrainData */,
                                                this);
            _flightPathSegmentHashTable[lastSegmentVisualItemPair] = coordVector;
1352 1353 1354 1355 1356
        }

        _directionArrows.append(coordVector);
    }

1357
    _simpleFlightPathSegments.endReset();
1358
    _directionArrows.endReset();
1359
    _incompleteComplexItemLines.endReset();
1360

1361
    // Anything left in the old table is an obsolete line object that can go
1362
    qDeleteAll(oldSegmentTable);
1363

1364
    emit _recalcMissionFlightStatusSignal();
1365

1366
    if (_waypointPath.count() == 0) {
1367
        // MapPolyLine has a bug where if you change from a path which has elements to an empty path the line drawn
1368 1369 1370 1371 1372 1373 1374
        // 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();
1375
    emit recalcTerrainProfile();
1376 1377
}

1378 1379 1380 1381 1382 1383
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);
1384 1385 1386
        // 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.
1387
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410
            _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);
}

1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437
/// 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
1438
void MissionController::_recalcMissionFlightStatus()
1439
{
1440
    if (!_visualItems->count()) {
1441
        return;
1442
    }
1443

1444
    bool                firstCoordinateItem =           true;
1445
    VisualMissionItem*  lastFlyThroughVI =   qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1446

1447
    bool homePositionValid = _settingsItem->coordinate().isValid();
1448

DonLakeFlyer's avatar
DonLakeFlyer committed
1449
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1450

1451 1452 1453
    // 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.
1454

1455
    // No values for first item
1456 1457 1458
    lastFlyThroughVI->setAltDifference(0.0);
    lastFlyThroughVI->setAzimuth(0.0);
    lastFlyThroughVI->setDistance(0.0);
1459

1460
    _minAMSLAltitude = _maxAMSLAltitude = _settingsItem->coordinate().altitude();
1461

1462
    _resetMissionFlightStatus();
1463

1464
    bool   vtolInHover =                _missionContainsVTOLTakeoff;
1465 1466 1467 1468
    bool   linkStartToHome =            false;
    bool   foundRTL =                   false;
    bool   vehicleYawSpecificallySet =  false;
    double totalHorizontalDistance =    0;
1469

DonLakeFlyer's avatar
DonLakeFlyer committed
1470
    for (int i=0; i<_visualItems->count(); i++) {
1471 1472 1473 1474 1475 1476 1477
        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;
        }
1478

1479 1480
        // Assume the worst
        item->setAzimuth(0.0);
1481
        item->setDistance(0.0);
1482

DonLakeFlyer's avatar
DonLakeFlyer committed
1483 1484 1485
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1486
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1487
                _missionFlightStatus.hoverSpeed = newSpeed;
1488
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1489 1490
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1491
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1492
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1493
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1494 1495
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1496
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1497 1498 1499
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514
        // 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
1515
        double gimbalYaw = item->specifiedGimbalYaw();
Remek Zajac's avatar
Remek Zajac committed
1516
        if (!qIsNaN(gimbalYaw) || _planViewSettings->showGimbalOnlyWhenSet()->rawValue().toBool()) {
1517 1518 1519
            _missionFlightStatus.gimbalYaw = gimbalYaw;
        }
        double gimbalPitch = item->specifiedGimbalPitch();
Remek Zajac's avatar
Remek Zajac committed
1520
        if (!qIsNaN(gimbalPitch) || _planViewSettings->showGimbalOnlyWhenSet()->rawValue().toBool()) {
1521
            _missionFlightStatus.gimbalPitch = gimbalPitch;
DonLakeFlyer's avatar
DonLakeFlyer committed
1522 1523 1524 1525 1526
        }

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

1529 1530 1531 1532 1533
        if (foundRTL) {
            // No more vehicle distances after RTL
            continue;
        }

1534
        // Link back to home if first item is takeoff and we have home position
1535 1536
        if (firstCoordinateItem && simpleItem && (simpleItem->mavCommand() == MAV_CMD_NAV_TAKEOFF || simpleItem->mavCommand() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
            if (homePositionValid) {
1537
                linkStartToHome = true;
1538 1539 1540
                if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
                    // We have to special case takeoff, assuming vehicle takes off straight up to specified altitude
                    double azimuth, distance, altDifference;
1541
                    _calcPrevWaypointValues(_settingsItem, simpleItem, &azimuth, &distance, &altDifference);
1542 1543 1544
                    double takeoffTime = qAbs(altDifference) / _appSettings->offlineEditingAscentSpeed()->rawValue().toDouble();
                    _addHoverTime(takeoffTime, 0, -1);
                }
1545 1546 1547 1548
            }
        }

        // Update VTOL state
1549
        if (simpleItem && _controllerVehicle->vtol()) {
1550
            switch (simpleItem->command()) {
1551 1552
            case MAV_CMD_NAV_TAKEOFF:       // This will do a fixed wing style takeoff
            case MAV_CMD_NAV_VTOL_TAKEOFF:  // Vehicle goes straight up and then transitions to FW
1553 1554
                vtolInHover = false;
                break;
1555
            case MAV_CMD_NAV_LAND:
1556 1557
                vtolInHover = false;
                break;
1558
            case MAV_CMD_NAV_VTOL_LAND:
DonLakeFlyer's avatar
DonLakeFlyer committed
1559 1560
                vtolInHover = true;
                break;
1561
            case MAV_CMD_DO_VTOL_TRANSITION:
1562 1563 1564 1565 1566 1567
            {
                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;
1568 1569
                }
            }
1570 1571 1572
                break;
            default:
                break;
1573
            }
Don Gagne's avatar
Don Gagne committed
1574 1575
        }

1576
        _addTimeDistance(vtolInHover, 0, 0, item->additionalTimeDelay(), 0, -1);
1577

1578 1579
        if (item->specifiesCoordinate()) {

1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590
            // Keep track of the min/max AMSL altitude for entire mission so we can calculate altitude percentages in terrain status display
            if (simpleItem) {
                double amslAltitude = item->amslEntryAlt();
                _minAMSLAltitude = std::min(_minAMSLAltitude, amslAltitude);
                _maxAMSLAltitude = std::max(_maxAMSLAltitude, amslAltitude);
            } else {
                // Complex item
                double complexMinAMSLAltitude = complexItem->minAMSLAltitude();
                double complexMaxAMSLAltitude = complexItem->maxAMSLAltitude();
                _minAMSLAltitude = std::min(_minAMSLAltitude, complexMinAMSLAltitude);
                _maxAMSLAltitude = std::max(_maxAMSLAltitude, complexMaxAMSLAltitude);
1591 1592 1593
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1594
                firstCoordinateItem = false;
1595

1596
                // Update vehicle yaw assuming direction to next waypoint and/or mission item change
1597
                if (item != lastFlyThroughVI) {
1598 1599 1600 1601
                    if (simpleItem && !qIsNaN(simpleItem->specifiedVehicleYaw())) {
                        vehicleYawSpecificallySet = true;
                        _missionFlightStatus.vehicleYaw = simpleItem->specifiedVehicleYaw();
                    } else if (!vehicleYawSpecificallySet) {
1602
                        _missionFlightStatus.vehicleYaw = lastFlyThroughVI->exitCoordinate().azimuthTo(item->coordinate());
1603
                    }
1604
                    lastFlyThroughVI->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1605 1606
                }

1607
                if (lastFlyThroughVI != _settingsItem || linkStartToHome) {
1608 1609
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1610

1611 1612
                    _calcPrevWaypointValues(item, lastFlyThroughVI, &azimuth, &distance, &altDifference);
                    totalHorizontalDistance += distance;
1613 1614 1615
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1616
                    item->setDistanceFromStart(totalHorizontalDistance);
1617

1618
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1619

DonLakeFlyer's avatar
DonLakeFlyer committed
1620 1621 1622
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1623
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1624
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1625

1626
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1627 1628
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1629
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1630

1631 1632
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1633
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1634 1635

                    totalHorizontalDistance += distance;
1636
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1637 1638

                item->setMissionFlightStatus(_missionFlightStatus);
1639

1640
                lastFlyThroughVI = item;
1641
            }
1642 1643
        }
    }
1644
    lastFlyThroughVI->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1645

1646
    // Add the information for the final segment back to home
1647
    if (foundRTL && lastFlyThroughVI != _settingsItem && homePositionValid) {
1648
        double azimuth, distance, altDifference;
1649
        _calcPrevWaypointValues(lastFlyThroughVI, _settingsItem, &azimuth, &distance, &altDifference);
1650 1651 1652 1653 1654

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

1658 1659 1660
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1661

1662 1663 1664 1665 1666 1667 1668 1669 1670 1671 1672
    emit missionMaxTelemetryChanged     (_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged         (_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged    (_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged   (_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged             ();
    emit missionHoverTimeChanged        ();
    emit missionCruiseTimeChanged       ();
    emit batteryChangePointChanged      (_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged       (_missionFlightStatus.batteriesRequired);
    emit minAMSLAltitudeChanged         (_minAMSLAltitude);
    emit maxAMSLAltitudeChanged         (_maxAMSLAltitude);
1673

1674
    // Walk the list again calculating altitude percentages
1675
    double altRange = _maxAMSLAltitude - _minAMSLAltitude;
1676 1677
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1678 1679

        if (item->specifiesCoordinate()) {
1680
            double amslAlt = item->amslEntryAlt();
1681 1682
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1683
                item->setTerrainPercent(qQNaN());
1684
                item->setTerrainCollision(false);
1685
            } else {
1686
                item->setAltPercent((amslAlt - _minAMSLAltitude) / altRange);
1687 1688 1689 1690 1691
                double terrainAltitude = item->terrainAltitude();
                if (qIsNaN(terrainAltitude)) {
                    item->setTerrainPercent(qQNaN());
                    item->setTerrainCollision(false);
                } else {
1692 1693
                    item->setTerrainPercent((terrainAltitude - _minAMSLAltitude) / altRange);
                    item->setTerrainCollision(amslAlt < terrainAltitude);
1694
                }
1695
            }
1696 1697
        }
    }
1698 1699

    _updateTimer.start(UPDATE_TIMEOUT);
1700 1701

    emit recalcTerrainProfile();
1702 1703
}

1704 1705 1706
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1707 1708 1709 1710 1711
    if (_inRecalcSequence) {
        // Don't let this call recurse due to signalling
        return;
    }

1712 1713
    // Setup ascending sequence numbers for all visual items

1714
    _inRecalcSequence = true;
1715 1716 1717
    int sequenceNumber = 0;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1718 1719
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1720
    }
1721
    _inRecalcSequence = false;
1722 1723
}

1724 1725 1726
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1727
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1728 1729 1730

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

1731
    for (int i=1; i<_visualItems->count(); i++) {
1732 1733 1734 1735
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

        item->setParentItem(nullptr);
        item->setHasCurrentChildItem(false);
1736 1737 1738 1739 1740

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1741
        } else if (item->isSimpleItem()) {
1742
            item->setParentItem(currentParentItem);
1743
            currentParentItem->childItems()->append(item);
1744 1745 1746
            if (item->isCurrentItem()) {
                currentParentItem->setHasCurrentChildItem(true);
            }
1747 1748 1749 1750
        }
    }
}

1751
void MissionController::_setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate)
1752
{
1753
    bool foundFirstCoordinate = false;
1754 1755
    QGeoCoordinate firstCoordinate;

1756 1757 1758 1759
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

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

1764 1765
        if (item->specifiesCoordinate() && item->coordinate().isValid()) {
            foundFirstCoordinate = true;
1766 1767
            firstCoordinate = item->coordinate();
            break;
1768 1769 1770
        }
    }

1771
    // No item specifying a coordinate was found, in this case it we have a clickCoordinate use that
1772
    if (!foundFirstCoordinate) {
1773 1774
        firstCoordinate = clickCoordinate;
    }
1775

1776 1777 1778
    if (firstCoordinate.isValid()) {
        QGeoCoordinate plannedHomeCoord = firstCoordinate.atDistanceAndAzimuth(30, 0);
        plannedHomeCoord.setAltitude(0);
1779
        _settingsItem->setInitialHomePositionFromUser(plannedHomeCoord);
1780 1781 1782
    }
}

1783
void MissionController::_recalcAllWithCoordinate(const QGeoCoordinate& coordinate)
1784
{
1785
    if (!_flyView) {
1786
        _setPlannedHomePositionFromFirstCoordinate(coordinate);
1787
    }
1788
    _recalcSequence();
1789
    _recalcChildItems();
1790
    emit _recalcFlightPathSegmentsSignal();
1791
    _updateTimer.start(UPDATE_TIMEOUT);
1792 1793
}

1794 1795 1796
void MissionController::_recalcAll(void)
{
    QGeoCoordinate emptyCoord;
1797
    _recalcAllWithCoordinate(emptyCoord);
1798 1799
}

1800
/// Initializes a new set of mission items
1801
void MissionController::_initAllVisualItems(void)
1802
{
1803 1804
    // Setup home position at index 0

1805
    if (!_settingsItem) {
1806 1807 1808 1809 1810
        _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
        if (!_settingsItem) {
            qWarning() << "First item not MissionSettingsItem";
            return;
        }
1811
    }
1812

1813 1814
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1815

1816 1817 1818 1819
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1820

1821
    _recalcAll();
1822

1823
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1824 1825 1826
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1827
    emit containsItemsChanged(containsItems());
1828
    emit plannedHomePositionChanged(plannedHomePosition());
1829

1830
    if (!_flyView) {
1831
        setCurrentPlanViewSeqNum(0, true);
1832 1833
    }

1834
    setDirty(false);
1835 1836
}

1837
void MissionController::_deinitAllVisualItems(void)
1838
{
1839 1840 1841
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1842 1843
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1844 1845
    }

1846
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1847
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1848 1849
}

1850
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1851
{
1852
    setDirty(false);
1853

1854 1855 1856 1857 1858 1859 1860 1861
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcFlightPathSegmentsSignal,  Qt::QueuedConnection);
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
    connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged,                this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
    connect(visualItem, &VisualMissionItem::specifiedVehicleYawChanged,                 this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
    connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged,                 this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);

1862
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1863

1864 1865 1866 1867 1868 1869 1870 1871
    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";
        }
1872 1873
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1874
        if (complexItem) {
1875 1876 1877 1878 1879
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
            connect(complexItem, &ComplexMissionItem::minAMSLAltitudeChanged,       this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
            connect(complexItem, &ComplexMissionItem::maxAMSLAltitudeChanged,       this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
            connect(complexItem, &ComplexMissionItem::isIncompleteChanged,          this, &MissionController::_recalcFlightPathSegmentsSignal,  Qt::QueuedConnection);
1880 1881 1882
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1883
    }
1884 1885
}

1886
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1887
{
1888
    // Disconnect all signals
1889
    disconnect(visualItem, nullptr, nullptr, nullptr);
1890 1891
}

1892
void MissionController::_itemCommandChanged(void)
1893
{
1894
    _recalcChildItems();
1895
    emit _recalcFlightPathSegmentsSignal();
1896 1897
}

1898
void MissionController::_managerVehicleChanged(Vehicle* managerVehicle)
1899
{
1900 1901 1902
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
1903 1904
        _managerVehicle = nullptr;
        _missionManager = nullptr;
1905
    }
1906

1907 1908
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1909
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1910 1911
        return;
    }
1912

1913 1914
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1915 1916
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1917 1918 1919 1920 1921
    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);
1922
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1923 1924
    connect(_managerVehicle, &Vehicle::defaultCruiseSpeedChanged,       this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
    connect(_managerVehicle, &Vehicle::defaultHoverSpeedChanged,        this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
1925
    connect(_managerVehicle, &Vehicle::vehicleTypeChanged,              this, &MissionController::complexMissionItemNamesChanged);
1926

1927
    emit complexMissionItemNamesChanged();
1928
    emit resumeMissionIndexChanged();
1929 1930 1931
}

void MissionController::_inProgressChanged(bool inProgress)
1932
{
1933
    emit syncInProgressChanged(inProgress);
1934
}
1935

1936
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1937
{
1938
    bool        found = false;
1939
    double      foundAltitude = 0;
1940
    int         foundAltitudeMode = QGroundControlQmlGlobal::AltitudeModeNone;
1941

1942 1943 1944 1945 1946 1947
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1950 1951 1952
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1953 1954 1955
                if (simpleItem->specifiesAltitude()) {
                    foundAltitude = simpleItem->altitude()->rawValue().toDouble();
                    foundAltitudeMode = simpleItem->altitudeMode();
1956
                    found = true;
1957
                    break;
1958 1959
                }
            }
1960 1961 1962
        }
    }

1963
    if (found) {
1964
        *prevAltitude = foundAltitude;
1965
        *prevAltitudeMode = foundAltitudeMode;
1966 1967 1968
    }

    return found;
1969
}
1970 1971 1972 1973 1974 1975 1976 1977 1978 1979 1980 1981 1982

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

1983
/// Add the Mission Settings complex item to the front of the items
1984
MissionSettingsItem* MissionController::_addMissionSettings(QmlObjectListModel* visualItems)
1985
{
1986 1987
    qCDebug(MissionControllerLog) << "_addMissionSettings";

1988
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_masterController, _flyView, visualItems);
1989
    visualItems->insert(0, settingsItem);
1990

1991 1992 1993 1994 1995
    if (visualItems == _visualItems) {
        _settingsItem = settingsItem;
    }

    return settingsItem;
1996
}
Don Gagne's avatar
Don Gagne committed
1997

1998 1999 2000
void MissionController::_centerHomePositionOnMissionItems(QmlObjectListModel *visualItems)
{
    qCDebug(MissionControllerLog) << "_centerHomePositionOnMissionItems";
2001

2002 2003 2004 2005 2006 2007 2008 2009 2010 2011 2012 2013 2014 2015 2016 2017 2018 2019 2020 2021 2022 2023 2024
    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;
2025 2026
                }
            }
2027
        }
2028

2029 2030
        if (firstCoordSet) {
            _settingsItem->setInitialHomePositionFromUser(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
2031 2032 2033
        }
    }
}
2034

2035
int MissionController::resumeMissionIndex(void) const
2036
{
2037

2038
    int resumeIndex = 0;
2039

2040
    if (_flyView) {
2041
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
2042
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
2043 2044
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
2045 2046
        } else {
            resumeIndex = 0;
2047 2048 2049 2050 2051
        }
    }

    return resumeIndex;
}
2052

2053 2054
int MissionController::currentMissionIndex(void) const
{
2055
    if (!_flyView) {
2056 2057 2058 2059 2060 2061 2062 2063 2064 2065
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

2066
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
2067
{
2068
    if (_flyView) {
2069
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
2070 2071 2072
            sequenceNumber++;
        }

2073 2074
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
2075 2076
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
2077
        emit currentMissionIndexChanged(currentMissionIndex());
2078 2079
    }
}
2080

2081
bool MissionController::syncInProgress(void) const
2082
{
2083
    return _missionManager->inProgress();
2084 2085 2086 2087 2088 2089 2090 2091 2092 2093 2094 2095
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
2096
    }
2097
}
2098

2099
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, PlanMasterController* masterController)
2100
{
2101
    // First we look for a Fixed Wing Landing Pattern which is at the end
2102
    FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, masterController);
2103

2104 2105 2106 2107 2108 2109
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

2110
        if (!_flyView) {
2111 2112 2113 2114 2115 2116
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
2117 2118 2119
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
2120
        if (simpleItem) {
2121
            scanIndex++;
2122
            simpleItem->scanForSections(visualItems, scanIndex, masterController);
2123 2124 2125
        } else {
            // Complex item, can't have sections
            scanIndex++;
2126 2127 2128
        }
    }
}
2129 2130 2131 2132 2133 2134 2135 2136 2137 2138 2139 2140 2141

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
2142 2143 2144 2145 2146 2147 2148 2149
    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();
    }
2150
}
2151 2152 2153 2154 2155

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

2156 2157
    complexItems.append(SurveyComplexItem::name);
    complexItems.append(CorridorScanComplexItem::name);
2158
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
2159
        complexItems.append(StructureScanComplexItem::name);
2160
    }
2161

2162 2163
    // Note: The landing pattern items are not added here since they have there own button which adds them

2164
    return qgcApp()->toolbox()->corePlugin()->complexMissionItemNames(_controllerVehicle, complexItems);
2165
}
2166

2167 2168
void MissionController::resumeMission(int resumeIndex)
{
2169
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
2170 2171
        resumeIndex--;
    }
2172
    _missionManager->generateResumeMission(resumeIndex);
2173
}
2174 2175 2176 2177 2178 2179 2180 2181 2182

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
2183 2184 2185 2186 2187 2188 2189 2190 2191 2192

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

2194 2195 2196 2197 2198 2199 2200
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
2201 2202 2203 2204 2205 2206

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
2207 2208 2209

bool MissionController::showPlanFromManagerVehicle (void)
{
2210
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
DonLakeFlyer's avatar
DonLakeFlyer committed
2211 2212
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
2213
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
2214 2215 2216 2217 2218 2219 2220 2221 2222 2223 2224 2225 2226 2227 2228 2229 2230 2231 2232
    } 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;
        }
    }
}

2233
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2234
{
2235
    // Fly view always reloads on send complete
2236
    if (!error && _flyView) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2237 2238 2239 2240
        showPlanFromManagerVehicle();
    }
}

2241
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2242
{
2243 2244 2245 2246
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2247
}
2248

2249 2250 2251 2252 2253 2254 2255 2256 2257 2258 2259 2260 2261 2262 2263
bool MissionController::_isROIBeginItem(SimpleMissionItem* simpleItem)
{
    return simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI_LOCATION ||
            simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET ||
            (simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI &&
             static_cast<int>(simpleItem->missionItem().param1()) == MAV_ROI_LOCATION);
}

bool MissionController::_isROICancelItem(SimpleMissionItem* simpleItem)
{
    return simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI_NONE ||
            (simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI &&
             static_cast<int>(simpleItem->missionItem().param1()) == MAV_ROI_NONE);
}

2264
void MissionController::setCurrentPlanViewSeqNum(int sequenceNumber, bool force)
2265
{
2266
    if (_visualItems && (force || sequenceNumber != _currentPlanViewSeqNum)) {
2267 2268 2269 2270
        bool    foundLand =             false;
        int     takeoffSeqNum =         -1;
        int     landSeqNum =            -1;
        int     lastFlyThroughSeqNum =  -1;
2271

2272 2273
        _splitSegment =                 nullptr;
        _currentPlanViewItem  =         nullptr;
2274 2275
        _currentPlanViewSeqNum =        -1;
        _currentPlanViewVIIndex =       -1;
2276
        _onlyInsertTakeoffValid =       !_planViewSettings->takeoffItemNotRequired()->rawValue().toBool() && _visualItems->count() == 1; // First item must be takeoff
2277 2278
        _isInsertTakeoffValid =         true;
        _isInsertLandValid =            true;
2279
        _isROIActive =                  false;
2280
        _isROIBeginCurrentItem =        false;
2281
        _flyThroughCommandsAllowed =    true;
2282
        _previousCoordinate =           QGeoCoordinate();
2283

2284
        for (int viIndex=0; viIndex<_visualItems->count(); viIndex++) {
2285 2286 2287
            VisualMissionItem*  pVI =        qobject_cast<VisualMissionItem*>(_visualItems->get(viIndex));
            SimpleMissionItem*  simpleItem = qobject_cast<SimpleMissionItem*>(pVI);
            int                 currentSeqNumber = pVI->sequenceNumber();
2288

2289
            if (sequenceNumber != 0 && currentSeqNumber <= sequenceNumber) {
2290 2291 2292 2293 2294 2295 2296
                if (pVI->specifiesCoordinate() && !pVI->isStandaloneCoordinate()) {
                    // Coordinate based flight commands prior to where the takeoff would be inserted
                    _isInsertTakeoffValid = false;
                }
            }

            if (qobject_cast<TakeoffMissionItem*>(pVI)) {
2297
                takeoffSeqNum = currentSeqNumber;
2298 2299 2300
                _isInsertTakeoffValid = false;
            }

2301 2302 2303 2304 2305 2306 2307 2308
            if (!foundLand) {
                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;
2309
                        landSeqNum = currentSeqNumber;
2310 2311 2312 2313 2314 2315 2316 2317
                        break;
                    default:
                        break;
                    }
                } else {
                    FixedWingLandingComplexItem* fwLanding = qobject_cast<FixedWingLandingComplexItem*>(pVI);
                    if (fwLanding) {
                        foundLand = true;
2318
                        landSeqNum = currentSeqNumber;
2319 2320 2321 2322 2323
                    }
                }
            }

            if (simpleItem) {
2324
                // Remember previous coordinate
2325
                if (currentSeqNumber < sequenceNumber && simpleItem->specifiesCoordinate() && !simpleItem->isStandaloneCoordinate()) {
2326 2327 2328 2329
                    _previousCoordinate = simpleItem->coordinate();
                }

                // ROI state handling
2330
                if (currentSeqNumber <= sequenceNumber) {
2331
                    if (_isROIActive) {
2332
                        if (_isROICancelItem(simpleItem)) {
2333 2334 2335
                            _isROIActive = false;
                        }
                    } else {
2336
                        if (_isROIBeginItem(simpleItem)) {
2337 2338
                            _isROIActive = true;
                        }
2339 2340
                    }
                }
2341
                if (currentSeqNumber == sequenceNumber && _isROIBeginItem(simpleItem)) {
2342 2343
                    _isROIBeginCurrentItem = true;
                }
2344
            }
2345

2346 2347 2348
            if (viIndex != 0) {
                // Complex items are assumed to be fly through
                if (!simpleItem || (simpleItem->specifiesCoordinate() && !simpleItem->isStandaloneCoordinate())) {
2349 2350
                    lastFlyThroughSeqNum = currentSeqNumber;
                }
2351 2352
            }

2353
            if (currentSeqNumber == sequenceNumber) {
2354
                pVI->setIsCurrentItem(true);
2355 2356
                pVI->setHasCurrentChildItem(false);

2357
                _currentPlanViewItem  = pVI;
2358 2359
                _currentPlanViewSeqNum = sequenceNumber;
                _currentPlanViewVIIndex = viIndex;
2360

2361 2362 2363 2364 2365 2366 2367
                if (pVI->specifiesCoordinate()) {
                    if (!pVI->isStandaloneCoordinate()) {
                        // Determine split segment used to display line split editing ui.
                        for (int j=viIndex-1; j>0; j--) {
                            VisualMissionItem* pPrev = qobject_cast<VisualMissionItem*>(_visualItems->get(j));
                            if (pPrev->specifiesCoordinate() && !pPrev->isStandaloneCoordinate()) {
                                VisualItemPair splitPair(pPrev, pVI);
2368 2369
                                if (_flightPathSegmentHashTable.contains(splitPair)) {
                                    _splitSegment = _flightPathSegmentHashTable[splitPair];
2370
                                }
2371 2372 2373
                            }
                        }
                    }
2374 2375
                } else if (pVI->parentItem()) {
                    pVI->parentItem()->setHasCurrentChildItem(true);
2376
                }
2377 2378 2379 2380
            } else {
                pVI->setIsCurrentItem(false);
            }
        }
2381

2382
        if (takeoffSeqNum != -1) {
2383
            // Takeoff item was found which means mission starts from ground
2384
            if (sequenceNumber < takeoffSeqNum) {
2385 2386 2387 2388 2389 2390 2391
                // Land is only valid after the takeoff item.
                _isInsertLandValid = false;
                // Fly through commands are not allowed prior to the takeoff command
                _flyThroughCommandsAllowed = false;
            }
        }

2392 2393 2394 2395 2396 2397 2398
        if (lastFlyThroughSeqNum != -1) {
            // Land item must be after any fly through coordinates
            if (sequenceNumber < lastFlyThroughSeqNum) {
                _isInsertLandValid = false;
            }
        }

2399 2400
        if (foundLand) {
            // Can't have more than one land sequence
2401
            _isInsertLandValid = false;
2402
            if (sequenceNumber >= landSeqNum) {
2403 2404 2405
                // Can't have fly through commands after a land item
                _flyThroughCommandsAllowed = false;
            }
2406 2407
        }

2408 2409 2410 2411
        // These are not valid when only takeoff is allowed
        _isInsertLandValid =            _isInsertLandValid && !_onlyInsertTakeoffValid;
        _flyThroughCommandsAllowed =    _flyThroughCommandsAllowed && !_onlyInsertTakeoffValid;

2412 2413
        emit currentPlanViewSeqNumChanged();
        emit currentPlanViewVIIndexChanged();
2414
        emit currentPlanViewItemChanged();
2415
        emit splitSegmentChanged();
2416
        emit onlyInsertTakeoffValidChanged();
2417
        emit isInsertTakeoffValidChanged();
2418
        emit isInsertLandValidChanged();
2419
        emit isROIActiveChanged();
2420
        emit isROIBeginCurrentItemChanged();
2421
        emit flyThroughCommandsAllowedChanged();
2422
        emit previousCoordinateChanged();
2423 2424
    }
}
2425 2426 2427

void MissionController::_updateTimeout()
{
Gus Grubba's avatar
Gus Grubba committed
2428
    QGeoCoordinate firstCoordinate;
2429
    QGeoCoordinate takeoffCoordinate;
2430
    QGCGeoBoundingCube boundingCube;
2431 2432 2433 2434
    double north = 0.0;
    double south = 180.0;
    double east  = 0.0;
    double west  = 360.0;
2435 2436
    double minAlt = QGCGeoBoundingCube::MaxAlt;
    double maxAlt = QGCGeoBoundingCube::MinAlt;
2437 2438 2439 2440 2441 2442
    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()) {
2443
                case MAV_CMD_NAV_TAKEOFF:
2444 2445
                case MAV_CMD_NAV_WAYPOINT:
                case MAV_CMD_NAV_LAND:
2446 2447 2448 2449 2450 2451 2452 2453 2454 2455 2456 2457 2458 2459 2460
                    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
2461
                    }
2462
                    break;
2463 2464 2465 2466 2467 2468 2469
                default:
                    break;
                }
            }
        } else {
            ComplexMissionItem* pComplexItem = qobject_cast<ComplexMissionItem*>(item);
            if(pComplexItem) {
2470 2471
                QGCGeoBoundingCube bc = pComplexItem->boundingCube();
                if(bc.isValid()) {
Gus Grubba's avatar
Gus Grubba committed
2472 2473 2474
                    if(!firstCoordinate.isValid() && pComplexItem->coordinate().isValid()) {
                        firstCoordinate = pComplexItem->coordinate();
                    }
2475 2476 2477 2478 2479 2480
                    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());
2481 2482 2483 2484
                }
            }
        }
    }
Gus Grubba's avatar
Gus Grubba committed
2485 2486 2487 2488 2489 2490 2491 2492 2493
    //-- Figure out where this thing is taking off from
    if(!takeoffCoordinate.isValid()) {
        if(firstCoordinate.isValid()) {
            takeoffCoordinate = firstCoordinate;
        } else {
            takeoffCoordinate = plannedHomePosition();
        }
    }
    //-- Build bounding "cube"
2494
    boundingCube = QGCGeoBoundingCube(
2495 2496
                QGeoCoordinate(north - 90.0, west - 180.0, minAlt),
                QGeoCoordinate(south - 90.0, east - 180.0, maxAlt));
2497 2498
    if(_travelBoundingCube != boundingCube || _takeoffCoordinate != takeoffCoordinate) {
        _takeoffCoordinate  = takeoffCoordinate;
2499
        _travelBoundingCube = boundingCube;
2500
        emit missionBoundingCubeChanged();
2501
        qCDebug(MissionControllerLog) << "Bounding cube:" << _travelBoundingCube.pointNW << _travelBoundingCube.pointSE;
2502 2503 2504 2505 2506 2507 2508
    }
}

void MissionController::_complexBoundingBoxChanged()
{
    _updateTimer.start(UPDATE_TIMEOUT);
}
2509 2510 2511 2512 2513

bool MissionController::isEmpty(void) const
{
    return _visualItems->count() <= 1;
}
2514 2515 2516 2517 2518 2519

void MissionController::_takeoffItemNotRequiredChanged(void)
{
    // Force a recalc of allowed bits
    setCurrentPlanViewSeqNum(_currentPlanViewSeqNum, true /* force */);
}
2520 2521 2522 2523 2524 2525 2526 2527 2528 2529 2530 2531 2532 2533 2534

QString MissionController::surveyComplexItemName(void) const
{
    return SurveyComplexItem::name;
}

QString MissionController::corridorScanComplexItemName(void) const
{
    return CorridorScanComplexItem::name;
}

QString MissionController::structureScanComplexItemName(void) const
{
    return StructureScanComplexItem::name;
}