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


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

33
#ifndef __mobile__
34
#include "MainWindow.h"
35
#include "QGCQFileDialog.h"
36 37
#endif

38 39
#define UPDATE_TIMEOUT 5000 ///< How often we check for bounding box changes

40 41
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

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

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

84 85
}

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

    // Battery information

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

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

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

129 130
}

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

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

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

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

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

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

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

182
        for (; i < newMissionItems.count(); i++) {
183
            const MissionItem* missionItem = newMissionItems[i];
184
            newControllerMissionItems->append(new SimpleMissionItem(_controllerVehicle, _flyView, *missionItem, this));
185 186 187
        }

        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
188
        _visualItems->deleteLater();
189
        _settingsItem = NULL;
190 191
        _visualItems = NULL;
        _updateContainsItems(); // This will clear containsItems which will be set again below. This will re-pop Start Mission confirmation.
192 193
        _visualItems = newControllerMissionItems;

194
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
195
            _addMissionSettings(_visualItems, !_flyView && _visualItems->count() > 0 /* addToCenter */);
196 197
        }

198
        MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
199

200
        _initAllVisualItems();
201
        _updateContainsItems();
202
        emit newItemsFromVehicle();
203
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
204
    _itemsRequested = false;
205 206
}

207
void MissionController::loadFromVehicle(void)
208
{
DonLakeFlyer's avatar
DonLakeFlyer committed
209 210 211 212 213 214 215 216
    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();
    }
217 218
}

219 220 221 222 223 224 225 226 227 228 229
void MissionController::_warnIfTerrainFrameUsed(void)
{
    for (int i=1; i<_visualItems->count(); i++) {
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(i));
        if (simpleItem && simpleItem->altitudeMode() == SimpleMissionItem::AltitudeTerrainFrame) {
            qgcApp()->showMessage(tr("Warning: You are using MAV_FRAME_GLOBAL_TERRAIN_ALT in a mission. %1 does not support sending terrain tiles to vehicle.").arg(qgcApp()->applicationName()));
            break;
        }
    }
}

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

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

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

    return endActionSet;
}

283 284
void MissionController::convertToKMLDocument(QDomDocument& document)
{
285 286
    QObject*            deleteParent = new QObject();
    QList<MissionItem*> rgMissionItems;
287

288 289
    _convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
    if (rgMissionItems.count() == 0) {
290 291
        return;
    }
292

293
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
294 295 296 297 298

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

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

    deleteParent->deleteLater();

320 321 322 323 324
    Kml kml;
    kml.points(coords);
    kml.save(document);
}

Don Gagne's avatar
Don Gagne committed
325 326 327
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
328
        QList<MissionItem*> rgMissionItems;
329

330
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
331

332
        // PlanManager takes control of MissionItems so no need to delete
333
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
334 335
    }
}
336

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

348
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
349
{
350
    int sequenceNumber = _nextSequenceNumber();
351
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
352
    newItem->setSequenceNumber(sequenceNumber);
353
    newItem->setCoordinate(coordinate);
354
    newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
355 356
    _initVisualItem(newItem);
    if (_visualItems->count() == 1) {
357
        MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
358 359 360
        if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains((MAV_CMD)takeoffCmd)) {
            newItem->setCommand(takeoffCmd);
        }
361
    }
362
    newItem->setDefaultsForCommand();
363 364 365
    if (newItem->specifiesAltitude()) {
        double  prevAltitude;
        int     prevAltitudeMode;
366

367 368 369
        if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
            newItem->altitude()->setRawValue(prevAltitude);
            newItem->setAltitudeMode((SimpleMissionItem::AltitudeMode)prevAltitudeMode);
370
        }
371
    }
372
    newItem->setMissionFlightStatus(_missionFlightStatus);
373
    _visualItems->insert(i, newItem);
374 375

    _recalcAll();
376
    return newItem->sequenceNumber();
377 378
}

379 380 381
int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
{
    int sequenceNumber = _nextSequenceNumber();
382
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
383
    newItem->setSequenceNumber(sequenceNumber);
384
    newItem->setCommand((MAV_CMD)(_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains((MAV_CMD)MAV_CMD_DO_SET_ROI_LOCATION) ?
385 386
        MAV_CMD_DO_SET_ROI_LOCATION :
        MAV_CMD_DO_SET_ROI));
387 388
    _initVisualItem(newItem);
    newItem->setDefaultsForCommand();
389
    newItem->setCoordinate(coordinate);
390

391 392
    double  prevAltitude;
    int     prevAltitudeMode;
393

394 395 396
    if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
        newItem->altitude()->setRawValue(prevAltitude);
        newItem->setAltitudeMode((SimpleMissionItem::AltitudeMode)prevAltitudeMode);
397 398 399 400 401 402 403 404
    }
    _visualItems->insert(i, newItem);

    _recalcAll();

    return newItem->sequenceNumber();
}

405
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
406
{
407 408
    ComplexMissionItem* newItem;

409
    int sequenceNumber = _nextSequenceNumber();
410
    if (itemName == _surveyMissionItemName) {
411
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
412
        newItem->setCoordinate(mapCenterCoordinate);
413
    } else if (itemName == _fwLandingMissionItemName) {
414
        newItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, _visualItems /* parent */);
415
    } else if (itemName == _structureScanMissionItemName) {
416
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
417
    } else if (itemName == _corridorScanMissionItemName) {
418
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
419 420 421 422 423
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }

