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


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

34 35
#include "src/Wima/CircularSurveyComplexItem.h"

36
#ifndef __mobile__
37
#include "MainWindow.h"
38
#include "QGCQFileDialog.h"
39 40
#endif

41
#define UPDATE_TIMEOUT 5000 ///< How often we check for bounding box changes
42
#define REMAINING_DIST_TIME_UPDATE_INTERVAL 300 ///< How often we check for bounding box changes
43

44 45
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

62 63 64
const QString MissionController::patternFWLandingName      (QT_TRANSLATE_NOOP("MissionController", "Fixed Wing Landing"));
const QString MissionController::patternStructureScanName  (QT_TRANSLATE_NOOP("MissionController", "Structure Scan"));
const QString MissionController::patternCorridorScanName   (QT_TRANSLATE_NOOP("MissionController", "Corridor Scan"));
65

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

89
    _remainingDistanceTimeTimer.setInterval(REMAINING_DIST_TIME_UPDATE_INTERVAL);
90
    connect(&_remainingDistanceTimeTimer, &QTimer::timeout, this, &MissionController::_updateRemainingDistanceTime);
91 92 93 94
}

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

96 97
}

98 99 100 101 102 103 104 105 106
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;
107 108 109
    _missionFlightStatus.cruiseSpeed =          _controllerVehicle->defaultCruiseSpeed();
    _missionFlightStatus.hoverSpeed =           _controllerVehicle->defaultHoverSpeed();
    _missionFlightStatus.vehicleSpeed =         _controllerVehicle->multiRotor() || _managerVehicle->vtol() ? _missionFlightStatus.hoverSpeed : _missionFlightStatus.cruiseSpeed;
110
    _missionFlightStatus.vehicleYaw =           0.0;
111
    _missionFlightStatus.gimbalYaw =            std::numeric_limits<double>::quiet_NaN();
112
    _missionFlightStatus.gimbalPitch =          std::numeric_limits<double>::quiet_NaN();
113 114 115 116 117 118 119 120 121 122 123 124

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

125 126 127
    _controllerVehicle->firmwarePlugin()->batteryConsumptionData(_controllerVehicle, _missionFlightStatus.mAhBattery, _missionFlightStatus.hoverAmps, _missionFlightStatus.cruiseAmps);
    if (_missionFlightStatus.mAhBattery != 0) {
        double batteryPercentRemainingAnnounce = qgcApp()->toolbox()->settingsManager()->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toDouble();
128
        _missionFlightStatus.ampMinutesAvailable = static_cast<double>(_missionFlightStatus.mAhBattery) / 1000.0 * 60.0 * ((100.0 - batteryPercentRemainingAnnounce) / 100.0);
129
    }
130 131 132 133 134 135 136 137 138 139 140

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

141 142
}

143
void MissionController::start(bool flyView)
144
{
145
    qCDebug(MissionControllerLog) << "start flyView" << flyView;
146

147
    PlanElementController::start(flyView);
148 149 150 151 152
    _init();
}

void MissionController::_init(void)
{
153
    // We start with an empty mission
154
    _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
155
    _addMissionSettings(_visualItems, false /* addToCenter */);
156
    _initAllVisualItems();
157 158
}

159
// Called when new mission items have completed downloading from Vehicle
160
void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllRequested)
161
{
162
    qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle flyView:count" << _flyView << _missionManager->missionItems().count();
163

DonLakeFlyer's avatar
DonLakeFlyer committed
164 165
    // Fly view always reloads on _loadComplete
    // Plan view only reloads on _loadComplete if specifically requested
166
    if (_flyView || removeAllRequested || _itemsRequested || _visualItems->count() <= 1) {
167
        // Fly Mode (accept if):
Don Gagne's avatar
Don Gagne committed
168
        //      - Always accepts new items from the vehicle so Fly view is kept up to date
169
        // Edit Mode (accept if):
170 171
        //      - 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
172
        //      - The initial automatic load from a vehicle completed and the current editor is empty
173

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

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

181
        int i = 0;
182
        if (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() && newMissionItems.count() != 0) {
183
            // First item is fake home position
DonLakeFlyer's avatar
DonLakeFlyer committed
184
            _addMissionSettings(newControllerMissionItems, false /* addToCenter */);
185
            MissionSettingsItem* settingsItem = newControllerMissionItems->value<MissionSettingsItem*>(0);
186 187 188 189
            if (!settingsItem) {
                qWarning() << "First item is not settings item";
                return;
            }
190 191 192 193
            MissionItem* fakeHomeItem = newMissionItems[0];
            if (fakeHomeItem->coordinate().latitude() != 0 || fakeHomeItem->coordinate().longitude() != 0) {
                settingsItem->setCoordinate(fakeHomeItem->coordinate());
            }
194 195
            i = 1;
        }
196

197
        for (; i < newMissionItems.count(); i++) {
198
            const MissionItem* missionItem = newMissionItems[i];
199
            newControllerMissionItems->append(new SimpleMissionItem(_controllerVehicle, _flyView, *missionItem, this));
200 201 202
        }

        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
203
        _visualItems->deleteLater();
204 205
        _settingsItem = nullptr;
        _visualItems  = nullptr;
206
        _updateContainsItems(); // This will clear containsItems which will be set again below. This will re-pop Start Mission confirmation.
207 208
        _visualItems = newControllerMissionItems;

209
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
210
            _addMissionSettings(_visualItems, !_flyView && _visualItems->count() > 0 /* addToCenter */);
211 212
        }

213
        MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
214

215
        _initAllVisualItems();
216
        _updateContainsItems();
217
        emit newItemsFromVehicle();
218
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
219
    _itemsRequested = false;
220 221
}

222
void MissionController::loadFromVehicle(void)
223
{
DonLakeFlyer's avatar
DonLakeFlyer committed
224 225 226 227 228 229 230 231
    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();
    }
232 233
}

234 235 236 237
void MissionController::_warnIfTerrainFrameUsed(void)
{
    for (int i=1; i<_visualItems->count(); i++) {
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(i));
238
        if (simpleItem && simpleItem->altitudeMode() == QGroundControlQmlGlobal::AltitudeModeTerrainFrame) {
239 240 241 242 243 244
            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;
        }
    }
}

245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262
void MissionController::_setRemainingDistance(double dist)
{
    if (qFuzzyCompare(dist, _remainingDistance) == false) {
        _remainingDistance = dist;

        emit remainingDistanceChanged();
    }
}

void MissionController::_setRemainingTime(double time)
{
    if (qFuzzyCompare(time, _remainingTime) == false) {
        _remainingTime = time;

        emit remainingTimeChanged();
    }
}

263
void MissionController::sendToVehicle(void)
264
{
DonLakeFlyer's avatar
DonLakeFlyer committed
265 266 267 268 269
    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
270
        qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
271
        _warnIfTerrainFrameUsed();
DonLakeFlyer's avatar
DonLakeFlyer committed
272 273 274 275 276 277 278 279 280
        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
281 282
}

283
/// Converts from visual items to MissionItems
284
///     @param missionItemParent QObject parent for newly allocated MissionItems, _surveyMissionItemName    (tr("Survey"))
285
/// @return true: Mission end action was added to end of list
286
bool MissionController::convertToMissionItems(QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent)
287
{
DonLakeFlyer's avatar
DonLakeFlyer committed
288 289 290 291
    if (visualMissionItems->count() == 0) {
        return false;
    }

292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307
    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
308
    MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
309 310 311 312 313 314 315
    if (settingsItem) {
        endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
    }

    return endActionSet;
}

