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


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

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

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

41 42
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

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

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

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

87 88
}

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

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

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

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

132 133
}

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

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

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

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

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

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

169 170 171
        _missionItemCount = newMissionItems.count();
        emit missionItemCountChanged(_missionItemCount);

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

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

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

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

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

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

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

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

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

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

265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280
    bool endActionSet = false;
    int lastSeqNum = 0;

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

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

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

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

    return endActionSet;
}

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

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

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

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

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

    deleteParent->deleteLater();

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

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

336
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
337

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

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

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

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

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

383
    return newItem->sequenceNumber();
384 385
}

386 387 388
int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
{
    int sequenceNumber = _nextSequenceNumber();
389
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
390
    newItem->setSequenceNumber(sequenceNumber);
391
    newItem->setCommand((_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_DO_SET_ROI_LOCATION) ?
392 393
        MAV_CMD_DO_SET_ROI_LOCATION :
        MAV_CMD_DO_SET_ROI));
394
    _initVisualItem(newItem);
395
    newItem->setCoordinate(coordinate);
396

397 398
    double  prevAltitude;
    int     prevAltitudeMode;
399

400 401
    if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
        newItem->altitude()->setRawValue(prevAltitude);
402
        newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
403 404 405 406 407 408 409 410
    }
    _visualItems->insert(i, newItem);

    _recalcAll();

    return newItem->sequenceNumber();
}

411
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
412
{
413 414
    ComplexMissionItem* newItem;

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

430 431 432
    return _insertComplexMissionItemWorker(newItem, i);
}

433
int MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int i)
434 435 436 437
{
    ComplexMissionItem* newItem;

    if (itemName == _surveyMissionItemName) {
438
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
439
    } else if (itemName == patternStructureScanName) {
440
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
441
    } else if (itemName == patternCorridorScanName) {
442
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
443 444 445 446 447 448 449 450 451 452 453 454 455
    } 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);

456
    if (surveyStyleItem) {
457
        bool rollSupported  = false;
458
        bool pitchSupported = false;
459
        bool yawSupported   = false;
460 461 462

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

463 464
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
        CameraSection* cameraSection = settingsItem->cameraSection();
465

466
        // Set camera to photo mode (leave alone if user already specified)
467
        if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
468
            cameraSection->setSpecifyCameraMode(true);
469
            cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
470
        }
471

472
        // Point gimbal straight down
473
        if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
474 475 476
            // If the user already specified a gimbal angle leave it alone
            if (!cameraSection->specifyGimbal()) {
                cameraSection->setSpecifyGimbal(true);
477
                cameraSection->gimbalPitch()->setRawValue(-90.0);
478 479
            }
        }
480
    }
481

482 483
    complexItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(complexItem);
484

485 486 487 488 489
    if (i == -1) {
        _visualItems->append(complexItem);
    } else {
        _visualItems->insert(i, complexItem);
    }
490

491
    //-- Keep track of bounding box changes in complex items
492 493
    if(!complexItem->isSimpleItem()) {
        connect(complexItem, &ComplexMissionItem::boundingCubeChanged, this, &MissionController::_complexBoundingBoxChanged);
494
    }
495 496
    _recalcAll();

497
    return complexItem->sequenceNumber();
498 499
}

500 501
void MissionController::removeMissionItem(int index)
{
502 503 504 505 506
    if (index <= 0 || index >= _visualItems->count()) {
        qWarning() << "MissionController::removeMissionItem called with bad index - count:index" << _visualItems->count() << index;
        return;
    }

507
    bool removeSurveyStyle = _visualItems->value<SurveyComplexItem*>(index) || _visualItems->value<CorridorScanComplexItem*>(index);
508
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
509

510
    _deinitVisualItem(item);
511
    item->deleteLater();
512

513 514
    if (removeSurveyStyle) {
        // Determine if the mission still has another survey style item in it
515 516
        bool foundSurvey = false;
        for (int i=1; i<_visualItems->count(); i++) {
517
            if (_visualItems->value<SurveyComplexItem*>(i) || _visualItems->value<CorridorScanComplexItem*>(i)) {
518 519 520 521 522
                foundSurvey = true;
                break;
            }
        }

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

541
    _recalcAll();
542
    setDirty(true);
543 544
}

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

560
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
561 562 563 564 565 566 567 568 569
{
    // 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)) {
570 571 572
        return false;
    }

573
    // Read complex items
574
    QList<SurveyComplexItem*> surveyItems;
575 576 577 578
    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];