424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449
    return _insertComplexMissionItemWorker(newItem, i);
}

int MissionController::insertComplexMissionItemFromKML(QString itemName, QString kmlFile, int i)
{
    ComplexMissionItem* newItem;

    if (itemName == _surveyMissionItemName) {
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, kmlFile, _visualItems);
    } else if (itemName == _structureScanMissionItemName) {
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, kmlFile, _visualItems);
    } else if (itemName == _corridorScanMissionItemName) {
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, kmlFile, _visualItems);
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return _nextSequenceNumber();
    }

    return _insertComplexMissionItemWorker(newItem, i);
}

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

450
    if (surveyStyleItem) {
451
        bool rollSupported  = false;
452
        bool pitchSupported = false;
453
        bool yawSupported   = false;
454 455 456

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

457 458
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
        CameraSection* cameraSection = settingsItem->cameraSection();
459

460
        // Set camera to photo mode (leave alone if user already specified)
461
        if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
462
            cameraSection->setSpecifyCameraMode(true);
463
            cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
464
        }
465

466
        // Point gimbal straight down
467
        if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
468 469 470
            // If the user already specified a gimbal angle leave it alone
            if (!cameraSection->specifyGimbal()) {
                cameraSection->setSpecifyGimbal(true);
471
                cameraSection->gimbalPitch()->setRawValue(-90.0);
472 473
            }
        }
474
    }
475

476 477
    complexItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(complexItem);
478

479 480 481 482 483
    if (i == -1) {
        _visualItems->append(complexItem);
    } else {
        _visualItems->insert(i, complexItem);
    }
484

485
    //-- Keep track of bounding box changes in complex items
486 487
    if(!complexItem->isSimpleItem()) {
        connect(complexItem, &ComplexMissionItem::boundingCubeChanged, this, &MissionController::_complexBoundingBoxChanged);
488
    }
489 490
    _recalcAll();

491
    return complexItem->sequenceNumber();
492 493
}

494 495
void MissionController::removeMissionItem(int index)
{
496 497 498 499 500
    if (index <= 0 || index >= _visualItems->count()) {
        qWarning() << "MissionController::removeMissionItem called with bad index - count:index" << _visualItems->count() << index;
        return;
    }

501
    bool removeSurveyStyle = _visualItems->value<SurveyComplexItem*>(index) || _visualItems->value<CorridorScanComplexItem*>(index);
502
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
503

504
    _deinitVisualItem(item);
505
    item->deleteLater();
506

507 508
    if (removeSurveyStyle) {
        // Determine if the mission still has another survey style item in it
509 510
        bool foundSurvey = false;
        for (int i=1; i<_visualItems->count(); i++) {
511
            if (_visualItems->value<SurveyComplexItem*>(i) || _visualItems->value<CorridorScanComplexItem*>(i)) {
512 513 514 515 516
                foundSurvey = true;
                break;
            }
        }

517
        // If there is no longer a survey item in the mission remove added commands
518 519 520 521
        if (!foundSurvey) {
            bool rollSupported = false;
            bool pitchSupported = false;
            bool yawSupported = false;
522 523
            MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
            CameraSection* cameraSection = settingsItem->cameraSection();
524
            if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
525
                if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
526 527 528
                    cameraSection->setSpecifyGimbal(false);
                }
            }
529
            if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
530 531
                cameraSection->setSpecifyCameraMode(false);
            }
532 533 534
        }
    }

535
    _recalcAll();
536
    setDirty(true);
537 538
}

539
void MissionController::removeAll(void)
540
{
541 542
    if (_visualItems) {
        _deinitAllVisualItems();
DonLakeFlyer's avatar
DonLakeFlyer committed
543
        _visualItems->clearAndDeleteContents();
Don Gagne's avatar
Don Gagne committed
544
        _visualItems->deleteLater();
545
        _settingsItem = NULL;
546
        _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
547
        _addMissionSettings(_visualItems, false /* addToCenter */);
548
        _initAllVisualItems();
549
        setDirty(true);
550
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
551 552 553
    }
}

554
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
555 556 557 558 559 560 561 562 563
{
    // 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)) {
564 565 566
        return false;
    }

567
    // Read complex items
568
    QList<SurveyComplexItem*> surveyItems;
569 570 571 572
    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];
573

574 575 576 577 578
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

579
        SurveyComplexItem* item = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems /* parent */);
Don Gagne's avatar
Don Gagne committed
580 581
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
582
            surveyItems.append(item);
583 584
        } else {
            return false;
585
        }
586
    }
587

588 589 590 591 592
    // 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
593
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
594

595
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
596 597 598 599
    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
600
        if (nextComplexItemIndex < surveyItems.count()) {
601
            SurveyComplexItem* complexItem = surveyItems[nextComplexItemIndex];
602 603 604 605 606 607 608 609 610 611 612 613 614 615

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

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

Don Gagne's avatar
Don Gagne committed
621
            const QJsonObject itemObject = itemValue.toObject();
622
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
Don Gagne's avatar
Don Gagne committed
623
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
624
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
625
                nextSequenceNumber = item->lastSequenceNumber() + 1;
626
                visualItems->append(item);
627 628 629 630
            } else {
                return false;
            }
        }