316 317
void MissionController::convertToKMLDocument(QDomDocument& document)
{
318 319
    QObject*            deleteParent = new QObject();
    QList<MissionItem*> rgMissionItems;
320

321
    convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
322
    if (rgMissionItems.count() == 0) {
323 324
        return;
    }
325

326
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
327 328 329 330 331

    QString coord;
    QStringList coords;
    // Drop home position
    bool dropPoint = true;
332
    for(const auto& item : rgMissionItems) {
333 334 335 336 337
        if(dropPoint) {
            dropPoint = false;
            continue;
        }
        const MissionCommandUIInfo* uiInfo = \
338
                qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, item->command());
339 340

        if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
341
            double amslAltitude = item->param7() + (item->frame() == MAV_FRAME_GLOBAL ? 0 : homePositionAltitude);
yaoling's avatar
yaoling committed
342
            coord = QString::number(item->param6(),'f',7) \
343 344 345
                    + "," \
                    + QString::number(item->param5(),'f',7) \
                    + "," \
346
                    + QString::number(amslAltitude,'f',2);
347 348 349
            coords.append(coord);
        }
    }
350 351 352

    deleteParent->deleteLater();

353 354 355 356 357
    Kml kml;
    kml.points(coords);
    kml.save(document);
}

Don Gagne's avatar
Don Gagne committed
358 359 360
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
361
        QList<MissionItem*> rgMissionItems;
362

363
        convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
364

365
        // PlanManager takes control of MissionItems so no need to delete
366
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
367 368
    }
}
369

370 371 372 373 374 375
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
376 377
        VisualMissionItem* lastItem = _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1);
        return lastItem->lastSequenceNumber() + 1;
378 379 380
    }
}

381
int MissionController::insertSimpleMissionItem(const QGeoCoordinate &coordinate, int i)
382
{
383
    int sequenceNumber = _nextSequenceNumber();
384
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
385
    newItem->setSequenceNumber(sequenceNumber);
386
    newItem->setCoordinate(coordinate);
387
    newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
388
    _initVisualItem(newItem);
389
    if (_visualItems->count() == 1 && (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() || _controllerVehicle->multiRotor())) {
390
        MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
391
        if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) {
392 393
            newItem->setCommand(takeoffCmd);
        }
394
    }
395 396 397
    if (newItem->specifiesAltitude()) {
        double  prevAltitude;
        int     prevAltitudeMode;
398

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

407 408
    // 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);
409

410
    return newItem->sequenceNumber();
411 412
}

413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464
int MissionController::insertSimpleMissionItems(const QList<QGeoCoordinate> &coordinates, int idx)
{
    MAV_CMD mavCmd = MAV_CMD_NAV_WAYPOINT;
    if (    _visualItems->count() == 1
        && (   _controllerVehicle->fixedWing()
            || _controllerVehicle->vtol()
            || _controllerVehicle->multiRotor()) )
    {
        mavCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
        if ( !_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(mavCmd)) {
            mavCmd = MAV_CMD_NAV_WAYPOINT;
        }
    }

    int sequenceNumber = _nextSequenceNumber();
    int size = coordinates.size();

    SimpleMissionItem *newItem = nullptr;
    bool firstItem = true;
    double prevAltitude = 0.0;
    int prevAltitudeMode = 0;
    for (int i = 0; i < size; ++i) {
        newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
        newItem->setSequenceNumber(sequenceNumber);
        newItem->setCoordinate(coordinates[i]);
        newItem->setCommand(mavCmd);
        _initSimpleItem(newItem);
        if (!firstItem || (  newItem->specifiesAltitude()
                           && _findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) )
        {
            newItem->altitude()->setRawValue(prevAltitude);
            newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
        }
        newItem->setMissionFlightStatus(_missionFlightStatus);
        _visualItems->insert(idx++, newItem);
        sequenceNumber = newItem->lastSequenceNumber() + 1;
        mavCmd  = MAV_CMD_NAV_WAYPOINT;
        firstItem = false;
    }


    _recalcSequence();
    _recalcChildItems();
    _recalcWaypointLines();
    _updateTimer.start(UPDATE_TIMEOUT);

    if ( newItem == nullptr)
        return -1;
    return newItem->sequenceNumber();

}

465 466 467 468 469 470 471 472 473
int MissionController::insertSimpleMissionItem(const MissionItem &missionItem, int i)
{
    int sequenceNumber = _nextSequenceNumber();
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, missionItem, this);
    newItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(newItem);
    MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
    if (newItem->command() ==  takeoffCmd) {
        if (!_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) {
474
            newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
475 476 477
            return -1; // can not add this takeoff command for this vehicle
        }
    }
478 479 480 481 482 483
    if (newItem->specifiesAltitude()) {        
        newItem->altitude()->setRawValue(missionItem.relativeAltitude());
        newItem->setAltitudeMode(QGroundControlQmlGlobal::AltitudeMode::AltitudeModeRelative);
    }
    newItem->setMissionFlightStatus(_missionFlightStatus);
    _visualItems->insert(i, newItem);
484

485 486 487
    return newItem->sequenceNumber();
}

488
int MissionController::insertSimpleMissionItem(const SimpleMissionItem &missionItem, int i)
489 490 491 492 493 494 495 496 497 498
{
    int sequenceNumber = _nextSequenceNumber();
    SimpleMissionItem * newItem = new SimpleMissionItem(missionItem, _flyView, this);
    newItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(newItem);
    MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
    if (newItem->command() ==  takeoffCmd) {
        if (!_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) {
            newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
            return -1; // can not add this takeoff command for this vehicle
499 500
        }
    }
Valentin Platzgummer's avatar
Valentin Platzgummer committed
501
    newItem->setMissionFlightStatus(_missionFlightStatus);
502 503 504
    _visualItems->insert(i, newItem);

    return newItem->sequenceNumber();
505
}
506

507 508 509
int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
{
    int sequenceNumber = _nextSequenceNumber();
510
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
511
    newItem->setSequenceNumber(sequenceNumber);
512
    newItem->setCommand((_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_DO_SET_ROI_LOCATION) ?
513 514
        MAV_CMD_DO_SET_ROI_LOCATION :
        MAV_CMD_DO_SET_ROI));
515
    _initVisualItem(newItem);
516
    newItem->setCoordinate(coordinate);
517

518 519
    double  prevAltitude;
    int     prevAltitudeMode;
520

521 522
    if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
        newItem->altitude()->setRawValue(prevAltitude);
523
        newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
524 525 526 527 528 529 530 531
    }
    _visualItems->insert(i, newItem);

    _recalcAll();

    return newItem->sequenceNumber();
}

532
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
533
{
534 535
    ComplexMissionItem* newItem;

536
    int sequenceNumber = _nextSequenceNumber();
537
    if (itemName == _surveyMissionItemName) {
538
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
539
        newItem->setCoordinate(mapCenterCoordinate);
540
    } else if (itemName == patternFWLandingName) {
541
        newItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, _visualItems /* parent */);
542
    } else if (itemName == patternStructureScanName) {
543
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
544
    } else if (itemName == patternCorridorScanName) {
545
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
546 547
    } else if (itemName == _circularSurveyMissionItemName) {
        newItem = new CircularSurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
548 549 550 551 552
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }

553 554 555
    return _insertComplexMissionItemWorker(newItem, i);
}

556
int MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int i)
557 558 559 560
{
    ComplexMissionItem* newItem;

    if (itemName == _surveyMissionItemName) {
561
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
562 563
    } else if (itemName == _circularSurveyMissionItemName) {
        newItem = new CircularSurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
564
    } else if (itemName == patternStructureScanName) {
565
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
566
    } else if (itemName == patternCorridorScanName) {
567
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
568 569 570 571 572 573 574 575 576 577 578
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return _nextSequenceNumber();
    }

    return _insertComplexMissionItemWorker(newItem, i);
}

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

583
    if (surveyStyleItem) {
584
        bool rollSupported  = false;
585
        bool pitchSupported = false;
586
        bool yawSupported   = false;
587 588 589

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

590 591
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
        CameraSection* cameraSection = settingsItem->cameraSection();
592

593
        // Set camera to photo mode (leave alone if user already specified)
594
        if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
595
            cameraSection->setSpecifyCameraMode(true);
596
            cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
597
        }
598

599
        // Point gimbal straight down
600
        if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
601 602 603
            // If the user already specified a gimbal angle leave it alone
            if (!cameraSection->specifyGimbal()) {
                cameraSection->setSpecifyGimbal(true);
604
                cameraSection->gimbalPitch()->setRawValue(-90.0);
605 606
            }
        }
607
    }
608

609 610
    complexItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(complexItem);
611

612 613 614 615 616
    if (i == -1) {
        _visualItems->append(complexItem);
    } else {
        _visualItems->insert(i, complexItem);
    }
617

618
    //-- Keep track of bounding box changes in complex items
619 620
    if(!complexItem->isSimpleItem()) {
        connect(complexItem, &ComplexMissionItem::boundingCubeChanged, this, &MissionController::_complexBoundingBoxChanged);
621
    }
622 623
    _recalcAll();

624
    return complexItem->sequenceNumber();
625 626
}

627 628
void MissionController::removeMissionItem(int index)
{
629 630 631 632 633
    if (index <= 0 || index >= _visualItems->count()) {
        qWarning() << "MissionController::removeMissionItem called with bad index - count:index" << _visualItems->count() << index;
        return;
    }

634 635 636
    bool removeSurveyStyle =    _visualItems->value<SurveyComplexItem*>(index)
                             || _visualItems->value<CorridorScanComplexItem*>(index)
                             || _visualItems->value<CircularSurveyComplexItem*>(index);
637
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
638

639
    _deinitVisualItem(item);
640
    item->deleteLater();
641

642 643
    if (removeSurveyStyle) {
        // Determine if the mission still has another survey style item in it
644 645
        bool foundSurvey = false;
        for (int i=1; i<_visualItems->count(); i++) {
646 647 648
            if (    _visualItems->value<SurveyComplexItem*>(i)
                 || _visualItems->value<CorridorScanComplexItem*>(i)
                 || _visualItems->value<CircularSurveyComplexItem*>(i)) {
649 650 651 652 653
                foundSurvey = true;
                break;
            }
        }

654
        // If there is no longer a survey item in the mission remove added commands
655 656 657 658
        if (!foundSurvey) {
            bool rollSupported = false;
            bool pitchSupported = false;
            bool yawSupported = false;
659 660
            MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
            CameraSection* cameraSection = settingsItem->cameraSection();
661
            if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
662
                if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
663 664 665
                    cameraSection->setSpecifyGimbal(false);
                }
            }
666
            if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
667 668
                cameraSection->setSpecifyCameraMode(false);
            }
669 670 671
        }
    }

672
    _recalcAll();
673
    setDirty(true);
674 675
}

676
void MissionController::removeAll(void)
677
{
678 679
    if (_visualItems) {
        _deinitAllVisualItems();
DonLakeFlyer's avatar
DonLakeFlyer committed
680
        _visualItems->clearAndDeleteContents();
Don Gagne's avatar
Don Gagne committed
681
        _visualItems->deleteLater();
682
        _settingsItem = nullptr;
683
        _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
684
        _addMissionSettings(_visualItems, false /* addToCenter */);
685
        _initAllVisualItems();
686
        setDirty(true);
687
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
688 689 690
    }
}

691
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
692 693 694 695 696 697 698 699 700
{
    // 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)) {
701 702 703
        return false;
    }

704
    // Read complex items
705
    QList<SurveyComplexItem*> surveyItems;
706 707 708 709
    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];
710

711 712 713 714 715
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

716
        SurveyComplexItem* item = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems /* parent */);
Don Gagne's avatar
Don Gagne committed
717 718
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
719
            surveyItems.append(item);
720 721
        } else {
            return false;
722
        }
723
    }
724

725 726 727 728 729
    // 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
730
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
731

732
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
733 734 735 736
    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
737
        if (nextComplexItemIndex < surveyItems.count()) {
738
            SurveyComplexItem* complexItem = surveyItems[nextComplexItemIndex];
739 740 741 742 743 744 745 746 747 748 749 750 751 752

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

753 754 755 756 757
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
758
            const QJsonObject itemObject = itemValue.toObject();
759
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
Don Gagne's avatar
Don Gagne committed
760
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
761
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
762
                nextSequenceNumber = item->lastSequenceNumber() + 1;
763
                visualItems->append(item);
764 765 766 767
            } else {
                return false;
            }
        }
768
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
769 770

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

Don Gagne's avatar
Don Gagne committed
773
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
774
            MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
775 776 777
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
778 779 780 781
        } else {
            return false;
        }
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
782
        _addMissionSettings(visualItems, true /* addToCenter */);
783 784 785 786 787
    }

    return true;
}

788
bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
789 790 791 792 793 794
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
795
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
796 797
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
798 799 800 801 802 803 804
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

805
    // Mission Settings
806
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
807

808 809
    if (_masterController->offline()) {
        // We only update if offline since if we are online we use the online vehicle settings
810
        appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType(static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt())));
811
        if (json.contains(_jsonVehicleTypeKey)) {
812
            appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType(static_cast<MAV_TYPE>(json[_jsonVehicleTypeKey].toInt())));
813
        }
814
    }
815
    if (json.contains(_jsonCruiseSpeedKey)) {
816
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
817 818
    }
    if (json.contains(_jsonHoverSpeedKey)) {
819
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
820 821
    }