579

580 581 582 583 584
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

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

594 595 596 597 598
    // 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
599
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
600

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

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

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

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

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

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

    return true;
}

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

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

674
    // Mission Settings
675
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
676

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

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

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

823 824 825 826 827 828 829 830
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;
831 832 833 834 835 836
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
837 838

    if (fileVersion == 1) {
839
        return _loadJsonMissionFileV1(json, visualItems, errorString);
840
    } else {
841
        return _loadJsonMissionFileV2(json, visualItems, errorString);
842 843 844
    }
}

845
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
846
{
847 848
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
849 850 851 852 853 854 855 856 857

    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;
858
            plannedHomePositionInFile = true;
859 860 861
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
862
            plannedHomePositionInFile = false;
863 864 865 866
        }
    }

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

871
        while (!stream.atEnd()) {
872
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
873 874

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

891
    if (!plannedHomePositionInFile) {
892 893 894
        // 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));
895
            if (item && item->command() == MAV_CMD_DO_JUMP) {
896
                item->missionItem().setParam1(static_cast<int>(item->missionItem().param1()) + 1);
Don Gagne's avatar
Don Gagne committed
897 898
            }
        }
899 900 901
    }

    return true;
902 903
}

904
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
905
{
Don Gagne's avatar
Don Gagne committed
906 907 908
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
909
        _settingsItem = nullptr;
Don Gagne's avatar
Don Gagne committed
910 911
    }

912
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
913 914

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

918
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
919

Don Gagne's avatar
Don Gagne committed
920
    _initAllVisualItems();
921
}
922

923 924 925 926 927 928
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

929
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954
        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;
955
    }
956

957 958 959 960 961 962 963 964 965 966 967 968 969
    _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);
970
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
971 972 973 974 975 976
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
977
    return true;
978 979
}

980 981 982 983 984 985 986 987 988 989 990 991
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;
}

992
void MissionController::save(QJsonObject& json)
993
{
994
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
995

996
    // Mission settings
997

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

1011
    // Save the visual items
1012

1013 1014 1015
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1016

1017 1018
        visualItem->save(rgJsonMissionItems);
    }
1019

1020 1021 1022
    // Mission settings has a special case for end mission action
    if (settingsItem) {
        QList<MissionItem*> rgMissionItems;
1023

1024 1025 1026 1027 1028
        if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
1029
        }
1030 1031
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
1032 1033 1034
        }
    }

1035
    json[_jsonItemsKey] = rgJsonMissionItems;
1036 1037
}

1038
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
1039
{
Don Gagne's avatar
Don Gagne committed
1040
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
1041
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
1042 1043 1044 1045
    bool            distanceOk =    false;

    // Convert to fixed altitudes

1046
    distanceOk = true;
1047
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
1048 1049
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
1050
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
1051
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
1052 1053 1054
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
1055 1056 1057
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
1058
    } else {
Don Gagne's avatar
Don Gagne committed
1059
        *altDifference = 0.0;
1060
        *azimuth = 0.0;
1061
        *distance = 0.0;
1062 1063 1064
    }
}

1065
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
1066 1067 1068 1069 1070 1071 1072
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

1073
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
1074 1075
}

1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097
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;
    }
}