631
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
632 633

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

Don Gagne's avatar
Don Gagne committed
636
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
637
            MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
638 639 640
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
641 642 643 644
        } else {
            return false;
        }
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
645
        _addMissionSettings(visualItems, true /* addToCenter */);
646 647 648 649 650
    }

    return true;
}

651
bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
652 653 654 655 656 657
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
658
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
659 660
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
661 662 663 664 665 666 667
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

668
    // Mission Settings
669
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
670

671 672
    if (_masterController->offline()) {
        // We only update if offline since if we are online we use the online vehicle settings
673 674 675 676
        appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType((MAV_AUTOPILOT)json[_jsonFirmwareTypeKey].toInt()));
        if (json.contains(_jsonVehicleTypeKey)) {
            appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType((MAV_TYPE)json[_jsonVehicleTypeKey].toInt()));
        }
677
    }
678
    if (json.contains(_jsonCruiseSpeedKey)) {
679
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
680 681
    }
    if (json.contains(_jsonHoverSpeedKey)) {
682
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
683 684
    }

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

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

817 818 819 820 821 822 823 824
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;
825 826 827 828 829 830
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
831 832

    if (fileVersion == 1) {
833
        return _loadJsonMissionFileV1(json, visualItems, errorString);
834
    } else {
835
        return _loadJsonMissionFileV2(json, visualItems, errorString);
836 837 838
    }
}

839
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
840
{
841 842
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
843 844 845 846 847 848 849 850 851

    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;
852
            plannedHomePositionInFile = true;
853 854 855
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
856
            plannedHomePositionInFile = false;
857 858 859 860
        }
    }

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

865
        while (!stream.atEnd()) {
866
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
867 868

            if (item->load(stream)) {
869 870 871 872 873 874
                if (firstItem && plannedHomePositionInFile) {
                    settingsItem->setCoordinate(item->coordinate());
                } else {
                    visualItems->append(item);
                }
                firstItem = false;
875
            } else {
876
                errorString = tr("The mission file is corrupted.");
877 878 879 880
                return false;
            }
        }
    } else {
881
        errorString = tr("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
882 883 884
        return false;
    }

885
    if (!plannedHomePositionInFile) {
886 887 888
        // 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));
889
            if (item && item->command() == MAV_CMD_DO_JUMP) {
890
                item->missionItem().setParam1((int)item->missionItem().param1() + 1);
Don Gagne's avatar
Don Gagne committed
891 892
            }
        }
893 894 895
    }

    return true;
896 897
}

898
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
899
{
Don Gagne's avatar
Don Gagne committed
900 901 902
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
903
        _settingsItem = NULL;
Don Gagne's avatar
Don Gagne committed
904 905
    }

906
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
907 908

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

912
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
913

Don Gagne's avatar
Don Gagne committed
914
    _initAllVisualItems();
915
}
916

917 918 919 920 921 922
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

923
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948
        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;
949
    }
950

951 952 953 954 955 956 957 958 959 960 961 962 963
    _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);
964
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
965 966 967 968 969 970
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
971
    return true;
972 973
}

974 975 976 977 978 979 980 981 982 983 984 985
bool MissionController::readyForSaveSend(void) const
{
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        if (!visualItem->readyForSave()) {
            return false;
        }
    }

    return true;
}

986
void MissionController::save(QJsonObject& json)
987
{
988
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
989

990
    // Mission settings
991

992 993 994 995 996 997 998 999
    MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsItem";
        return;
    }
    QJsonValue coordinateValue;
    JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
    json[_jsonPlannedHomePositionKey] = coordinateValue;
1000 1001 1002 1003
    json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
1004

1005
    // Save the visual items
1006

1007 1008 1009
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1010

1011 1012
        visualItem->save(rgJsonMissionItems);
    }
1013

1014 1015 1016
    // Mission settings has a special case for end mission action
    if (settingsItem) {
        QList<MissionItem*> rgMissionItems;
1017

1018 1019 1020 1021 1022
        if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
1023
        }
1024 1025
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
1026 1027 1028
        }
    }

1029
    json[_jsonItemsKey] = rgJsonMissionItems;
1030 1031
}

1032
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
1033
{
Don Gagne's avatar
Don Gagne committed
1034
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
1035
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
1036 1037 1038 1039
    bool            distanceOk =    false;

    // Convert to fixed altitudes

1040
    distanceOk = true;
1041
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
1042 1043
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
1044
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
1045
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
1046 1047 1048
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
1049 1050 1051
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
1052
    } else {
Don Gagne's avatar
Don Gagne committed
1053
        *altDifference = 0.0;
1054
        *azimuth = 0.0;
1055
        *distance = 0.0;
1056 1057 1058
    }
}

1059
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
1060 1061 1062 1063 1064 1065 1066
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

1067
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
1068 1069
}