822 823 824 825
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
826
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
827 828
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854
    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) {
855
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
856
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
857
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
858
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
859 860 861 862 863 864 865 866 867 868 869 870 871
                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();

872
            if (complexItemType == SurveyComplexItem::jsonComplexItemTypeValue) {
Don Gagne's avatar
Don Gagne committed
873
                qCDebug(MissionControllerLog) << "Loading Survey: nextSequenceNumber" << nextSequenceNumber;
874
                SurveyComplexItem* surveyItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
Don Gagne's avatar
Don Gagne committed
875 876 877 878 879 880
                if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(surveyItem);
881
            } else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
882
                qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
883
                FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
884 885 886 887 888 889
                if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(landingItem);
890 891
            } else if (complexItemType == StructureScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Structure Scan: nextSequenceNumber" << nextSequenceNumber;
892
                StructureScanComplexItem* structureItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
893 894 895 896 897 898
                if (!structureItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = structureItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Structure Scan load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(structureItem);
899 900
            } else if (complexItemType == CorridorScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Corridor Scan: nextSequenceNumber" << nextSequenceNumber;
901
                CorridorScanComplexItem* corridorItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
902 903 904 905 906 907
                if (!corridorItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = corridorItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Corridor Scan load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(corridorItem);
Valentin Platzgummer's avatar
Valentin Platzgummer committed
908 909 910 911 912 913 914 915 916
            } else if (complexItemType == CircularSurveyComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Circular Survey: nextSequenceNumber" << nextSequenceNumber;
                CircularSurveyComplexItem* circularSurvey = new CircularSurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
                if (!circularSurvey->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = circularSurvey->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Circular Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(circularSurvey);
917
            } else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
918
                qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
919
                MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
920 921 922 923 924 925
                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
926 927 928 929 930 931 932 933 934 935 936 937 938
            } 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);
939
            if (doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
940
                bool found = false;
941
                int findDoJumpId = static_cast<int>(doJumpItem->missionItem().param1());
Don Gagne's avatar
Don Gagne committed
942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962
                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;
}

963 964 965 966 967 968 969 970
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;
971 972 973 974 975 976
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
977 978

    if (fileVersion == 1) {
979
        return _loadJsonMissionFileV1(json, visualItems, errorString);
980
    } else {
981
        return _loadJsonMissionFileV2(json, visualItems, errorString);
982 983 984
    }
}

985
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
986
{
987 988
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
989 990 991 992 993 994 995 996 997

    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;
998
            plannedHomePositionInFile = true;
999 1000 1001
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
1002
            plannedHomePositionInFile = false;
1003 1004 1005 1006
        }
    }

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

1011
        while (!stream.atEnd()) {
1012
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
1013 1014

            if (item->load(stream)) {
1015 1016 1017 1018 1019 1020
                if (firstItem && plannedHomePositionInFile) {
                    settingsItem->setCoordinate(item->coordinate());
                } else {
                    visualItems->append(item);
                }
                firstItem = false;
1021
            } else {
1022
                errorString = tr("The mission file is corrupted.");
1023 1024 1025 1026
                return false;
            }
        }
    } else {
1027
        errorString = tr("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
1028 1029 1030
        return false;
    }

1031
    if (!plannedHomePositionInFile) {
1032 1033 1034
        // 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));
1035
            if (item && item->command() == MAV_CMD_DO_JUMP) {
1036
                item->missionItem().setParam1(static_cast<int>(item->missionItem().param1()) + 1);
Don Gagne's avatar
Don Gagne committed
1037 1038
            }
        }
1039 1040 1041
    }

    return true;
1042 1043
}

1044
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
1045
{
Don Gagne's avatar
Don Gagne committed
1046 1047 1048
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
1049
        _settingsItem = nullptr;
Don Gagne's avatar
Don Gagne committed
1050 1051
    }

1052
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
1053 1054

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

1058
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
1059

Don Gagne's avatar
Don Gagne committed
1060
    _initAllVisualItems();
1061
}
1062

1063 1064 1065 1066 1067 1068
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

1069
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094
        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;
1095
    }
1096

1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109
    _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);
1110
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
1111 1112 1113 1114 1115 1116
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
1117
    return true;
1118 1119
}

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

1132
bool MissionController::setTakeoffCommand(SimpleMissionItem &missionItem)
1133
{
1134
    if (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() || _controllerVehicle->multiRotor()) {
1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145
        MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
        if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) {
            missionItem.setCommand(takeoffCmd);
        }
    }
    else
       return false;

    return true;
}

1146
bool MissionController::setLandCommand(SimpleMissionItem &missionItem)
1147
{
1148 1149
    MAV_CMD landCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_LAND;
    if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(landCmd)) {
1150 1151 1152 1153 1154 1155 1156
        missionItem.setCommand(landCmd);
    } else
        return false;

    return true;
}

1157
void MissionController::save(QJsonObject& json)
1158
{
1159
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
1160

1161
    // Mission settings
1162

1163 1164 1165 1166 1167 1168 1169
    MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsItem";
        return;
    }
    QJsonValue coordinateValue;
    JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
1170 1171 1172 1173 1174
    json[_jsonPlannedHomePositionKey]   = coordinateValue;
    json[_jsonFirmwareTypeKey]          = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey]           = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey]           = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey]            = _controllerVehicle->defaultHoverSpeed();
1175

1176
    // Save the visual items
1177

1178 1179 1180
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1181

1182 1183
        visualItem->save(rgJsonMissionItems);
    }
1184

1185 1186 1187
    // Mission settings has a special case for end mission action
    if (settingsItem) {
        QList<MissionItem*> rgMissionItems;
1188

1189
        if (convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
1190 1191 1192 1193
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
1194
        }
1195 1196
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
1197 1198 1199
        }
    }

1200
    json[_jsonItemsKey] = rgJsonMissionItems;
1201 1202
}

1203
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
1204
{
Don Gagne's avatar
Don Gagne committed
1205
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
1206
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
1207 1208 1209 1210
    bool            distanceOk =    false;

    // Convert to fixed altitudes

1211
    distanceOk = true;
1212
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
1213 1214
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
1215
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
1216
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
1217 1218 1219
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
1220 1221 1222
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
1223
    } else {
Don Gagne's avatar
Don Gagne committed
1224
        *altDifference = 0.0;
1225
        *azimuth = 0.0;
1226
        *distance = 0.0;
1227 1228 1229
    }
}

1230
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
1231 1232 1233 1234 1235 1236 1237
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

1238
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
1239 1240
}

1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262
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;
    }
}

1263 1264
void MissionController::_recalcWaypointLines(void)
{
1265 1266 1267
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

1268
    bool homePositionValid = _settingsItem->coordinate().isValid();
1269

1270
    qCDebug(MissionControllerLog) << "_recalcWaypointLines homePositionValid" << homePositionValid;
1271

Nate Weibley's avatar
Nate Weibley committed
1272 1273
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
1274
    _waypointLines.clear();
1275
    _waypointPath.clear();
1276

1277 1278 1279 1280 1281 1282 1283 1284 1285
    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;
1286 1287 1288
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));

1289 1290 1291 1292 1293 1294
        // 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;
1295
            }
1296 1297
        }

1298 1299 1300
        if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
            firstCoordinateItem = false;
            if (lastCoordinateItem != _settingsItem || (homePositionValid && linkStartToHome)) {
1301
                if (!_flyView) {
1302 1303
                    VisualItemPair pair(lastCoordinateItem, item);
                    _addWaypointLineSegment(old_table, pair);
1304 1305
                }
            }
1306 1307
            _waypointPath.append(QVariant::fromValue(item->coordinate()));
            lastCoordinateItem = item;
1308 1309
        }
    }
1310 1311 1312 1313 1314 1315

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

    if (linkEndToHome && lastCoordinateItem != _settingsItem && homePositionValid) {
1316
        if (!_flyView) {
1317 1318 1319 1320 1321
            VisualItemPair pair(lastCoordinateItem, _settingsItem);
            _addWaypointLineSegment(old_table, pair);
        } else {
            _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
        }
1322
    }