1098 1099
void MissionController::_recalcWaypointLines(void)
{
1100 1101 1102
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

1103
    bool homePositionValid = _settingsItem->coordinate().isValid();
1104

1105
    qCDebug(MissionControllerLog) << "_recalcWaypointLines homePositionValid" << homePositionValid;
1106

Nate Weibley's avatar
Nate Weibley committed
1107 1108
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
1109
    _waypointLines.clear();
1110
    _waypointPath.clear();
1111

1112 1113 1114 1115 1116 1117 1118 1119 1120
    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;
1121 1122 1123
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));

1124 1125 1126 1127 1128 1129
        // 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;
1130
            }
1131 1132
        }

1133 1134 1135
        if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
            firstCoordinateItem = false;
            if (lastCoordinateItem != _settingsItem || (homePositionValid && linkStartToHome)) {
1136
                if (!_flyView) {
1137 1138
                    VisualItemPair pair(lastCoordinateItem, item);
                    _addWaypointLineSegment(old_table, pair);
1139 1140
                }
            }
1141 1142
            _waypointPath.append(QVariant::fromValue(item->coordinate()));
            lastCoordinateItem = item;
1143 1144
        }
    }
1145 1146 1147 1148 1149 1150

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

    if (linkEndToHome && lastCoordinateItem != _settingsItem && homePositionValid) {
1151
        if (!_flyView) {
1152 1153 1154 1155 1156
            VisualItemPair pair(lastCoordinateItem, _settingsItem);
            _addWaypointLineSegment(old_table, pair);
        } else {
            _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
        }
1157
    }
1158 1159 1160 1161

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1162
        objs.reserve(_linesTable.count());
1163
        for(CoordinateVector *vect: _linesTable.values()) {
1164 1165 1166 1167 1168 1169 1170 1171 1172 1173
            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
1174
    _recalcMissionFlightStatus();
1175

1176 1177 1178 1179 1180 1181 1182 1183
    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)));
    }

1184
    emit waypointLinesChanged();
1185
    emit waypointPathChanged();
1186 1187
}

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

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

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

1257
    bool showHomePosition = _settingsItem->coordinate().isValid();
1258

DonLakeFlyer's avatar
DonLakeFlyer committed
1259
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1260

1261 1262 1263
    // 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.
1264

1265
    // No values for first item
1266
    lastCoordinateItem->setAltDifference(0.0);
1267
    lastCoordinateItem->setAzimuth(0.0);
1268
    lastCoordinateItem->setDistance(0.0);
1269

1270 1271
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1272 1273
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1274

1275
    _resetMissionFlightStatus();
1276

DonLakeFlyer's avatar
DonLakeFlyer committed
1277
    bool vtolInHover = true;
1278
    bool linkStartToHome = false;
1279 1280 1281 1282 1283 1284 1285 1286 1287 1288
    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();
        }
    }
1289

DonLakeFlyer's avatar
DonLakeFlyer committed
1290
    for (int i=0; i<_visualItems->count(); i++) {
1291
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1292 1293 1294
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1295 1296
        // Assume the worst
        item->setAzimuth(0.0);
1297
        item->setDistance(0.0);
1298

DonLakeFlyer's avatar
DonLakeFlyer committed
1299 1300 1301
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1302
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1303
                _missionFlightStatus.hoverSpeed = newSpeed;
1304
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1305 1306
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1307
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1308
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1309
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1310 1311
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1312
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1313 1314 1315 1316
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1317 1318 1319 1320 1321 1322 1323
        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
1324 1325 1326 1327 1328
        }

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

1331
        // Link back to home if first item is takeoff and we have home position
1332
        if (firstCoordinateItem && simpleItem && (simpleItem->command() == MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
1333
            if (showHomePosition) {
1334
                linkStartToHome = true;
1335 1336 1337 1338 1339 1340 1341
                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);
                }
1342 1343 1344 1345
            }
        }

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

1375
        _addTimeDistance(vtolInHover, 0, 0, item->additionalTimeDelay(), 0, -1);
