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

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

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

40 41
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

// Deprecated V1 format keys
const char* MissionController::_jsonComplexItemsKey =           "complexItems";
const char* MissionController::_jsonMavAutopilotKey =           "MAV_AUTOPILOT";

const int   MissionController::_missionFileVersion =            2;
57

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

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

85 86
}

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

    // Battery information

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

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

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

130 131
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

223 224 225 226 227 228 229 230 231 232 233
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;
        }
    }
}

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

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

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

    return endActionSet;
}

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

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

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

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

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

    deleteParent->deleteLater();

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

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

334
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
335

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

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

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

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

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

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

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

395 396
    double  prevAltitude;
    int     prevAltitudeMode;
397

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

    _recalcAll();

    return newItem->sequenceNumber();
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

    return true;
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

    return true;
900 901
}

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

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

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

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

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

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

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

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

    _initLoadedVisualItems(loadedVisualItems);

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

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

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

994
    // Mission settings
995

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

1009
    // Save the visual items
1010

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

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

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

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

1033
    json[_jsonItemsKey] = rgJsonMissionItems;
1034 1035
}

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

    // Convert to fixed altitudes

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

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

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

    distanceOk = true;

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1273
    _resetMissionFlightStatus();
1274

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

                item->setMissionFlightStatus(_missionFlightStatus);
1428

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

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

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

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

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

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

    _updateTimer.start(UPDATE_TIMEOUT);
1489 1490
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1606
    _recalcAll();
1607

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

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

1615
    setDirty(false);
1616 1617
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1835
    int resumeIndex = 0;
1836

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

    return resumeIndex;
}
1849

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

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

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

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

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


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

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

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

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

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

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

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

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

    complexItems.append(_surveyMissionItemName);
1954
    complexItems.append(_corridorScanMissionItemName);
1955
    if (_controllerVehicle->fixedWing()) {
1956 1957
        complexItems.append(_fwLandingMissionItemName);
    }
1958 1959 1960
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
        complexItems.append(_structureScanMissionItemName);
    }
1961 1962 1963

    return complexItems;
}
1964

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

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

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

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

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

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

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

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

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

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

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