1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091
void MissionController::_addWaypointLineSegment(CoordVectHashTable& prevItemPairHashTable, VisualItemPair& pair)
{
    if (prevItemPairHashTable.contains(pair)) {
        // Pair already exists and connected, just re-use
        _linesTable[pair] = prevItemPairHashTable.take(pair);
    } else {
        // Create a new segment and wire update notifiers
        auto linevect       = new CoordinateVector(pair.first->isSimpleItem() ? pair.first->coordinate() : pair.first->exitCoordinate(), pair.second->coordinate(), this);
        auto originNotifier = pair.first->isSimpleItem() ? &VisualMissionItem::coordinateChanged : &VisualMissionItem::exitCoordinateChanged;
        auto endNotifier    = &VisualMissionItem::coordinateChanged;

        // Use signals/slots to update the coordinate endpoints
        connect(pair.first,     originNotifier, linevect, &CoordinateVector::setCoordinate1);
        connect(pair.second,    endNotifier,    linevect, &CoordinateVector::setCoordinate2);

        // FIXME: We should ideally have signals for 2D position change, alt change, and 3D position change
        // Not optimal, but still pretty fast, do a full update of range/bearing/altitudes
        connect(pair.second, &VisualMissionItem::coordinateChanged, this, &MissionController::_recalcMissionFlightStatus);
        _linesTable[pair] = linevect;
    }
}

1092 1093
void MissionController::_recalcWaypointLines(void)
{
1094 1095 1096
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

1097
    bool homePositionValid = _settingsItem->coordinate().isValid();
1098

1099
    qCDebug(MissionControllerLog) << "_recalcWaypointLines homePositionValid" << homePositionValid;
1100

Nate Weibley's avatar
Nate Weibley committed
1101 1102
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
1103
    _waypointLines.clear();
1104
    _waypointPath.clear();
1105

1106 1107 1108 1109 1110 1111 1112 1113 1114
    bool linkEndToHome;
    SimpleMissionItem* lastItem = _visualItems->value<SimpleMissionItem*>(_visualItems->count() - 1);
    if (lastItem && (int)lastItem->command() == MAV_CMD_NAV_RETURN_TO_LAUNCH) {
        linkEndToHome = true;
    } else {
        linkEndToHome = _settingsItem->missionEndRTL();
    }

    bool linkStartToHome = false;
1115 1116 1117
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));

1118 1119 1120 1121 1122 1123
        // If we still haven't found the first coordinate item and we hit a takeoff command this means the mission starts from the ground.
        // Link the first item back to home to show that.
        if (firstCoordinateItem && item->isSimpleItem()) {
            MAV_CMD command = (MAV_CMD)qobject_cast<SimpleMissionItem*>(item)->command();
            if (command == MAV_CMD_NAV_TAKEOFF || command == MAV_CMD_NAV_VTOL_TAKEOFF) {
                linkStartToHome = true;
1124
            }
1125 1126
        }

1127 1128 1129
        if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
            firstCoordinateItem = false;
            if (lastCoordinateItem != _settingsItem || (homePositionValid && linkStartToHome)) {
1130
                if (!_flyView) {
1131 1132
                    VisualItemPair pair(lastCoordinateItem, item);
                    _addWaypointLineSegment(old_table, pair);
1133 1134
                }
            }
1135 1136
            _waypointPath.append(QVariant::fromValue(item->coordinate()));
            lastCoordinateItem = item;
1137 1138
        }
    }
1139 1140 1141 1142 1143 1144

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

    if (linkEndToHome && lastCoordinateItem != _settingsItem && homePositionValid) {
1145
        if (!_flyView) {
1146 1147 1148 1149 1150
            VisualItemPair pair(lastCoordinateItem, _settingsItem);
            _addWaypointLineSegment(old_table, pair);
        } else {
            _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
        }
1151
    }
1152 1153 1154 1155

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1156 1157
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
1158 1159 1160 1161 1162 1163 1164 1165 1166 1167
            objs.append(vect);
        }

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

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1168
    _recalcMissionFlightStatus();
1169

1170 1171 1172 1173 1174 1175 1176 1177
    if (_waypointPath.count() == 0) {
        // MapPolyLine has a bug where if you can from a path which has elements to an empty path the line drawn
        // is not cleared from the map. This hack works around that since it causes the previous lines to be remove
        // as then doesn't draw anything on the map.
        _waypointPath.append(QVariant::fromValue(QGeoCoordinate(0, 0)));
        _waypointPath.append(QVariant::fromValue(QGeoCoordinate(0, 0)));
    }

1178
    emit waypointLinesChanged();
1179
    emit waypointPathChanged();
1180 1181
}

1182 1183 1184 1185 1186 1187
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);
1188 1189 1190
        // 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.
1191
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214
            _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);
}