1376

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

1380
            double absoluteAltitude = item->coordinate().altitude();
1381
            if (item->coordinateHasRelativeAltitude()) {
1382 1383 1384 1385 1386
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1387 1388 1389 1390
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1391 1392 1393
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1394
                firstCoordinateItem = false;
1395 1396 1397 1398 1399 1400 1401

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

1402
                if (lastCoordinateItem != _settingsItem || linkStartToHome) {
1403 1404
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1405

1406
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1407 1408 1409
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1410

1411
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1412

DonLakeFlyer's avatar
DonLakeFlyer committed
1413 1414 1415
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1416
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1417
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1418

1419
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1420 1421
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1422
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1423

1424 1425
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1426
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1427
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1428 1429

                item->setMissionFlightStatus(_missionFlightStatus);
1430

1431 1432
                lastCoordinateItem = item;
            }
1433 1434
        }
    }
1435
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1436

1437 1438 1439 1440 1441 1442 1443 1444
    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();
1445
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1446 1447
    }

1448 1449 1450
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1451

DonLakeFlyer's avatar
DonLakeFlyer committed
1452 1453 1454 1455 1456 1457 1458
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1459 1460
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1461

1462 1463
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1464 1465
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1466 1467 1468

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1469
            if (item->coordinateHasRelativeAltitude()) {
1470 1471 1472 1473
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1474
                item->setTerrainPercent(qQNaN());
1475
                item->setTerrainCollision(false);
1476 1477
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1478 1479 1480 1481 1482 1483 1484
                double terrainAltitude = item->terrainAltitude();
                if (qIsNaN(terrainAltitude)) {
                    item->setTerrainPercent(qQNaN());
                    item->setTerrainCollision(false);
                } else {
                    item->setTerrainPercent((terrainAltitude - minAltSeen) / altRange);
                    item->setTerrainCollision(absoluteAltitude < terrainAltitude);
1485
                }
1486
            }
1487 1488
        }
    }
1489 1490

    _updateTimer.start(UPDATE_TIMEOUT);
1491 1492
}

1493 1494 1495
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1496 1497 1498 1499 1500
    if (_inRecalcSequence) {
        // Don't let this call recurse due to signalling
        return;
    }

1501 1502
    // Setup ascending sequence numbers for all visual items

1503
    _inRecalcSequence = true;
1504 1505 1506
    int sequenceNumber = 0;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1507 1508
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1509 1510
    }    
    _inRecalcSequence = false;
1511 1512
}

1513 1514 1515
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1516
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1517 1518 1519

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

1520 1521
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1522 1523 1524 1525 1526

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1527
        } else if (item->isSimpleItem()) {
1528 1529 1530 1531 1532
            currentParentItem->childItems()->append(item);
        }
    }
}

1533
void MissionController::_setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate)
1534
{
1535 1536
    QGeoCoordinate firstCoordinate;

1537 1538 1539 1540
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1541
    // Set the planned home position to be a delta from first coordinate
1542 1543 1544 1545
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

        if (item->specifiesCoordinate()) {
1546 1547
            firstCoordinate = item->coordinate();
            break;
1548 1549 1550
        }
    }

1551 1552 1553 1554
    // No item specifying a coordinate was found, in this case it we have a clickCoordinate use that
    if (!firstCoordinate.isValid()) {
        firstCoordinate = clickCoordinate;
    }
1555

1556 1557 1558 1559 1560 1561 1562 1563 1564
    if (firstCoordinate.isValid()) {
        QGeoCoordinate plannedHomeCoord = firstCoordinate.atDistanceAndAzimuth(30, 0);
        plannedHomeCoord.setAltitude(0);
        _settingsItem->setCoordinate(plannedHomeCoord);
    }
}