1323 1324 1325 1326

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1327
        objs.reserve(_linesTable.count());
1328
        for(CoordinateVector *vect: _linesTable.values()) {
1329 1330 1331 1332 1333 1334 1335 1336 1337 1338
            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
1339
    _recalcMissionFlightStatus();
1340

1341 1342 1343 1344 1345 1346 1347 1348
    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)));
    }

1349
    emit waypointLinesChanged();
1350
    emit waypointPathChanged();
1351 1352
}

1353 1354 1355 1356 1357 1358
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);
1359 1360 1361
        // 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.
1362
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385
            _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);
}

1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412
/// 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
1413
void MissionController::_recalcMissionFlightStatus()
1414
{
1415
    if (!_visualItems->count()) {
1416
        return;
1417
    }
1418 1419 1420 1421

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

1422
    bool showHomePosition = _settingsItem->coordinate().isValid();
1423

DonLakeFlyer's avatar
DonLakeFlyer committed
1424
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1425

1426 1427 1428
    // 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.
1429

1430
    // No values for first item
1431
    lastCoordinateItem->setAltDifference(0.0);
1432
    lastCoordinateItem->setAzimuth(0.0);
1433
    lastCoordinateItem->setDistance(0.0);
1434

1435 1436
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1437 1438
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1439

1440
    _resetMissionFlightStatus();
1441

DonLakeFlyer's avatar
DonLakeFlyer committed
1442
    bool vtolInHover = true;
1443
    bool linkStartToHome = false;
1444 1445 1446 1447 1448 1449 1450 1451 1452 1453
    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();
        }
    }
1454

DonLakeFlyer's avatar
DonLakeFlyer committed
1455
    for (int i=0; i<_visualItems->count(); i++) {
1456
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1457 1458 1459
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1460 1461
        // Assume the worst
        item->setAzimuth(0.0);
1462
        item->setDistance(0.0);
1463

DonLakeFlyer's avatar
DonLakeFlyer committed
1464 1465 1466
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1467
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1468
                _missionFlightStatus.hoverSpeed = newSpeed;
1469
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1470 1471
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1472
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1473
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1474
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1475 1476
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1477
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1478 1479 1480 1481
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1482 1483 1484 1485 1486 1487 1488
        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
1489 1490 1491 1492 1493
        }

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

1496
        // Link back to home if first item is takeoff and we have home position
1497
        if (firstCoordinateItem && simpleItem && (simpleItem->command() == MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
1498
            if (showHomePosition) {
1499
                linkStartToHome = true;
1500 1501 1502 1503 1504 1505 1506
                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);
                }
1507 1508 1509 1510
            }
        }

        // Update VTOL state
1511
        if (simpleItem && _controllerVehicle->vtol()) {
1512
            switch (simpleItem->command()) {
1513
            case MAV_CMD_NAV_TAKEOFF:
1514 1515
                vtolInHover = false;
                break;
1516
            case MAV_CMD_NAV_VTOL_TAKEOFF:
DonLakeFlyer's avatar
DonLakeFlyer committed
1517 1518
                vtolInHover = true;
                break;
1519
            case MAV_CMD_NAV_LAND:
1520 1521
                vtolInHover = false;
                break;
1522
            case MAV_CMD_NAV_VTOL_LAND:
DonLakeFlyer's avatar
DonLakeFlyer committed
1523 1524
                vtolInHover = true;
                break;
1525
            case MAV_CMD_DO_VTOL_TRANSITION:
1526 1527 1528 1529 1530 1531
            {
                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;
1532 1533
                }
            }
1534 1535 1536
                break;
            default:
                break;
1537
            }
Don Gagne's avatar
Don Gagne committed
1538 1539
        }

1540
        _addTimeDistance(vtolInHover, 0, 0, item->additionalTimeDelay(), 0, -1);
1541

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

1545
            double absoluteAltitude = item->coordinate().altitude();
1546
            if (item->coordinateHasRelativeAltitude()) {
1547 1548 1549 1550 1551
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1552 1553 1554 1555
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1556 1557 1558
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1559
                firstCoordinateItem = false;
1560 1561 1562 1563 1564 1565 1566

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

1567
                if (lastCoordinateItem != _settingsItem || linkStartToHome) {
1568 1569
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1570

1571
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1572 1573 1574
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1575

1576
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1577

DonLakeFlyer's avatar
DonLakeFlyer committed
1578 1579 1580
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1581
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1582
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1583

1584
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1585 1586
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1587
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1588

1589 1590
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1591
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1592
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1593 1594

                item->setMissionFlightStatus(_missionFlightStatus);
1595

1596 1597
                lastCoordinateItem = item;
            }
1598 1599
        }
    }
1600
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1601

1602 1603 1604 1605 1606 1607 1608 1609
    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();
1610
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1611 1612
    }

1613 1614 1615
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1616

DonLakeFlyer's avatar
DonLakeFlyer committed
1617 1618 1619 1620 1621 1622 1623
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1624 1625
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1626

1627 1628
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1629 1630
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1631 1632 1633

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1634
            if (item->coordinateHasRelativeAltitude()) {
1635 1636 1637 1638
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1639
                item->setTerrainPercent(qQNaN());
1640
                item->setTerrainCollision(false);
1641 1642
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1643 1644 1645 1646 1647 1648 1649
                double terrainAltitude = item->terrainAltitude();
                if (qIsNaN(terrainAltitude)) {
                    item->setTerrainPercent(qQNaN());
                    item->setTerrainCollision(false);
                } else {
                    item->setTerrainPercent((terrainAltitude - minAltSeen) / altRange);
                    item->setTerrainCollision(absoluteAltitude < terrainAltitude);
1650
                }
1651
            }
1652 1653
        }
    }
1654 1655

    _updateTimer.start(UPDATE_TIMEOUT);
1656 1657
}

1658 1659 1660
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1661 1662 1663 1664 1665
    if (_inRecalcSequence) {
        // Don't let this call recurse due to signalling
        return;
    }

1666 1667
    // Setup ascending sequence numbers for all visual items

1668
    _inRecalcSequence = true;
1669 1670 1671
    int sequenceNumber = 0;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1672 1673
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1674 1675
    }    
    _inRecalcSequence = false;
1676 1677
}

1678 1679 1680
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1681
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1682 1683 1684

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

1685 1686
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1687 1688 1689 1690 1691

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1692
        } else if (item->isSimpleItem()) {
1693 1694 1695 1696 1697
            currentParentItem->childItems()->append(item);
        }
    }
}

1698
void MissionController::_setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate)
1699
{
1700 1701
    QGeoCoordinate firstCoordinate;

1702 1703 1704 1705
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1706
    // Set the planned home position to be a delta from first coordinate
1707 1708 1709 1710
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

        if (item->specifiesCoordinate()) {
1711 1712
            firstCoordinate = item->coordinate();
            break;
1713 1714 1715
        }
    }

1716 1717 1718 1719
    // No item specifying a coordinate was found, in this case it we have a clickCoordinate use that
    if (!firstCoordinate.isValid()) {
        firstCoordinate = clickCoordinate;
    }
1720

1721 1722 1723 1724 1725 1726 1727 1728
    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