1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241
/// 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
1242
void MissionController::_recalcMissionFlightStatus()
1243
{
1244
    if (!_visualItems->count()) {
1245
        return;
1246
    }
1247 1248 1249 1250

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

1251
    bool showHomePosition = _settingsItem->coordinate().isValid();
1252

DonLakeFlyer's avatar
DonLakeFlyer committed
1253
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1254

1255 1256 1257
    // 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.
1258

1259
    // No values for first item
1260
    lastCoordinateItem->setAltDifference(0.0);
1261
    lastCoordinateItem->setAzimuth(0.0);
1262
    lastCoordinateItem->setDistance(0.0);
1263

1264 1265
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1266 1267
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1268

1269
    _resetMissionFlightStatus();
1270

DonLakeFlyer's avatar
DonLakeFlyer committed
1271
    bool vtolInHover = true;
1272
    bool linkStartToHome = false;
1273 1274 1275 1276 1277 1278 1279 1280 1281 1282
    bool linkEndToHome = false;

    if (showHomePosition) {
        SimpleMissionItem* lastItem = _visualItems->value<SimpleMissionItem*>(_visualItems->count() - 1);
        if (lastItem && (int)lastItem->command() == MAV_CMD_NAV_RETURN_TO_LAUNCH) {
            linkEndToHome = true;
        } else {
            linkEndToHome = _settingsItem->missionEndRTL();
        }
    }
1283

DonLakeFlyer's avatar
DonLakeFlyer committed
1284
    for (int i=0; i<_visualItems->count(); i++) {
1285
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1286 1287 1288
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1289 1290
        // Assume the worst
        item->setAzimuth(0.0);
1291
        item->setDistance(0.0);
1292

DonLakeFlyer's avatar
DonLakeFlyer committed
1293 1294 1295
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1296
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1297
                _missionFlightStatus.hoverSpeed = newSpeed;
1298
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1299 1300
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1301
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1302
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1303
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1304 1305
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1306
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1307 1308 1309 1310
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1311 1312 1313 1314 1315 1316 1317
        double gimbalYaw = item->specifiedGimbalYaw();
        if (!qIsNaN(gimbalYaw)) {
            _missionFlightStatus.gimbalYaw = gimbalYaw;
        }
        double gimbalPitch = item->specifiedGimbalPitch();
        if (!qIsNaN(gimbalPitch)) {
            _missionFlightStatus.gimbalPitch = gimbalPitch;
DonLakeFlyer's avatar
DonLakeFlyer committed
1318 1319 1320 1321 1322
        }

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

1325
        // Link back to home if first item is takeoff and we have home position
1326
        if (firstCoordinateItem && simpleItem && (simpleItem->command() == MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
1327
            if (showHomePosition) {
1328
                linkStartToHome = true;
1329 1330 1331 1332 1333 1334 1335
                if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
                    // We have to special case takeoff, assuming vehicle takes off straight up to specified altitude
                    double azimuth, distance, altDifference;
                    _calcPrevWaypointValues(homePositionAltitude, _settingsItem, simpleItem, &azimuth, &distance, &altDifference);
                    double takeoffTime = qAbs(altDifference) / _appSettings->offlineEditingAscentSpeed()->rawValue().toDouble();
                    _addHoverTime(takeoffTime, 0, -1);
                }
1336 1337 1338 1339
            }
        }

        // Update VTOL state
1340
        if (simpleItem && _controllerVehicle->vtol()) {
1341
            switch (simpleItem->command()) {
1342
            case MAV_CMD_NAV_TAKEOFF:
1343 1344
                vtolInHover = false;
                break;
1345
            case MAV_CMD_NAV_VTOL_TAKEOFF:
DonLakeFlyer's avatar
DonLakeFlyer committed
1346 1347
                vtolInHover = true;
                break;
1348
            case MAV_CMD_NAV_LAND:
1349 1350
                vtolInHover = false;
                break;
1351
            case MAV_CMD_NAV_VTOL_LAND:
DonLakeFlyer's avatar
DonLakeFlyer committed
1352 1353
                vtolInHover = true;
                break;
1354
            case MAV_CMD_DO_VTOL_TRANSITION:
1355 1356 1357 1358 1359 1360
            {
                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;
1361 1362
                }
            }
1363 1364 1365
                break;
            default:
                break;
1366
            }
Don Gagne's avatar
Don Gagne committed
1367 1368
        }

1369
        _addTimeDistance(vtolInHover, 0, 0, item->additionalTimeDelay(), 0, -1);
1370

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

1374
            double absoluteAltitude = item->coordinate().altitude();
1375
            if (item->coordinateHasRelativeAltitude()) {
1376 1377 1378 1379 1380
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1381 1382 1383 1384
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1385 1386 1387
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1388
                firstCoordinateItem = false;
1389 1390 1391 1392 1393 1394 1395

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

1396
                if (lastCoordinateItem != _settingsItem || linkStartToHome) {
1397 1398
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1399

1400
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1401 1402 1403
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1404

1405
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1406

DonLakeFlyer's avatar
DonLakeFlyer committed
1407 1408 1409
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1410
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1411
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1412

1413
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1414 1415
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1416
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1417

1418 1419
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1420
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1421
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1422 1423

                item->setMissionFlightStatus(_missionFlightStatus);
1424

1425 1426
                lastCoordinateItem = item;
            }
1427 1428
        }
    }
1429
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1430