/// @param clickCoordinate The location of the user click when inserting a new item
void MissionController::_recalcAllWithClickCoordinate(QGeoCoordinate& clickCoordinate)
1565
{
1566
    if (!_flyView) {
1567
        _setPlannedHomePositionFromFirstCoordinate(clickCoordinate);
1568
    }
1569
    _recalcSequence();
1570 1571
    _recalcChildItems();
    _recalcWaypointLines();
1572
    _updateTimer.start(UPDATE_TIMEOUT);
1573 1574
}

1575 1576 1577 1578 1579 1580
void MissionController::_recalcAll(void)
{
    QGeoCoordinate emptyCoord;
    _recalcAllWithClickCoordinate(emptyCoord);
}

1581
/// Initializes a new set of mission items
1582
void MissionController::_initAllVisualItems(void)
1583
{
1584 1585
    // Setup home position at index 0

1586 1587 1588
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1589 1590
        return;
    }
1591
    if (!_flyView) {
1592 1593
        _settingsItem->setIsCurrentItem(true);
    }
1594

1595
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1596
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1597
    }
1598

1599 1600 1601
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1602

1603 1604 1605 1606
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1607

1608
    _recalcAll();
1609

1610
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1611 1612 1613
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1614
    emit containsItemsChanged(containsItems());
1615
    emit plannedHomePositionChanged(plannedHomePosition());
1616

1617
    setDirty(false);
1618 1619
}

1620
void MissionController::_deinitAllVisualItems(void)
1621
{
1622 1623 1624
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1625 1626
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1627 1628
    }

1629
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1630
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1631 1632
}

1633
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1634
{
1635
    setDirty(false);
1636

1637
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1638 1639
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1640 1641
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1642
    connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged,                this, &MissionController::_recalcMissionFlightStatus);
1643
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1644
    connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged,                 this, &MissionController::_recalcMissionFlightStatus);
1645
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1646

1647 1648 1649 1650 1651 1652 1653 1654
    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";
        }
1655 1656
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1657
        if (complexItem) {
1658
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
1659
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
1660 1661 1662
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1663
    }
1664 1665
}

1666
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1667
{
1668 1669
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1670 1671
}

1672
void MissionController::_itemCommandChanged(void)
1673
{
1674 1675
    _recalcChildItems();
    _recalcWaypointLines();
1676 1677
}

1678
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1679
{
1680 1681 1682 1683 1684 1685
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1686

1687 1688
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1689
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1690 1691
        return;
    }
1692

1693 1694
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1695 1696
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1697 1698 1699 1700 1701
    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);
1702
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1703 1704 1705 1706
    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);
1707

1708 1709
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1710
    }
1711

1712
    emit complexMissionItemNamesChanged();
1713
    emit resumeMissionIndexChanged();
1714 1715
}

1716
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1717
{
1718
    if (_visualItems) {
1719 1720
        bool currentDirtyBit = dirty();

1721
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1722
        if (settingsItem) {
1723
            settingsItem->setHomePositionFromVehicle(homePosition);
1724
        } else {
1725
            qWarning() << "First item is not MissionSettingsItem";
1726
        }
1727 1728 1729 1730 1731 1732

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

void MissionController::_inProgressChanged(bool inProgress)
1737
{
1738
    emit syncInProgressChanged(inProgress);
1739
}
1740

1741
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1742
{
1743 1744
    bool        found = false;
    double      foundAltitude;
1745
    int         foundAltitudeMode;
1746

1747 1748 1749 1750 1751 1752
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1755 1756 1757
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1758 1759 1760
                if (simpleItem->specifiesAltitude()) {
                    foundAltitude = simpleItem->altitude()->rawValue().toDouble();
                    foundAltitudeMode = simpleItem->altitudeMode();
1761
                    found = true;
1762
                    break;
1763 1764
                }
            }
1765 1766 1767
        }
    }

1768
    if (found) {
1769
        *prevAltitude = foundAltitude;
1770
        *prevAltitudeMode = foundAltitudeMode;
1771 1772 1773
    }

    return found;