1729
void MissionController::_recalcAllWithClickCoordinate(const QGeoCoordinate& clickCoordinate)
1730
{
1731
    if (!_flyView) {
1732
        _setPlannedHomePositionFromFirstCoordinate(clickCoordinate);
1733
    }
1734
    _recalcSequence();
1735 1736
    _recalcChildItems();
    _recalcWaypointLines();
1737
    _updateTimer.start(UPDATE_TIMEOUT);
1738 1739
}

1740 1741 1742 1743 1744 1745
void MissionController::_recalcAll(void)
{
    QGeoCoordinate emptyCoord;
    _recalcAllWithClickCoordinate(emptyCoord);
}

1746 1747 1748 1749 1750 1751
void MissionController::_enableDisableRemainingDistTimeCalculation(bool flying)
{
    if (flying) {
        _remainingDistanceTimeTimer.start();
    } else {
        _remainingDistanceTimeTimer.stop();
1752 1753
        _setRemainingTime(-1);
        _setRemainingDistance(-1);
1754 1755 1756 1757 1758 1759 1760
    }
}

void MissionController::_updateRemainingDistanceTime()
{
    double dist = 0;
    double time = 0;
1761
    bool success = distanceTimeToMissionEnd(dist, time, _missionManager->currentIndex() /*missionIndex >= 1*/, true /* useVehiclePostion */);
1762
    if (success) {
1763 1764 1765 1766 1767
        _setRemainingTime(time);
        _setRemainingDistance(dist);
    } else {
        _setRemainingTime(-1);
        _setRemainingDistance(-1);
1768 1769 1770
    }
}

1771
/// Initializes a new set of mission items
1772
void MissionController::_initAllVisualItems(void)
1773
{
1774 1775
    // Setup home position at index 0

1776 1777 1778
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1779 1780
        return;
    }
1781
    if (!_flyView) {
1782 1783
        _settingsItem->setIsCurrentItem(true);
    }
1784

1785
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1786
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1787
    }
1788

1789 1790 1791
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1792

1793 1794 1795 1796
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1797

1798
    _recalcAll();
1799

1800
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1801 1802 1803
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1804
    emit containsItemsChanged(containsItems());
1805
    emit plannedHomePositionChanged(plannedHomePosition());
1806

1807
    setDirty(false);
1808 1809
}

1810
void MissionController::_deinitAllVisualItems(void)
1811
{
1812 1813 1814
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1815 1816
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1817 1818
    }

1819
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1820
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1821 1822
}

1823
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1824
{
1825 1826 1827
    if (visualItem->isSimpleItem()) {
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
        if (simpleItem) {
1828
            _initSimpleItem(simpleItem);
1829 1830 1831
        } else {
            qWarning() << "isSimpleItem == true, yet not SimpleMissionItem";
        }
1832 1833
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1834
        if (complexItem) {
1835
            _initComplexItem(complexItem);
1836 1837 1838
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1839
    }
1840 1841
}

1842 1843 1844 1845 1846 1847 1848 1849 1850 1851 1852 1853 1854 1855 1856 1857 1858 1859 1860 1861 1862 1863 1864 1865 1866 1867 1868 1869 1870 1871 1872 1873 1874 1875 1876 1877 1878 1879
void MissionController::_initVisualItemCommon(VisualMissionItem *visualItem)
{
    setDirty(false);

    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,
            this,       &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,
            this,       &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,
            this,       &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,
            this,       &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,
            this,       &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged,
            this,       &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,
            this,       &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged,
            this,       &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,
            this,       &MissionController::_recalcSequence);
}

void MissionController::_initSimpleItem(SimpleMissionItem *item)
{
    _initVisualItemCommon(item);
    // We need to track commandChanged on simple item since recalc has special handling for takeoff command
    connect(&item->missionItem()._commandFact, &Fact::valueChanged, this, &MissionController::_itemCommandChanged);
}

void MissionController::_initComplexItem(ComplexMissionItem *item)
{
    _initVisualItemCommon(item);
    connect(item, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
    connect(item, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
}

1880
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1881
{
1882 1883
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1884 1885
}

1886
void MissionController::_itemCommandChanged(void)
1887
{
1888 1889
    _recalcChildItems();
    _recalcWaypointLines();
1890 1891
}

1892
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1893
{
1894 1895 1896 1897 1898 1899
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1900

1901 1902
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1903
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1904 1905
        return;
    }
1906

1907 1908
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1909 1910
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1911 1912 1913 1914 1915
    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);
1916
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1917 1918 1919 1920
    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);
1921
    connect(_managerVehicle, &Vehicle::flyingChanged,                   this, &MissionController::_enableDisableRemainingDistTimeCalculation);
1922

1923 1924
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1925
    }
1926

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

1931
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1932
{
1933
    if (_visualItems) {
1934 1935
        bool currentDirtyBit = dirty();

1936
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1937
        if (settingsItem) {
1938
            settingsItem->setHomePositionFromVehicle(homePosition);
1939
        } else {
1940
            qWarning() << "First item is not MissionSettingsItem";
1941
        }
1942 1943 1944 1945 1946 1947

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

void MissionController::_inProgressChanged(bool inProgress)
1952
{
1953
    emit syncInProgressChanged(inProgress);
1954
}
1955

1956
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1957
{
1958 1959
    bool        found = false;
    double      foundAltitude;
1960
    int         foundAltitudeMode;
1961

1962 1963 1964 1965 1966 1967
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1970 1971 1972
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1973 1974 1975
                if (simpleItem->specifiesAltitude()) {
                    foundAltitude = simpleItem->altitude()->rawValue().toDouble();
                    foundAltitudeMode = simpleItem->altitudeMode();
1976
                    found = true;
1977
                    break;
1978 1979
                }
            }
1980 1981 1982
        }
    }

1983
    if (found) {
1984
        *prevAltitude = foundAltitude;
1985
        *prevAltitudeMode = foundAltitudeMode;
1986 1987 1988
    }

    return found;
1989
}
1990 1991 1992 1993 1994 1995 1996 1997 1998 1999 2000 2001 2002

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

2003
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
2004
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
2005
{
2006
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
2007

Don Gagne's avatar
Don Gagne committed
2008 2009
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

2010
    visualItems->insert(0, settingsItem);
2011

2012 2013 2014 2015 2016 2017 2018 2019 2020 2021 2022 2023 2024 2025 2026 2027 2028 2029 2030 2031 2032 2033 2034 2035 2036
    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;
                    }
2037 2038
                }
            }
2039

2040 2041 2042
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
2043
        }
Don Gagne's avatar
Don Gagne committed
2044 2045
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
2046 2047
    }
}
2048

2049
int MissionController::resumeMissionIndex(void) const
2050
{
2051

2052
    int resumeIndex = 0;
2053

2054
    if (_flyView) {
2055
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
2056
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
2057 2058
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
2059 2060
        } else {
            resumeIndex = 0;
2061 2062 2063 2064 2065
        }
    }

    return resumeIndex;
}
2066

2067 2068
int MissionController::currentMissionIndex(void) const
{
2069
    if (!_flyView) {
2070 2071 2072 2073 2074 2075 2076 2077 2078 2079
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

2080
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
2081
{
2082
    if (_flyView) {
2083
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
2084 2085 2086
            sequenceNumber++;
        }

2087 2088
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
2089 2090
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
2091
        emit currentMissionIndexChanged(currentMissionIndex());
2092 2093
    }
}
2094

2095
bool MissionController::syncInProgress(void) const
2096
{
2097
    return _missionManager->inProgress();
2098 2099 2100 2101 2102 2103 2104 2105 2106 2107 2108 2109
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
2110
    }
2111
}
2112