1431 1432 1433 1434 1435 1436 1437 1438
    if (linkEndToHome && lastCoordinateItem != _settingsItem) {
        double azimuth, distance, altDifference;
        _calcPrevWaypointValues(homePositionAltitude, lastCoordinateItem, _settingsItem, &azimuth, &distance, &altDifference);

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

1442 1443 1444
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1445

DonLakeFlyer's avatar
DonLakeFlyer committed
1446 1447 1448 1449 1450 1451 1452
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1453 1454
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1455

1456 1457
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1458 1459
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1460 1461 1462

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1463
            if (item->coordinateHasRelativeAltitude()) {
1464 1465 1466 1467
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1468
                item->setTerrainPercent(qQNaN());
1469 1470
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1471 1472 1473
                if (!qIsNaN(item->terrainAltitude())) {
                    item->setTerrainPercent((item->terrainAltitude() - minAltSeen) / altRange);
                }
1474
            }
1475 1476
        }
    }
1477 1478

    _updateTimer.start(UPDATE_TIMEOUT);
1479 1480
}

1481 1482 1483
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1484 1485 1486 1487 1488
    if (_inRecalcSequence) {
        // Don't let this call recurse due to signalling
        return;
    }

1489 1490
    // Setup ascending sequence numbers for all visual items

1491
    _inRecalcSequence = true;
1492 1493 1494
    int sequenceNumber = 0;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1495 1496
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1497 1498
    }    
    _inRecalcSequence = false;
1499 1500
}

1501 1502 1503
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1504
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1505 1506 1507

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

1508 1509
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1510 1511 1512 1513 1514

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1515
        } else if (item->isSimpleItem()) {
1516 1517 1518 1519 1520
            currentParentItem->childItems()->append(item);
        }
    }
}

1521 1522 1523 1524 1525 1526
void MissionController::_setPlannedHomePositionFromFirstCoordinate(void)
{
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1527
    // Set the planned home position to be a delta from first coordinate
1528 1529 1530 1531 1532 1533 1534 1535 1536 1537
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

        if (item->specifiesCoordinate()) {
            _settingsItem->setCoordinate(item->coordinate().atDistanceAndAzimuth(30, 0));
        }
    }
}


1538 1539
void MissionController::_recalcAll(void)
{
1540
    if (!_flyView) {
1541 1542
        _setPlannedHomePositionFromFirstCoordinate();
    }
1543
    _recalcSequence();
1544 1545
    _recalcChildItems();
    _recalcWaypointLines();
1546
    _updateTimer.start(UPDATE_TIMEOUT);
1547 1548
}

1549
/// Initializes a new set of mission items
1550
void MissionController::_initAllVisualItems(void)
1551
{
1552 1553
    // Setup home position at index 0

1554 1555 1556
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1557 1558
        return;
    }
1559
    if (!_flyView) {
1560 1561
        _settingsItem->setIsCurrentItem(true);
    }
1562

1563
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1564
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1565
    }
1566

1567 1568 1569
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1570

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

1576
    _recalcAll();
1577

1578
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1579 1580 1581
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1582
    emit containsItemsChanged(containsItems());
1583
    emit plannedHomePositionChanged(plannedHomePosition());
1584

1585
    setDirty(false);
1586 1587
}

1588
void MissionController::_deinitAllVisualItems(void)
1589
{
1590 1591 1592
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1593 1594
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1595 1596
    }

1597
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1598
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1599 1600
}

1601
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1602
{
1603
    setDirty(false);
1604

1605
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1606 1607
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1608 1609
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1610
    connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged,                this, &MissionController::_recalcMissionFlightStatus);
1611
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1612
    connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged,                 this, &MissionController::_recalcMissionFlightStatus);
1613
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1614

1615 1616 1617 1618 1619 1620 1621 1622
    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";
        }
1623 1624
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1625
        if (complexItem) {
1626
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
1627
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
1628 1629 1630
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1631
    }
1632 1633
}

1634
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1635
{
1636 1637
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1638 1639
}

1640
void MissionController::_itemCommandChanged(void)
1641
{
1642 1643
    _recalcChildItems();
    _recalcWaypointLines();
1644 1645
}

1646
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1647
{
1648 1649 1650 1651 1652 1653
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1654

1655 1656
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1657
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1658 1659
        return;
    }
1660

1661 1662
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1663 1664
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1665 1666 1667 1668 1669
    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);
1670
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1671 1672 1673 1674
    connect(_managerVehicle, &Vehicle::homePositionChanged,             this, &MissionController::_managerVehicleHomePositionChanged);
    connect(_managerVehicle, &Vehicle::defaultCruiseSpeedChanged,       this, &MissionController::_recalcMissionFlightStatus);
    connect(_managerVehicle, &Vehicle::defaultHoverSpeedChanged,        this, &MissionController::_recalcMissionFlightStatus);
    connect(_managerVehicle, &Vehicle::vehicleTypeChanged,              this, &MissionController::complexMissionItemNamesChanged);
1675

1676 1677
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1678
    }
1679

1680
    emit complexMissionItemNamesChanged();
1681
    emit resumeMissionIndexChanged();
1682 1683
}

1684
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1685
{
1686 1687
    if (_visualItems) {
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1688
        if (settingsItem) {
1689
            settingsItem->setHomePositionFromVehicle(homePosition);
1690
        } else {
1691
            qWarning() << "First item is not MissionSettingsItem";
1692
        }
1693 1694 1695
        // Don't let this trip the dirty bit. Otherwise plan will keep getting marked dirty if vehicle home
        // changes.
        _visualItems->setDirty(false);
1696
    }
1697 1698 1699
}