1774
}
1775 1776 1777 1778 1779 1780 1781 1782 1783 1784 1785 1786 1787

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

1788
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1789
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1790
{
1791
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
1792

Don Gagne's avatar
Don Gagne committed
1793 1794
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1795
    visualItems->insert(0, settingsItem);
1796

1797 1798 1799 1800 1801 1802 1803 1804 1805 1806 1807 1808 1809 1810 1811 1812 1813 1814 1815 1816 1817 1818 1819 1820 1821
    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;
                    }
1822 1823
                }
            }
1824

1825 1826 1827
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1828
        }
Don Gagne's avatar
Don Gagne committed
1829 1830
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1831 1832
    }
}
1833

1834
int MissionController::resumeMissionIndex(void) const
1835
{
1836

1837
    int resumeIndex = 0;
1838

1839
    if (_flyView) {
1840
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1841
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1842 1843
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1844 1845
        } else {
            resumeIndex = 0;
1846 1847 1848 1849 1850
        }
    }

    return resumeIndex;
}
1851

1852 1853
int MissionController::currentMissionIndex(void) const
{
1854
    if (!_flyView) {
1855 1856 1857 1858 1859 1860 1861 1862 1863 1864
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

1865
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1866
{
1867
    if (_flyView) {
1868
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1869 1870 1871
            sequenceNumber++;
        }

1872 1873
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1874 1875
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1876
        emit currentMissionIndexChanged(currentMissionIndex());
1877 1878
    }
}
1879

1880
bool MissionController::syncInProgress(void) const
1881
{
1882
    return _missionManager->inProgress();
1883 1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1895
    }
1896
}
1897

1898 1899
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1900 1901
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, vehicle);
1902

1903 1904 1905 1906 1907 1908
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1909
        if (!_flyView) {
1910 1911 1912 1913 1914 1915
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
1916 1917 1918
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1919
        if (simpleItem) {
1920 1921 1922 1923 1924
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
1925 1926 1927
        }
    }
}
1928 1929 1930 1931 1932 1933 1934 1935 1936 1937 1938 1939 1940

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
1941 1942 1943 1944 1945 1946 1947 1948
    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();
    }
1949
}
1950 1951 1952 1953 1954 1955

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

    complexItems.append(_surveyMissionItemName);
1956
    complexItems.append(patternCorridorScanName);
1957
    if (_controllerVehicle->fixedWing()) {
1958
        complexItems.append(patternFWLandingName);
1959
    }
1960
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
1961
        complexItems.append(patternStructureScanName);
1962
    }
1963

1964
    return qgcApp()->toolbox()->corePlugin()->complexMissionItemNames(_controllerVehicle, complexItems);
1965
}
1966

1967 1968
void MissionController::resumeMission(int resumeIndex)
{
1969
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1970 1971
        resumeIndex--;
    }
1972
    _missionManager->generateResumeMission(resumeIndex);
1973
}
1974 1975 1976 1977 1978 1979 1980 1981 1982

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1983 1984 1985 1986 1987 1988 1989 1990 1991 1992

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

1994 1995 1996 1997 1998 1999 2000
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
2001 2002 2003 2004 2005 2006

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
2007 2008 2009

bool MissionController::showPlanFromManagerVehicle (void)
{
2010
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
DonLakeFlyer's avatar
DonLakeFlyer committed
2011 2012
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
2013
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
2014 2015 2016 2017 2018 2019 2020 2021 2022 2023 2024 2025 2026 2027 2028 2029 2030 2031 2032
    } 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;
        }
    }
}

2033
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2034
{
2035
    // Fly view always reloads on send complete
2036
    if (!error && _flyView) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2037 2038 2039 2040
        showPlanFromManagerVehicle();
    }
}

2041
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2042
{
2043 2044 2045 2046
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2047
}
2048 2049 2050 2051 2052 2053 2054 2055 2056 2057 2058 2059 2060 2061 2062 2063 2064 2065 2066 2067 2068 2069 2070 2071 2072 2073 2074 2075 2076 2077

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();
    }
}
2078 2079 2080