2113 2114
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
2115 2116
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, vehicle);
2117

2118 2119 2120 2121 2122 2123
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

2124
        if (!_flyView) {
2125 2126 2127 2128 2129 2130
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
2131 2132 2133
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
2134
        if (simpleItem) {
2135 2136 2137 2138 2139
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
2140 2141 2142
        }
    }
}
2143 2144 2145 2146 2147 2148 2149 2150 2151 2152 2153 2154 2155

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
2156 2157 2158 2159 2160 2161 2162 2163
    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();
    }
2164
}
2165 2166 2167 2168 2169

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

2170
    complexItems.append(_circularSurveyMissionItemName);
2171
    complexItems.append(_surveyMissionItemName);
2172
    complexItems.append(patternCorridorScanName);
2173
    if (_controllerVehicle->fixedWing()) {
2174
        complexItems.append(patternFWLandingName);
2175
    }
2176
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
2177
        complexItems.append(patternStructureScanName);
2178
    }
2179

2180
    return qgcApp()->toolbox()->corePlugin()->complexMissionItemNames(_controllerVehicle, complexItems);
2181
}
2182

2183 2184
void MissionController::resumeMission(int resumeIndex)
{
2185
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
2186 2187
        resumeIndex--;
    }
2188
    _missionManager->generateResumeMission(resumeIndex);
2189
}
2190 2191 2192 2193 2194 2195 2196 2197 2198

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
2199 2200 2201 2202 2203 2204 2205 2206 2207 2208

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

2210 2211 2212 2213 2214 2215 2216
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
2217 2218 2219 2220 2221 2222

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
2223 2224 2225

bool MissionController::showPlanFromManagerVehicle (void)
{
2226
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
DonLakeFlyer's avatar
DonLakeFlyer committed
2227 2228
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
2229
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
2230 2231 2232 2233 2234 2235 2236 2237 2238 2239 2240 2241 2242 2243 2244 2245 2246 2247 2248
    } 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;
        }
    }
}

2249
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2250
{
2251
    // Fly view always reloads on send complete
2252
    if (!error && _flyView) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2253 2254 2255 2256
        showPlanFromManagerVehicle();
    }
}

2257
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2258
{
2259 2260 2261 2262
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2263
}
2264 2265 2266 2267 2268 2269

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

2270
bool MissionController::distanceTimeToMissionEnd(double &remainingDistance, double &remainingTime, int missionIndex, bool useVehiclePosition) const
2271
{
2272
    // input check
2273 2274 2275 2276
    if (   _visualItems == nullptr
        || _visualItems->count() < 1
        || !_flyView
        || missionIndex < 1
2277
        || missionIndex > _visualItems->count()) {
2278 2279
        return false;
    }
2280 2281 2282 2283 2284 2285 2286 2287 2288 2289 2290
    // check if vehicle is flying and fetch vehicle coordinate
    QGeoCoordinate vehiclePosition;
    if (_managerVehicle && _managerVehicle->flying() && useVehiclePosition) {
        vehiclePosition = _managerVehicle->coordinate();
    } else {
        if (useVehiclePosition) {
            useVehiclePosition = false;
            qWarning("MissionController::distanceTimeToMissionEnd(): vehicle position can't be used. Either no vehicle connected, or vehicle not flying.");
        }
    }

2291 2292 2293 2294 2295 2296 2297 2298 2299 2300 2301 2302 2303 2304 2305 2306 2307 2308 2309 2310 2311 2312 2313 2314 2315 2316 2317 2318 2319 2320 2321 2322
    remainingDistance = 0;
    remainingTime = 0;

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


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

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

    // No values for first item
    lastCoordinateItem->setAltDifference(0.0);
    lastCoordinateItem->setAzimuth(0.0);
    lastCoordinateItem->setDistance(0.0);

    const double homePositionAltitude = _settingsItem->coordinate().altitude();

    bool linkStartToHome    = false;
    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();
        }
    }

2323
    // determine speed at waypoint with index missionIndex
2324 2325
    double currentSpeed = _settingsItem->specifiedFlightSpeed();
    currentSpeed = !qIsNaN(currentSpeed) ? currentSpeed : 5;
2326
    for (int i = 1; i < missionIndex; ++i) {
2327 2328 2329 2330 2331 2332 2333 2334 2335
        SimpleMissionItem* simpleItem = _visualItems->value<SimpleMissionItem*>(i);

        if (simpleItem != nullptr) {
            double speed = simpleItem->specifiedFlightSpeed();
            if (!qIsNaN(speed))
                currentSpeed = speed;
        }
    }

2336
    // calculate dist and time from current vehicle pos. to mission item with index missionIndex
2337
    if (useVehiclePosition) {
2338 2339 2340 2341 2342 2343 2344 2345 2346 2347 2348
        // find valid coordinate
        for (int i = missionIndex; i < _visualItems->count(); ++i) {
            SimpleMissionItem* simpleItem = _visualItems->value<SimpleMissionItem*>(missionIndex);
            if (simpleItem != nullptr && simpleItem->specifiesCoordinate()) {
                double dist = vehiclePosition.distanceTo(simpleItem->coordinate());
                double time = dist/currentSpeed;

                remainingDistance   += dist;
                remainingTime       += time;
                break;
            }
2349 2350 2351
        }
    }

2352
    // iterate over mission items starting at currentMissionIdx-1 and determine time and distance
2353
    for (int i=missionIndex; i<_visualItems->count(); i++) {
2354 2355 2356 2357 2358 2359 2360 2361 2362 2363 2364 2365 2366 2367 2368 2369 2370 2371 2372 2373 2374 2375 2376 2377 2378 2379 2380 2381 2382 2383 2384 2385 2386 2387 2388 2389 2390 2391 2392 2393 2394 2395 2396 2397 2398 2399 2400 2401 2402 2403 2404 2405 2406 2407 2408 2409 2410 2411 2412 2413 2414
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);

        // Assume the worst
        item->setAzimuth(0.0);
        item->setDistance(0.0);

        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
            currentSpeed = newSpeed;
        }

        // Link back to home if first item is takeoff and we have home position
        if (firstCoordinateItem && simpleItem && (simpleItem->command() == MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
            if (showHomePosition) {
                linkStartToHome = true;
                if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
                    // We have to special case takeoff, assuming vehicle takes off straight up to specified altitude

                    QGeoCoordinate itemCoordinate = item->exitCoordinate();
                    QGeoCoordinate settingsCoordinate = _settingsItem->coordinate();
                    if (item->exitCoordinateHasRelativeAltitude()) {
                        itemCoordinate.setAltitude(homePositionAltitude + settingsCoordinate.altitude());
                    }

                    double altDifference = settingsCoordinate.altitude() - itemCoordinate.altitude();

                    double takeoffTime = qAbs(altDifference) / _appSettings->offlineEditingAscentSpeed()->rawValue().toDouble();
                    remainingTime += takeoffTime;
                }
            }
        }

        remainingTime += item->additionalTimeDelay();

        if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
            firstCoordinateItem = false;

            if (lastCoordinateItem != _settingsItem || linkStartToHome) {
                // This is a subsequent waypoint or we are forcing the first waypoint back to home

                QGeoCoordinate  currentCoord =  item->coordinate();
                QGeoCoordinate  prevCoord =     lastCoordinateItem->exitCoordinate();

                if (item != _settingsItem && item->coordinateHasRelativeAltitude()) {
                    currentCoord.setAltitude(homePositionAltitude + currentCoord.altitude());
                }
                if (lastCoordinateItem != _settingsItem && lastCoordinateItem->exitCoordinateHasRelativeAltitude()) {
                    prevCoord.setAltitude(homePositionAltitude + prevCoord.altitude());
                }

                double distance = prevCoord.distanceTo(currentCoord);
                double time = distance / currentSpeed;

                remainingDistance += distance;
                remainingTime += time;
            }

            lastCoordinateItem = item;
        }