void MissionController::_inProgressChanged(bool inProgress)
1700
{
1701
    emit syncInProgressChanged(inProgress);
1702
}
1703

1704
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1705
{
1706 1707
    bool        found = false;
    double      foundAltitude;
1708
    int         foundAltitudeMode;
1709

1710 1711 1712 1713 1714 1715
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1718 1719 1720
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1721 1722 1723
                if (simpleItem->specifiesAltitude()) {
                    foundAltitude = simpleItem->altitude()->rawValue().toDouble();
                    foundAltitudeMode = simpleItem->altitudeMode();
1724
                    found = true;
1725
                    break;
1726 1727
                }
            }
1728 1729 1730
        }
    }

1731
    if (found) {
1732
        *prevAltitude = foundAltitude;
1733
        *prevAltitudeMode = foundAltitudeMode;
1734 1735 1736
    }

    return found;
1737
}
1738 1739 1740 1741 1742 1743 1744 1745 1746 1747 1748 1749 1750

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

1751
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1752
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1753
{
1754
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
1755

Don Gagne's avatar
Don Gagne committed
1756 1757
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1758
    visualItems->insert(0, settingsItem);
1759

1760 1761 1762 1763 1764 1765 1766 1767 1768 1769 1770 1771 1772 1773 1774 1775 1776 1777 1778 1779 1780 1781 1782 1783 1784
    if (addToCenter) {
        if (visualItems->count() > 1) {
            double north = 0.0;
            double south = 0.0;
            double east  = 0.0;
            double west  = 0.0;
            bool firstCoordSet = false;

            for (int i=1; i<visualItems->count(); i++) {
                VisualMissionItem* item = qobject_cast<VisualMissionItem*>(visualItems->get(i));
                if (item->specifiesCoordinate()) {
                    if (firstCoordSet) {
                        double lat = _normalizeLat(item->coordinate().latitude());
                        double lon = _normalizeLon(item->coordinate().longitude());
                        north = fmax(north, lat);
                        south = fmin(south, lat);
                        east  = fmax(east, lon);
                        west  = fmin(west, lon);
                    } else {
                        firstCoordSet = true;
                        north = _normalizeLat(item->coordinate().latitude());
                        south = north;
                        east  = _normalizeLon(item->coordinate().longitude());
                        west  = east;
                    }
1785 1786
                }
            }
1787

1788 1789 1790
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1791
        }
Don Gagne's avatar
Don Gagne committed
1792 1793
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1794 1795
    }
}
1796

1797
int MissionController::resumeMissionIndex(void) const
1798
{
1799

1800
    int resumeIndex = 0;
1801

1802
    if (_flyView) {
1803
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1804
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1805 1806
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1807 1808
        } else {
            resumeIndex = 0;
1809 1810 1811 1812 1813
        }
    }

    return resumeIndex;
}
1814

1815 1816
int MissionController::currentMissionIndex(void) const
{
1817
    if (!_flyView) {
1818 1819 1820 1821 1822 1823 1824 1825 1826 1827
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

1828
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1829
{
1830
    if (_flyView) {
1831
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1832 1833 1834
            sequenceNumber++;
        }

1835 1836
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1837 1838
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1839
        emit currentMissionIndexChanged(currentMissionIndex());
1840 1841
    }
}
1842

1843
bool MissionController::syncInProgress(void) const
1844
{
1845
    return _missionManager->inProgress();
1846 1847 1848 1849 1850 1851 1852 1853 1854 1855 1856 1857
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1858
    }
1859
}
1860

1861 1862
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1863 1864
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, vehicle);
1865

1866 1867 1868 1869 1870 1871
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1872
        if (!_flyView) {
1873 1874 1875 1876 1877 1878
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
1879 1880 1881
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1882
        if (simpleItem) {
1883 1884 1885 1886 1887
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
1888 1889 1890
        }
    }
}
1891 1892 1893 1894 1895 1896 1897 1898 1899 1900 1901 1902 1903

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
1904 1905 1906 1907 1908 1909 1910 1911
    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();
    }
1912
}
1913 1914 1915 1916 1917 1918

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

    complexItems.append(_surveyMissionItemName);
1919
    complexItems.append(_corridorScanMissionItemName);
1920
    if (_controllerVehicle->fixedWing()) {
1921 1922
        complexItems.append(_fwLandingMissionItemName);
    }
1923 1924 1925
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
        complexItems.append(_structureScanMissionItemName);
    }
1926 1927 1928

    return complexItems;
}
1929

1930 1931
void MissionController::resumeMission(int resumeIndex)
{
1932
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1933 1934
        resumeIndex--;
    }
1935
    _missionManager->generateResumeMission(resumeIndex);
1936
}
1937 1938 1939 1940 1941 1942 1943 1944 1945

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1946 1947 1948 1949 1950 1951 1952 1953 1954 1955

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

1957 1958 1959 1960 1961 1962 1963
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
1964 1965 1966 1967 1968 1969

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
1970 1971 1972