void MissionController::_updateTimeout()
{
Gus Grubba's avatar
Gus Grubba committed
2081
    QGeoCoordinate firstCoordinate;
2082
    QGeoCoordinate takeoffCoordinate;
2083
    QGCGeoBoundingCube boundingCube;
2084 2085 2086 2087
    double north = 0.0;
    double south = 180.0;
    double east  = 0.0;
    double west  = 360.0;
2088 2089
    double minAlt = QGCGeoBoundingCube::MaxAlt;
    double maxAlt = QGCGeoBoundingCube::MinAlt;
2090 2091 2092 2093 2094 2095
    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()) {
2096
                case MAV_CMD_NAV_TAKEOFF:
2097 2098 2099
                case MAV_CMD_NAV_WAYPOINT:
                case MAV_CMD_NAV_LAND:
                if(pSimpleItem->coordinate().isValid()) {
2100
                    if((MAV_CMD)pSimpleItem->command() == MAV_CMD_NAV_TAKEOFF) {
Gus Grubba's avatar
Gus Grubba committed
2101 2102 2103 2104
                        takeoffCoordinate = pSimpleItem->coordinate();
                    } else if(!firstCoordinate.isValid()) {
                        firstCoordinate = pSimpleItem->coordinate();
                    }
2105 2106
                    double lat = pSimpleItem->coordinate().latitude()  + 90.0;
                    double lon = pSimpleItem->coordinate().longitude() + 180.0;
2107
                    double alt = pSimpleItem->coordinate().altitude();
2108 2109 2110 2111
                    north  = fmax(north, lat);
                    south  = fmin(south, lat);
                    east   = fmax(east,  lon);
                    west   = fmin(west,  lon);
2112 2113
                    minAlt = fmin(minAlt, alt);
                    maxAlt = fmax(maxAlt, alt);
2114 2115 2116 2117 2118 2119 2120 2121 2122
                }
                break;
                default:
                    break;
                }
            }
        } else {
            ComplexMissionItem* pComplexItem = qobject_cast<ComplexMissionItem*>(item);
            if(pComplexItem) {
2123 2124
                QGCGeoBoundingCube bc = pComplexItem->boundingCube();
                if(bc.isValid()) {
Gus Grubba's avatar
Gus Grubba committed
2125 2126 2127
                    if(!firstCoordinate.isValid() && pComplexItem->coordinate().isValid()) {
                        firstCoordinate = pComplexItem->coordinate();
                    }
2128 2129 2130 2131 2132 2133
                    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());
2134 2135 2136 2137
                }
            }
        }
    }
Gus Grubba's avatar
Gus Grubba committed
2138 2139 2140 2141 2142 2143 2144 2145 2146
    //-- Figure out where this thing is taking off from
    if(!takeoffCoordinate.isValid()) {
        if(firstCoordinate.isValid()) {
            takeoffCoordinate = firstCoordinate;
        } else {
            takeoffCoordinate = plannedHomePosition();
        }
    }
    //-- Build bounding "cube"
2147 2148 2149
    boundingCube = QGCGeoBoundingCube(
        QGeoCoordinate(north - 90.0, west - 180.0, minAlt),
        QGeoCoordinate(south - 90.0, east - 180.0, maxAlt));
2150 2151
    if(_travelBoundingCube != boundingCube || _takeoffCoordinate != takeoffCoordinate) {
        _takeoffCoordinate  = takeoffCoordinate;
2152
        _travelBoundingCube = boundingCube;
2153
        emit missionBoundingCubeChanged();
2154
        qCDebug(MissionControllerLog) << "Bounding cube:" << _travelBoundingCube.pointNW << _travelBoundingCube.pointSE;
2155 2156 2157 2158 2159 2160 2161
    }
}

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