MissionController.cc 88.7 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
MissionController::MissionController(PlanMasterController* masterController, QObject *parent)
60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75
    : PlanElementController     (masterController, parent)
    , patternFWLandingName      (tr("Fixed Wing Landing"))
    , patternStructureScanName  (tr("Structure Scan"))
    , patternCorridorScanName   (tr("Corridor Scan"))
    , _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)
76
{
77
    _resetMissionFlightStatus();
78
    managerVehicleChanged(_managerVehicle);
79 80
    _updateTimer.setSingleShot(true);
    connect(&_updateTimer, &QTimer::timeout, this, &MissionController::_updateTimeout);
81 82 83 84
}

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

86 87
}

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

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

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

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

131 132
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

    return endActionSet;
}

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

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

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

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

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

    deleteParent->deleteLater();

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

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

335
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
336

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

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

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

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

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

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

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

396 397
    double  prevAltitude;
    int     prevAltitudeMode;
398

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

    _recalcAll();

    return newItem->sequenceNumber();
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

    return true;
}

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

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

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

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

690 691 692 693
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
694
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
695 696
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
697 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
    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) {
723
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
724
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
725
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
726
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
727 728 729 730 731 732 733 734 735 736 737 738 739
                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();

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

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

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

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

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

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

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

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

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

    return true;
901 902
}

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

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

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

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

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

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

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

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

    _initLoadedVisualItems(loadedVisualItems);

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

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

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

995
    // Mission settings
996

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

1010
    // Save the visual items
1011

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

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

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

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

1034
    json[_jsonItemsKey] = rgJsonMissionItems;
1035 1036
}

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

    // Convert to fixed altitudes

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

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

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

    distanceOk = true;

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1220 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
/// 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
1247
void MissionController::_recalcMissionFlightStatus()
1248
{
1249
    if (!_visualItems->count()) {
1250
        return;
1251
    }
1252 1253 1254 1255

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

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

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

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

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

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

1274
    _resetMissionFlightStatus();
1275

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

                item->setMissionFlightStatus(_missionFlightStatus);
1429

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

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

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

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

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

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

    _updateTimer.start(UPDATE_TIMEOUT);
1490 1491
}

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

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

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

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

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

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

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

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

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

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

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

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

1555 1556 1557 1558 1559 1560 1561 1562 1563
    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)
1564
{
1565
    if (!_flyView) {
1566
        _setPlannedHomePositionFromFirstCoordinate(clickCoordinate);
1567
    }
1568
    _recalcSequence();
1569 1570
    _recalcChildItems();
    _recalcWaypointLines();
1571
    _updateTimer.start(UPDATE_TIMEOUT);
1572 1573
}

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

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

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

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

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

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

1607
    _recalcAll();
1608

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

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

1616
    setDirty(false);
1617 1618
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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
    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;
                    }
1821 1822
                }
            }
1823

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

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

1836
    int resumeIndex = 0;
1837

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

    return resumeIndex;
}
1850

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

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

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

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

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


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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

2040
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2041
{
2042 2043 2044 2045
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2046
}
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

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

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

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