bool MissionController::showPlanFromManagerVehicle (void)
{
1973
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
DonLakeFlyer's avatar
DonLakeFlyer committed
1974 1975
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
1976
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
1977 1978 1979 1980 1981 1982 1983 1984 1985 1986 1987 1988 1989 1990 1991 1992 1993 1994 1995
    } 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;
        }
    }
}

1996
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1997
{
1998
    // Fly view always reloads on send complete
1999
    if (!error && _flyView) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2000 2001 2002 2003
        showPlanFromManagerVehicle();
    }
}

2004
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2005
{
2006 2007 2008 2009
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2010
}
2011 2012 2013 2014 2015 2016 2017 2018 2019 2020 2021 2022 2023 2024 2025 2026 2027 2028 2029 2030 2031 2032 2033 2034 2035 2036 2037 2038 2039 2040

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

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

void MissionController::setCurrentPlanViewIndex(int sequenceNumber, bool force)
{
    if(_visualItems && (force || sequenceNumber != _currentPlanViewIndex)) {
        _currentPlanViewItem  = NULL;
        _currentPlanViewIndex = -1;
        for (int i = 0; i < _visualItems->count(); i++) {
            VisualMissionItem* pVI = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
            if (pVI && pVI->sequenceNumber() == sequenceNumber) {
                pVI->setIsCurrentItem(true);
                _currentPlanViewItem  = pVI;
                _currentPlanViewIndex = sequenceNumber;
            } else {
                pVI->setIsCurrentItem(false);
            }
        }
        emit currentPlanViewIndexChanged();
        emit currentPlanViewItemChanged();
    }
}
2041 2042 2043

void MissionController::_updateTimeout()
{
Gus Grubba's avatar
Gus Grubba committed
2044
    QGeoCoordinate firstCoordinate;
2045
    QGeoCoordinate takeoffCoordinate;
2046
    QGCGeoBoundingCube boundingCube;
2047 2048 2049 2050
    double north = 0.0;
    double south = 180.0;
    double east  = 0.0;
    double west  = 360.0;
2051 2052
    double minAlt = QGCGeoBoundingCube::MaxAlt;
    double maxAlt = QGCGeoBoundingCube::MinAlt;
2053 2054 2055 2056 2057 2058
    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()) {
2059
                case MAV_CMD_NAV_TAKEOFF:
2060 2061 2062
                case MAV_CMD_NAV_WAYPOINT:
                case MAV_CMD_NAV_LAND:
                if(pSimpleItem->coordinate().isValid()) {
2063
                    if((MAV_CMD)pSimpleItem->command() == MAV_CMD_NAV_TAKEOFF) {
Gus Grubba's avatar
Gus Grubba committed
2064 2065 2066 2067
                        takeoffCoordinate = pSimpleItem->coordinate();
                    } else if(!firstCoordinate.isValid()) {
                        firstCoordinate = pSimpleItem->coordinate();
                    }
2068 2069
                    double lat = pSimpleItem->coordinate().latitude()  + 90.0;
                    double lon = pSimpleItem->coordinate().longitude() + 180.0;
2070
                    double alt = pSimpleItem->coordinate().altitude();
2071 2072 2073 2074
                    north  = fmax(north, lat);
                    south  = fmin(south, lat);
                    east   = fmax(east,  lon);
                    west   = fmin(west,  lon);
2075 2076
                    minAlt = fmin(minAlt, alt);
                    maxAlt = fmax(maxAlt, alt);
2077 2078 2079 2080 2081 2082 2083 2084 2085
                }
                break;
                default:
                    break;
                }
            }
        } else {
            ComplexMissionItem* pComplexItem = qobject_cast<ComplexMissionItem*>(item);
            if(pComplexItem) {
2086 2087
                QGCGeoBoundingCube bc = pComplexItem->boundingCube();
                if(bc.isValid()) {
Gus Grubba's avatar
Gus Grubba committed
2088 2089 2090
                    if(!firstCoordinate.isValid() && pComplexItem->coordinate().isValid()) {
                        firstCoordinate = pComplexItem->coordinate();
                    }
2091 2092 2093 2094 2095 2096
                    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());
2097 2098 2099 2100
                }
            }
        }
    }
Gus Grubba's avatar
Gus Grubba committed
2101 2102 2103 2104 2105 2106 2107 2108 2109
    //-- Figure out where this thing is taking off from
    if(!takeoffCoordinate.isValid()) {
        if(firstCoordinate.isValid()) {
            takeoffCoordinate = firstCoordinate;
        } else {
            takeoffCoordinate = plannedHomePosition();
        }
    }
    //-- Build bounding "cube"
2110 2111 2112
    boundingCube = QGCGeoBoundingCube(
        QGeoCoordinate(north - 90.0, west - 180.0, minAlt),
        QGeoCoordinate(south - 90.0, east - 180.0, maxAlt));
2113 2114
    if(_travelBoundingCube != boundingCube || _takeoffCoordinate != takeoffCoordinate) {
        _takeoffCoordinate  = takeoffCoordinate;
2115
        _travelBoundingCube = boundingCube;
2116
        emit missionBoundingCubeChanged();
2117
        qCDebug(MissionControllerLog) << "Bounding cube:" << _travelBoundingCube.pointNW << _travelBoundingCube.pointSE;
2118 2119 2120 2121 2122 2123 2124
    }
}

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