2415

2416 2417 2418 2419
        if (    simpleItem != nullptr
            && (   simpleItem->command() == MAV_CMD_NAV_LAND
                || simpleItem->command() == MAV_CMD_NAV_LAND_LOCAL
                || simpleItem->command() == MAV_CMD_NAV_VTOL_LAND)) {
2420

2421 2422 2423 2424 2425 2426 2427 2428 2429 2430 2431 2432 2433 2434 2435 2436
            double alt = 0;
            if (i == missionIndex) {
                alt = _managerVehicle->altitudeRelative()->rawValue().toDouble();
            } else {
                QGeoCoordinate  currentCoord =  simpleItem->coordinate();

                if (simpleItem->coordinateHasRelativeAltitude()) {
                    currentCoord.setAltitude(homePositionAltitude + currentCoord.altitude());
                }

                alt = currentCoord.altitude() - homePositionAltitude;
            }
            double landTime = qAbs(alt) / _appSettings->offlineEditingDescentSpeed()->rawValue().toDouble();

            remainingTime       += landTime;
        }
2437 2438 2439 2440 2441 2442 2443 2444 2445 2446 2447 2448 2449 2450 2451 2452 2453 2454 2455 2456 2457 2458 2459
    }

    if (linkEndToHome && lastCoordinateItem != _settingsItem) {

        QGeoCoordinate  currentCoord =  lastCoordinateItem->coordinate();
        QGeoCoordinate  prevCoord =     _settingsItem->exitCoordinate();

        if (lastCoordinateItem != _settingsItem && lastCoordinateItem->coordinateHasRelativeAltitude()) {
            currentCoord.setAltitude(homePositionAltitude + currentCoord.altitude());
        }

        double altDifference = currentCoord.altitude() - prevCoord.altitude();
        double distance      = currentCoord.distanceTo(prevCoord);

        double time     = distance / currentSpeed;
        double landTime = qAbs(altDifference) / _appSettings->offlineEditingDescentSpeed()->rawValue().toDouble();

        remainingDistance   += distance;
        remainingTime       += time + landTime;
    }
    return true;
}

2460 2461 2462 2463 2464 2465 2466 2467
VisualMissionItem* MissionController::currentPlanViewItem(void) const
{
    return _currentPlanViewItem;
}

void MissionController::setCurrentPlanViewIndex(int sequenceNumber, bool force)
{
    if(_visualItems && (force || sequenceNumber != _currentPlanViewIndex)) {
2468
        _currentPlanViewItem  = nullptr;
2469 2470 2471 2472 2473 2474 2475 2476 2477 2478 2479 2480 2481 2482 2483
        _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();
    }
}
2484 2485 2486

void MissionController::_updateTimeout()
{
Gus Grubba's avatar
Gus Grubba committed
2487
    QGeoCoordinate firstCoordinate;
2488
    QGeoCoordinate takeoffCoordinate;
2489
    QGCGeoBoundingCube boundingCube;
2490 2491 2492 2493
    double north = 0.0;
    double south = 180.0;
    double east  = 0.0;
    double west  = 360.0;
2494 2495
    double minAlt = QGCGeoBoundingCube::MaxAlt;
    double maxAlt = QGCGeoBoundingCube::MinAlt;
2496 2497 2498 2499 2500 2501
    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()) {
2502
                case MAV_CMD_NAV_TAKEOFF:
2503 2504 2505
                case MAV_CMD_NAV_WAYPOINT:
                case MAV_CMD_NAV_LAND:
                if(pSimpleItem->coordinate().isValid()) {
2506
                    if((MAV_CMD)pSimpleItem->command() == MAV_CMD_NAV_TAKEOFF) {
Gus Grubba's avatar
Gus Grubba committed
2507 2508 2509 2510
                        takeoffCoordinate = pSimpleItem->coordinate();
                    } else if(!firstCoordinate.isValid()) {
                        firstCoordinate = pSimpleItem->coordinate();
                    }
2511 2512
                    double lat = pSimpleItem->coordinate().latitude()  + 90.0;
                    double lon = pSimpleItem->coordinate().longitude() + 180.0;
2513
                    double alt = pSimpleItem->coordinate().altitude();
2514 2515 2516 2517
                    north  = fmax(north, lat);
                    south  = fmin(south, lat);
                    east   = fmax(east,  lon);
                    west   = fmin(west,  lon);
2518 2519
                    minAlt = fmin(minAlt, alt);
                    maxAlt = fmax(maxAlt, alt);
2520 2521 2522 2523 2524 2525 2526 2527 2528
                }
                break;
                default:
                    break;
                }
            }
        } else {
            ComplexMissionItem* pComplexItem = qobject_cast<ComplexMissionItem*>(item);
            if(pComplexItem) {
2529 2530
                QGCGeoBoundingCube bc = pComplexItem->boundingCube();
                if(bc.isValid()) {
Gus Grubba's avatar
Gus Grubba committed
2531 2532 2533
                    if(!firstCoordinate.isValid() && pComplexItem->coordinate().isValid()) {
                        firstCoordinate = pComplexItem->coordinate();
                    }
2534 2535 2536 2537 2538 2539
                    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());
2540 2541 2542 2543
                }
            }
        }
    }
Gus Grubba's avatar
Gus Grubba committed
2544 2545 2546 2547 2548 2549 2550 2551 2552
    //-- Figure out where this thing is taking off from
    if(!takeoffCoordinate.isValid()) {
        if(firstCoordinate.isValid()) {
            takeoffCoordinate = firstCoordinate;
        } else {
            takeoffCoordinate = plannedHomePosition();
        }
    }
    //-- Build bounding "cube"
2553 2554 2555
    boundingCube = QGCGeoBoundingCube(
        QGeoCoordinate(north - 90.0, west - 180.0, minAlt),
        QGeoCoordinate(south - 90.0, east - 180.0, maxAlt));
2556 2557
    if(_travelBoundingCube != boundingCube || _takeoffCoordinate != takeoffCoordinate) {
        _takeoffCoordinate  = takeoffCoordinate;
2558
        _travelBoundingCube = boundingCube;
2559
        emit missionBoundingCubeChanged();
2560
        qCDebug(MissionControllerLog) << "Bounding cube:" << _travelBoundingCube.pointNW << _travelBoundingCube.pointSE;
2561 2562 2563 2564 2565 2566 2567
    }
}

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