MissionController.cc 95.6 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 42
#define UPDATE_TIMEOUT 5000 ///< How often we check for bounding box changes

43 44
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

61 62 63
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"));
64

65
MissionController::MissionController(PlanMasterController* masterController, QObject *parent)
66 67 68 69 70 71 72 73 74 75 76 77 78 79
    : 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)
80
{
81
    _resetMissionFlightStatus();
82
    managerVehicleChanged(_managerVehicle);
83 84
    _updateTimer.setSingleShot(true);
    connect(&_updateTimer, &QTimer::timeout, this, &MissionController::_updateTimeout);
85 86 87 88
}

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

90 91
}

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

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

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

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

135 136
}

137
void MissionController::start(bool flyView)
138
{
139
    qCDebug(MissionControllerLog) << "start flyView" << flyView;
140

141
    PlanElementController::start(flyView);
142 143 144 145 146
    _init();
}

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

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

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

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

172 173 174
        _missionItemCount = newMissionItems.count();
        emit missionItemCountChanged(_missionItemCount);

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

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

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

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

207
        MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
208

209
        _initAllVisualItems();
210
        _updateContainsItems();
211
        emit newItemsFromVehicle();
212
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
213
    _itemsRequested = false;
214 215
}

216
void MissionController::loadFromVehicle(void)
217
{
DonLakeFlyer's avatar
DonLakeFlyer committed
218 219 220 221 222 223 224 225
    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();
    }
226 227
}

228 229 230 231
void MissionController::_warnIfTerrainFrameUsed(void)
{
    for (int i=1; i<_visualItems->count(); i++) {
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(i));
232
        if (simpleItem && simpleItem->altitudeMode() == QGroundControlQmlGlobal::AltitudeModeTerrainFrame) {
233 234 235 236 237 238
            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;
        }
    }
}

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

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

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

    return endActionSet;
}

292 293
void MissionController::convertToKMLDocument(QDomDocument& document)
{
294 295
    QObject*            deleteParent = new QObject();
    QList<MissionItem*> rgMissionItems;
296

297
    convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
298
    if (rgMissionItems.count() == 0) {
299 300
        return;
    }
301

302
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
303 304 305 306 307

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

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

    deleteParent->deleteLater();

329 330 331 332 333
    Kml kml;
    kml.points(coords);
    kml.save(document);
}

334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354
//QList<QObject *> MissionController::takeVisualItems()
//{
//    QList<QObject *> objectList;
//    if (_visualItems) {
//        _deinitAllVisualItems();
//        QList<QObject *> *objectListPt = _visualItems->objectList();
//        for (auto object : *objectListPt)
//            objectList.append(object);
//        _visualItems->clear();
//        _visualItems->deleteLater();
//        _settingsItem = nullptr;
//        _visualItems = new QmlObjectListModel(this);
//        _addMissionSettings(_visualItems, false /* addToCenter */);
//        _initAllVisualItems();
//        setDirty(true);
//        _resetMissionFlightStatus();
//    }

//    return objectList;
//}

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

360
        convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
361

362
        // PlanManager takes control of MissionItems so no need to delete
363
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
364 365
    }
}
366

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

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

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

404 405
    // 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);
406

407
    return newItem->sequenceNumber();
408 409
}

410 411 412 413 414 415 416 417 418
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)) {
419
            newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
420 421 422
            return -1; // can not add this takeoff command for this vehicle
        }
    }
423 424 425 426 427 428
    if (newItem->specifiesAltitude()) {        
        newItem->altitude()->setRawValue(missionItem.relativeAltitude());
        newItem->setAltitudeMode(QGroundControlQmlGlobal::AltitudeMode::AltitudeModeRelative);
    }
    newItem->setMissionFlightStatus(_missionFlightStatus);
    _visualItems->insert(i, newItem);
429

430 431 432
    return newItem->sequenceNumber();
}

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
int MissionController::insertSimpleMissionItem(const QList<const MissionItem *> &missionItems, int index)
{
    SimpleMissionItem *newItem = nullptr;
    for (int i = 0; i < missionItems.size(); ++i) {
        MissionItem missionItem = *missionItems[i];

        newItem = new SimpleMissionItem(_controllerVehicle, _flyView, missionItem, this);
        newItem->setSequenceNumber(_nextSequenceNumber());
        _initVisualItem(newItem, false /* doResetDirty */);
        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
            }
        }
        if (newItem->specifiesAltitude()) {
            newItem->altitude()->setRawValue(missionItem.relativeAltitude());
            newItem->setAltitudeMode(QGroundControlQmlGlobal::AltitudeMode::AltitudeModeRelative);
        }
        newItem->setMissionFlightStatus(_missionFlightStatus);
        _visualItems->insert(index + i, newItem);
    }

    setDirty(false); // must be called, since _initVisualItem(newItem, false /* doResetDirty */) was used

    return (newItem != nullptr) ? newItem->sequenceNumber(): -1;
}

462
/*int MissionController::insertSimpleMissionItem(SimpleMissionItem &missionItem, int i)
463 464 465 466 467 468 469 470 471 472
{
    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
473 474
        }
    }
Valentin Platzgummer's avatar
Valentin Platzgummer committed
475
    newItem->setMissionFlightStatus(_missionFlightStatus);
476 477 478
    _visualItems->insert(i, newItem);

    return newItem->sequenceNumber();
479
}*/
480

481 482 483
int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
{
    int sequenceNumber = _nextSequenceNumber();
484
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
485
    newItem->setSequenceNumber(sequenceNumber);
486
    newItem->setCommand((_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_DO_SET_ROI_LOCATION) ?
487 488
        MAV_CMD_DO_SET_ROI_LOCATION :
        MAV_CMD_DO_SET_ROI));
489
    _initVisualItem(newItem);
490
    newItem->setCoordinate(coordinate);
491

492 493
    double  prevAltitude;
    int     prevAltitudeMode;
494

495 496
    if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
        newItem->altitude()->setRawValue(prevAltitude);
497
        newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
498 499 500 501 502 503 504 505
    }
    _visualItems->insert(i, newItem);

    _recalcAll();

    return newItem->sequenceNumber();
}

506
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
507
{
508 509
    ComplexMissionItem* newItem;

510
    int sequenceNumber = _nextSequenceNumber();
511
    if (itemName == _surveyMissionItemName) {
512
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
513
        newItem->setCoordinate(mapCenterCoordinate);
514
    } else if (itemName == patternFWLandingName) {
515
        newItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, _visualItems /* parent */);
516
    } else if (itemName == patternStructureScanName) {
517
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
518
    } else if (itemName == patternCorridorScanName) {
519
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
520 521
    } else if (itemName == _circularSurveyMissionItemName) {
        newItem = new CircularSurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
522 523 524 525 526
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }

527 528 529
    return _insertComplexMissionItemWorker(newItem, i);
}

530
int MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int i)
531 532 533 534
{
    ComplexMissionItem* newItem;

    if (itemName == _surveyMissionItemName) {
535
        newItem = new SurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
536 537
    } else if (itemName == _circularSurveyMissionItemName) {
        newItem = new CircularSurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
538
    } else if (itemName == patternStructureScanName) {
539
        newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
540
    } else if (itemName == patternCorridorScanName) {
541
        newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
542 543 544 545 546 547 548 549 550 551 552
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return _nextSequenceNumber();
    }

    return _insertComplexMissionItemWorker(newItem, i);
}

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

557
    if (surveyStyleItem) {
558
        bool rollSupported  = false;
559
        bool pitchSupported = false;
560
        bool yawSupported   = false;
561 562 563

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

564 565
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
        CameraSection* cameraSection = settingsItem->cameraSection();
566

567
        // Set camera to photo mode (leave alone if user already specified)
568
        if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
569
            cameraSection->setSpecifyCameraMode(true);
570
            cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
571
        }
572

573
        // Point gimbal straight down
574
        if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
575 576 577
            // If the user already specified a gimbal angle leave it alone
            if (!cameraSection->specifyGimbal()) {
                cameraSection->setSpecifyGimbal(true);
578
                cameraSection->gimbalPitch()->setRawValue(-90.0);
579 580
            }
        }
581
    }
582

583 584
    complexItem->setSequenceNumber(sequenceNumber);
    _initVisualItem(complexItem);
585

586 587 588 589 590
    if (i == -1) {
        _visualItems->append(complexItem);
    } else {
        _visualItems->insert(i, complexItem);
    }
591

592
    //-- Keep track of bounding box changes in complex items
593 594
    if(!complexItem->isSimpleItem()) {
        connect(complexItem, &ComplexMissionItem::boundingCubeChanged, this, &MissionController::_complexBoundingBoxChanged);
595
    }
596 597
    _recalcAll();

598
    return complexItem->sequenceNumber();
599 600
}

601 602
void MissionController::removeMissionItem(int index)
{
603 604 605 606 607
    if (index <= 0 || index >= _visualItems->count()) {
        qWarning() << "MissionController::removeMissionItem called with bad index - count:index" << _visualItems->count() << index;
        return;
    }

608 609 610
    bool removeSurveyStyle =    _visualItems->value<SurveyComplexItem*>(index)
                             || _visualItems->value<CorridorScanComplexItem*>(index)
                             || _visualItems->value<CircularSurveyComplexItem*>(index);
611
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
612

613
    _deinitVisualItem(item);
614
    item->deleteLater();
615

616 617
    if (removeSurveyStyle) {
        // Determine if the mission still has another survey style item in it
618 619
        bool foundSurvey = false;
        for (int i=1; i<_visualItems->count(); i++) {
620 621 622
            if (    _visualItems->value<SurveyComplexItem*>(i)
                 || _visualItems->value<CorridorScanComplexItem*>(i)
                 || _visualItems->value<CircularSurveyComplexItem*>(i)) {
623 624 625 626 627
                foundSurvey = true;
                break;
            }
        }

628
        // If there is no longer a survey item in the mission remove added commands
629 630 631 632
        if (!foundSurvey) {
            bool rollSupported = false;
            bool pitchSupported = false;
            bool yawSupported = false;
633 634
            MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
            CameraSection* cameraSection = settingsItem->cameraSection();
635
            if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
636
                if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
637 638 639
                    cameraSection->setSpecifyGimbal(false);
                }
            }
640
            if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
641 642
                cameraSection->setSpecifyCameraMode(false);
            }
643 644 645
        }
    }

646
    _recalcAll();
647
    setDirty(true);
648 649
}

650
void MissionController::removeAll(void)
651
{
652 653
    if (_visualItems) {
        _deinitAllVisualItems();
DonLakeFlyer's avatar
DonLakeFlyer committed
654
        _visualItems->clearAndDeleteContents();
Don Gagne's avatar
Don Gagne committed
655
        _visualItems->deleteLater();
656
        _settingsItem = nullptr;
657
        _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
658
        _addMissionSettings(_visualItems, false /* addToCenter */);
659
        _initAllVisualItems();
660
        setDirty(true);
661
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
662 663 664
    }
}

665
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
666 667 668 669 670 671 672 673 674
{
    // 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)) {
675 676 677
        return false;
    }

678
    // Read complex items
679
    QList<SurveyComplexItem*> surveyItems;
680 681 682 683
    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];
684

685 686 687 688 689
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

690
        SurveyComplexItem* item = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems /* parent */);
Don Gagne's avatar
Don Gagne committed
691 692
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
693
            surveyItems.append(item);
694 695
        } else {
            return false;
696
        }
697
    }
698

699 700 701 702 703
    // 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
704
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
705

706
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
707 708 709 710
    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
711
        if (nextComplexItemIndex < surveyItems.count()) {
712
            SurveyComplexItem* complexItem = surveyItems[nextComplexItemIndex];
713 714 715 716 717 718 719 720 721 722 723 724 725 726

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

727 728 729 730 731
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
732
            const QJsonObject itemObject = itemValue.toObject();
733
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
Don Gagne's avatar
Don Gagne committed
734
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
735
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
736
                nextSequenceNumber = item->lastSequenceNumber() + 1;
737
                visualItems->append(item);
738 739 740 741
            } else {
                return false;
            }
        }
742
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
743 744

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

Don Gagne's avatar
Don Gagne committed
747
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
748
            MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
749 750 751
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
752 753 754 755
        } else {
            return false;
        }
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
756
        _addMissionSettings(visualItems, true /* addToCenter */);
757 758 759 760 761
    }

    return true;
}

762
bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
763 764 765 766 767 768
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
769
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
770 771
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
772 773 774 775 776 777 778
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

779
    // Mission Settings
780
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
781

782 783
    if (_masterController->offline()) {
        // We only update if offline since if we are online we use the online vehicle settings
784
        appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType(static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt())));
785
        if (json.contains(_jsonVehicleTypeKey)) {
786
            appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType(static_cast<MAV_TYPE>(json[_jsonVehicleTypeKey].toInt())));
787
        }
788
    }
789
    if (json.contains(_jsonCruiseSpeedKey)) {
790
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
791 792
    }
    if (json.contains(_jsonHoverSpeedKey)) {
793
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
794 795
    }

796 797 798 799
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
800
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
801 802
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828
    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) {
829
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
830
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
831
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
832
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
833 834 835 836 837 838 839 840 841 842 843 844 845
                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();

846
            if (complexItemType == SurveyComplexItem::jsonComplexItemTypeValue) {
Don Gagne's avatar
Don Gagne committed
847
                qCDebug(MissionControllerLog) << "Loading Survey: nextSequenceNumber" << nextSequenceNumber;
848
                SurveyComplexItem* surveyItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
Don Gagne's avatar
Don Gagne committed
849 850 851 852 853 854
                if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(surveyItem);
855
            } else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
856
                qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
857
                FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
858 859 860 861 862 863
                if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(landingItem);
864 865
            } else if (complexItemType == StructureScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Structure Scan: nextSequenceNumber" << nextSequenceNumber;
866
                StructureScanComplexItem* structureItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
867 868 869 870 871 872
                if (!structureItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = structureItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Structure Scan load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(structureItem);
873 874
            } else if (complexItemType == CorridorScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Corridor Scan: nextSequenceNumber" << nextSequenceNumber;
875
                CorridorScanComplexItem* corridorItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, visualItems);
876 877 878 879 880 881
                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
882 883 884 885 886 887 888 889 890
            } 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);
891
            } else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
892
                qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
893
                MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
894 895 896 897 898 899
                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
900 901 902 903 904 905 906 907 908 909 910 911 912
            } 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);
913
            if (doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
914
                bool found = false;
915
                int findDoJumpId = static_cast<int>(doJumpItem->missionItem().param1());
Don Gagne's avatar
Don Gagne committed
916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936
                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;
}

937 938 939 940 941 942 943 944
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;
945 946 947 948 949 950
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
951 952

    if (fileVersion == 1) {
953
        return _loadJsonMissionFileV1(json, visualItems, errorString);
954
    } else {
955
        return _loadJsonMissionFileV2(json, visualItems, errorString);
956 957 958
    }
}

959
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
960
{
961 962
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
963 964 965 966 967 968 969 970 971

    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;
972
            plannedHomePositionInFile = true;
973 974 975
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
976
            plannedHomePositionInFile = false;
977 978 979 980
        }
    }

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

985
        while (!stream.atEnd()) {
986
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
987 988

            if (item->load(stream)) {
989 990 991 992 993 994
                if (firstItem && plannedHomePositionInFile) {
                    settingsItem->setCoordinate(item->coordinate());
                } else {
                    visualItems->append(item);
                }
                firstItem = false;
995
            } else {
996
                errorString = tr("The mission file is corrupted.");
997 998 999 1000
                return false;
            }
        }
    } else {
1001
        errorString = tr("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
1002 1003 1004
        return false;
    }

1005
    if (!plannedHomePositionInFile) {
1006 1007 1008
        // 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));
1009
            if (item && item->command() == MAV_CMD_DO_JUMP) {
1010
                item->missionItem().setParam1(static_cast<int>(item->missionItem().param1()) + 1);
Don Gagne's avatar
Don Gagne committed
1011 1012
            }
        }
1013 1014 1015
    }

    return true;
1016 1017
}

1018
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
1019
{
Don Gagne's avatar
Don Gagne committed
1020 1021 1022
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
1023
        _settingsItem = nullptr;
Don Gagne's avatar
Don Gagne committed
1024 1025
    }

1026
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
1027 1028

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

1032
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
1033

Don Gagne's avatar
Don Gagne committed
1034
    _initAllVisualItems();
1035
}
1036

1037 1038 1039 1040 1041 1042
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

1043
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068
        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;
1069
    }
1070

1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083
    _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);
1084
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
1085 1086 1087 1088 1089 1090
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
1091
    return true;
1092 1093
}

1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105
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;
}

1106
bool MissionController::setTakeoffCommand(SimpleMissionItem &missionItem)
1107
{
1108
    if (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() || _controllerVehicle->multiRotor()) {
1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119
        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;
}

1120
bool MissionController::setLandCommand(SimpleMissionItem &missionItem)
1121
{
1122 1123
    MAV_CMD landCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_LAND;
    if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(landCmd)) {
1124 1125 1126 1127 1128 1129 1130
        missionItem.setCommand(landCmd);
    } else
        return false;

    return true;
}

1131
void MissionController::save(QJsonObject& json)
1132
{
1133
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
1134

1135
    // Mission settings
1136

1137 1138 1139 1140 1141 1142 1143
    MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsItem";
        return;
    }
    QJsonValue coordinateValue;
    JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
1144 1145 1146 1147 1148
    json[_jsonPlannedHomePositionKey]   = coordinateValue;
    json[_jsonFirmwareTypeKey]          = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey]           = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey]           = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey]            = _controllerVehicle->defaultHoverSpeed();
1149

1150
    // Save the visual items
1151

1152 1153 1154
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1155

1156 1157
        visualItem->save(rgJsonMissionItems);
    }
1158

1159 1160 1161
    // Mission settings has a special case for end mission action
    if (settingsItem) {
        QList<MissionItem*> rgMissionItems;
1162

1163
        if (convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
1164 1165 1166 1167
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
1168
        }
1169 1170
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
1171 1172 1173
        }
    }

1174
    json[_jsonItemsKey] = rgJsonMissionItems;
1175 1176
}

1177
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
1178
{
Don Gagne's avatar
Don Gagne committed
1179
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
1180
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
1181 1182 1183 1184
    bool            distanceOk =    false;

    // Convert to fixed altitudes

1185
    distanceOk = true;
1186
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
1187 1188
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
1189
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
1190
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
1191 1192 1193
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
1194 1195 1196
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
1197
    } else {
Don Gagne's avatar
Don Gagne committed
1198
        *altDifference = 0.0;
1199
        *azimuth = 0.0;
1200
        *distance = 0.0;
1201 1202 1203
    }
}

1204
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
1205 1206 1207 1208 1209 1210 1211
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

1212
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
1213 1214
}

1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236
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;
    }
}

1237 1238
void MissionController::_recalcWaypointLines(void)
{
1239 1240 1241
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

1242
    bool homePositionValid = _settingsItem->coordinate().isValid();
1243

1244
    qCDebug(MissionControllerLog) << "_recalcWaypointLines homePositionValid" << homePositionValid;
1245

Nate Weibley's avatar
Nate Weibley committed
1246 1247
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
1248
    _waypointLines.clear();
1249
    _waypointPath.clear();
1250

1251 1252 1253 1254 1255 1256 1257 1258 1259
    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;
1260 1261 1262
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));

1263 1264 1265 1266 1267 1268
        // 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;
1269
            }
1270 1271
        }

1272 1273 1274
        if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
            firstCoordinateItem = false;
            if (lastCoordinateItem != _settingsItem || (homePositionValid && linkStartToHome)) {
1275
                if (!_flyView) {
1276 1277
                    VisualItemPair pair(lastCoordinateItem, item);
                    _addWaypointLineSegment(old_table, pair);
1278 1279
                }
            }
1280 1281
            _waypointPath.append(QVariant::fromValue(item->coordinate()));
            lastCoordinateItem = item;
1282 1283
        }
    }
1284 1285 1286 1287 1288 1289

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

    if (linkEndToHome && lastCoordinateItem != _settingsItem && homePositionValid) {
1290
        if (!_flyView) {
1291 1292 1293 1294 1295
            VisualItemPair pair(lastCoordinateItem, _settingsItem);
            _addWaypointLineSegment(old_table, pair);
        } else {
            _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
        }
1296
    }
1297 1298 1299 1300

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1301
        objs.reserve(_linesTable.count());
1302
        for(CoordinateVector *vect: _linesTable.values()) {
1303 1304 1305 1306 1307 1308 1309 1310 1311 1312
            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
1313
    _recalcMissionFlightStatus();
1314

1315 1316 1317 1318 1319 1320 1321 1322
    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)));
    }

1323
    emit waypointLinesChanged();
1324
    emit waypointPathChanged();
1325 1326
}

1327 1328 1329 1330 1331 1332
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);
1333 1334 1335
        // 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.
1336
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359
            _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);
}

1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386
/// 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
1387
void MissionController::_recalcMissionFlightStatus()
1388
{
1389
    if (!_visualItems->count()) {
1390
        return;
1391
    }
1392 1393 1394 1395

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

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1398
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1399

1400 1401 1402
    // 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.
1403

1404
    // No values for first item
1405
    lastCoordinateItem->setAltDifference(0.0);
1406
    lastCoordinateItem->setAzimuth(0.0);
1407
    lastCoordinateItem->setDistance(0.0);
1408

1409 1410
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1411 1412
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1413

1414
    _resetMissionFlightStatus();
1415

DonLakeFlyer's avatar
DonLakeFlyer committed
1416
    bool vtolInHover = true;
1417
    bool linkStartToHome = false;
1418 1419 1420 1421 1422 1423 1424 1425 1426 1427
    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();
        }
    }
1428

DonLakeFlyer's avatar
DonLakeFlyer committed
1429
    for (int i=0; i<_visualItems->count(); i++) {
1430
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1431 1432 1433
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1434 1435
        // Assume the worst
        item->setAzimuth(0.0);
1436
        item->setDistance(0.0);
1437

DonLakeFlyer's avatar
DonLakeFlyer committed
1438 1439 1440
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1441
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1442
                _missionFlightStatus.hoverSpeed = newSpeed;
1443
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1444 1445
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1446
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1447
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1448
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1449 1450
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1451
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1452 1453 1454 1455
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1456 1457 1458 1459 1460 1461 1462
        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
1463 1464 1465 1466 1467
        }

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

1470
        // Link back to home if first item is takeoff and we have home position
1471
        if (firstCoordinateItem && simpleItem && (simpleItem->command() == MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
1472
            if (showHomePosition) {
1473
                linkStartToHome = true;
1474 1475 1476 1477 1478 1479 1480
                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);
                }
1481 1482 1483 1484
            }
        }

        // Update VTOL state
1485
        if (simpleItem && _controllerVehicle->vtol()) {
1486
            switch (simpleItem->command()) {
1487
            case MAV_CMD_NAV_TAKEOFF:
1488 1489
                vtolInHover = false;
                break;
1490
            case MAV_CMD_NAV_VTOL_TAKEOFF:
DonLakeFlyer's avatar
DonLakeFlyer committed
1491 1492
                vtolInHover = true;
                break;
1493
            case MAV_CMD_NAV_LAND:
1494 1495
                vtolInHover = false;
                break;
1496
            case MAV_CMD_NAV_VTOL_LAND:
DonLakeFlyer's avatar
DonLakeFlyer committed
1497 1498
                vtolInHover = true;
                break;
1499
            case MAV_CMD_DO_VTOL_TRANSITION:
1500 1501 1502 1503 1504 1505
            {
                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;
1506 1507
                }
            }
1508 1509 1510
                break;
            default:
                break;
1511
            }
Don Gagne's avatar
Don Gagne committed
1512 1513
        }

1514
        _addTimeDistance(vtolInHover, 0, 0, item->additionalTimeDelay(), 0, -1);
1515

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

1519
            double absoluteAltitude = item->coordinate().altitude();
1520
            if (item->coordinateHasRelativeAltitude()) {
1521 1522 1523 1524 1525
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1526 1527 1528 1529
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1530 1531 1532
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1533
                firstCoordinateItem = false;
1534 1535 1536 1537 1538 1539 1540

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

1541
                if (lastCoordinateItem != _settingsItem || linkStartToHome) {
1542 1543
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1544

1545
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1546 1547 1548
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1549

1550
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1551

DonLakeFlyer's avatar
DonLakeFlyer committed
1552 1553 1554
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1555
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1556
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1557

1558
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1559 1560
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1561
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1562

1563 1564
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1565
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1566
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1567 1568

                item->setMissionFlightStatus(_missionFlightStatus);
1569

1570 1571
                lastCoordinateItem = item;
            }
1572 1573
        }
    }
1574
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1575

1576 1577 1578 1579 1580 1581 1582 1583
    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();
1584
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1585 1586
    }

1587 1588 1589
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1590

DonLakeFlyer's avatar
DonLakeFlyer committed
1591 1592 1593 1594 1595 1596 1597
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1598 1599
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1600

1601 1602
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1603 1604
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1605 1606 1607

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1608
            if (item->coordinateHasRelativeAltitude()) {
1609 1610 1611 1612
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1613
                item->setTerrainPercent(qQNaN());
1614
                item->setTerrainCollision(false);
1615 1616
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1617 1618 1619 1620 1621 1622 1623
                double terrainAltitude = item->terrainAltitude();
                if (qIsNaN(terrainAltitude)) {
                    item->setTerrainPercent(qQNaN());
                    item->setTerrainCollision(false);
                } else {
                    item->setTerrainPercent((terrainAltitude - minAltSeen) / altRange);
                    item->setTerrainCollision(absoluteAltitude < terrainAltitude);
1624
                }
1625
            }
1626 1627
        }
    }
1628 1629

    _updateTimer.start(UPDATE_TIMEOUT);
1630 1631
}

1632 1633 1634
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1635 1636 1637 1638 1639
    if (_inRecalcSequence) {
        // Don't let this call recurse due to signalling
        return;
    }

1640 1641
    // Setup ascending sequence numbers for all visual items

1642
    _inRecalcSequence = true;
1643 1644 1645
    int sequenceNumber = 0;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1646 1647
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1648 1649
    }    
    _inRecalcSequence = false;
1650 1651
}

1652 1653 1654
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1655
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1656 1657 1658

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

1659 1660
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1661 1662 1663 1664 1665

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1666
        } else if (item->isSimpleItem()) {
1667 1668 1669 1670 1671
            currentParentItem->childItems()->append(item);
        }
    }
}

1672
void MissionController::_setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate)
1673
{
1674 1675
    QGeoCoordinate firstCoordinate;

1676 1677 1678 1679
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1680
    // Set the planned home position to be a delta from first coordinate
1681 1682 1683 1684
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

        if (item->specifiesCoordinate()) {
1685 1686
            firstCoordinate = item->coordinate();
            break;
1687 1688 1689
        }
    }

1690 1691 1692 1693
    // No item specifying a coordinate was found, in this case it we have a clickCoordinate use that
    if (!firstCoordinate.isValid()) {
        firstCoordinate = clickCoordinate;
    }
1694

1695 1696 1697 1698 1699 1700 1701 1702 1703
    if (firstCoordinate.isValid()) {
        QGeoCoordinate plannedHomeCoord = firstCoordinate.atDistanceAndAzimuth(30, 0);
        plannedHomeCoord.setAltitude(0);
        _settingsItem->setCoordinate(plannedHomeCoord);
    }
}

/// @param clickCoordinate The location of the user click when inserting a new item
void MissionController::_recalcAllWithClickCoordinate(QGeoCoordinate& clickCoordinate)
1704
{
1705
    if (!_flyView) {
1706
        _setPlannedHomePositionFromFirstCoordinate(clickCoordinate);
1707
    }
1708
    _recalcSequence();
1709 1710
    _recalcChildItems();
    _recalcWaypointLines();
1711
    _updateTimer.start(UPDATE_TIMEOUT);
1712 1713
}

1714 1715 1716 1717 1718 1719
void MissionController::_recalcAll(void)
{
    QGeoCoordinate emptyCoord;
    _recalcAllWithClickCoordinate(emptyCoord);
}

1720
/// Initializes a new set of mission items
1721
void MissionController::_initAllVisualItems(void)
1722
{
1723 1724
    // Setup home position at index 0

1725 1726 1727
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1728 1729
        return;
    }
1730
    if (!_flyView) {
1731 1732
        _settingsItem->setIsCurrentItem(true);
    }
1733

1734
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1735
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1736
    }
1737

1738 1739 1740
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1741

1742 1743 1744 1745
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1746

1747
    _recalcAll();
1748

1749
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1750 1751 1752
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1753
    emit containsItemsChanged(containsItems());
1754
    emit plannedHomePositionChanged(plannedHomePosition());
1755

1756
    setDirty(false);
1757 1758
}

1759
void MissionController::_deinitAllVisualItems(void)
1760
{
1761 1762 1763
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1764 1765
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1766 1767
    }

1768
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1769
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1770 1771
}

1772
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1773
{
1774 1775 1776 1777 1778 1779 1780 1781
    _initVisualItem(visualItem, true);
}

void MissionController::_initVisualItem(VisualMissionItem *visualItem, bool doResetDirty)
{

    if (doResetDirty)
        setDirty(false); // this is to expensive if called on many visualItems in a row (call setDirty(false) after last _initVisualItem)
1782

1783
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1784 1785
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1786 1787
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1788
    connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged,                this, &MissionController::_recalcMissionFlightStatus);
1789
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1790
    connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged,                 this, &MissionController::_recalcMissionFlightStatus);
1791
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1792

1793 1794 1795 1796 1797 1798 1799 1800
    if (visualItem->isSimpleItem()) {
        // We need to track commandChanged on simple item since recalc has special handling for takeoff command
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
        if (simpleItem) {
            connect(&simpleItem->missionItem()._commandFact, &Fact::valueChanged, this, &MissionController::_itemCommandChanged);
        } else {
            qWarning() << "isSimpleItem == true, yet not SimpleMissionItem";
        }
1801 1802
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1803
        if (complexItem) {
1804
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
1805
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
1806 1807 1808
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1809
    }
1810 1811
}

1812
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1813
{
1814 1815
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1816 1817
}

1818
void MissionController::_itemCommandChanged(void)
1819
{
1820 1821
    _recalcChildItems();
    _recalcWaypointLines();
1822 1823
}

1824
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1825
{
1826 1827 1828 1829 1830 1831
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1832

1833 1834
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1835
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1836 1837
        return;
    }
1838

1839 1840
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1841 1842
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1843 1844 1845 1846 1847
    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);
1848
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1849 1850 1851 1852
    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);
1853

1854 1855
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1856
    }
1857

1858
    emit complexMissionItemNamesChanged();
1859
    emit resumeMissionIndexChanged();
1860 1861
}

1862
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1863
{
1864
    if (_visualItems) {
1865 1866
        bool currentDirtyBit = dirty();

1867
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1868
        if (settingsItem) {
1869
            settingsItem->setHomePositionFromVehicle(homePosition);
1870
        } else {
1871
            qWarning() << "First item is not MissionSettingsItem";
1872
        }
1873 1874 1875 1876 1877 1878

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

void MissionController::_inProgressChanged(bool inProgress)
1883
{
1884
    emit syncInProgressChanged(inProgress);
1885
}
1886

1887
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
1888
{
1889 1890
    bool        found = false;
    double      foundAltitude;
1891
    int         foundAltitudeMode;
1892

1893 1894 1895 1896 1897 1898
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1901 1902 1903
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1904 1905 1906
                if (simpleItem->specifiesAltitude()) {
                    foundAltitude = simpleItem->altitude()->rawValue().toDouble();
                    foundAltitudeMode = simpleItem->altitudeMode();
1907
                    found = true;
1908
                    break;
1909 1910
                }
            }
1911 1912 1913
        }
    }

1914
    if (found) {
1915
        *prevAltitude = foundAltitude;
1916
        *prevAltitudeMode = foundAltitudeMode;
1917 1918 1919
    }

    return found;
1920
}
1921 1922 1923 1924 1925 1926 1927 1928 1929 1930 1931 1932 1933

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

1934
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1935
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1936
{
1937
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
1938

Don Gagne's avatar
Don Gagne committed
1939 1940
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1941
    visualItems->insert(0, settingsItem);
1942

1943 1944 1945 1946 1947 1948 1949 1950 1951 1952 1953 1954 1955 1956 1957 1958 1959 1960 1961 1962 1963 1964 1965 1966 1967
    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;
                    }
1968 1969
                }
            }
1970

1971 1972 1973
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1974
        }
Don Gagne's avatar
Don Gagne committed
1975 1976
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1977 1978
    }
}
1979

1980
int MissionController::resumeMissionIndex(void) const
1981
{
1982

1983
    int resumeIndex = 0;
1984

1985
    if (_flyView) {
1986
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1987
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1988 1989
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1990 1991
        } else {
            resumeIndex = 0;
1992 1993 1994 1995 1996
        }
    }

    return resumeIndex;
}
1997

1998 1999
int MissionController::currentMissionIndex(void) const
{
2000
    if (!_flyView) {
2001 2002 2003 2004 2005 2006 2007 2008 2009 2010
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

2011
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
2012
{
2013
    if (_flyView) {
2014
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
2015 2016 2017
            sequenceNumber++;
        }

2018 2019
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
2020 2021
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
2022
        emit currentMissionIndexChanged(currentMissionIndex());
2023 2024
    }
}
2025

2026
bool MissionController::syncInProgress(void) const
2027
{
2028
    return _missionManager->inProgress();
2029 2030 2031 2032 2033 2034 2035 2036 2037 2038 2039 2040
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
2041
    }
2042
}
2043

2044 2045
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
2046 2047
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, vehicle);
2048

2049 2050 2051 2052 2053 2054
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

2055
        if (!_flyView) {
2056 2057 2058 2059 2060 2061
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
2062 2063 2064
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
2065
        if (simpleItem) {
2066 2067 2068 2069 2070
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
2071 2072 2073
        }
    }
}
2074 2075 2076 2077 2078 2079 2080 2081 2082 2083 2084 2085 2086

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
2087 2088 2089 2090 2091 2092 2093 2094
    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();
    }
2095
}
2096 2097 2098 2099 2100

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

2101
    complexItems.append(_circularSurveyMissionItemName);
2102
    complexItems.append(_surveyMissionItemName);
2103
    complexItems.append(patternCorridorScanName);
2104
    if (_controllerVehicle->fixedWing()) {
2105
        complexItems.append(patternFWLandingName);
2106
    }
2107
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
2108
        complexItems.append(patternStructureScanName);
2109
    }
2110

2111
    return qgcApp()->toolbox()->corePlugin()->complexMissionItemNames(_controllerVehicle, complexItems);
2112
}
2113

2114 2115
void MissionController::resumeMission(int resumeIndex)
{
2116
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
2117 2118
        resumeIndex--;
    }
2119
    _missionManager->generateResumeMission(resumeIndex);
2120
}
2121 2122 2123 2124 2125 2126 2127 2128 2129

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
2130 2131 2132 2133 2134 2135 2136 2137 2138 2139

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

2141 2142 2143 2144 2145 2146 2147
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
2148 2149 2150 2151 2152 2153

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
2154 2155 2156

bool MissionController::showPlanFromManagerVehicle (void)
{
2157
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
DonLakeFlyer's avatar
DonLakeFlyer committed
2158 2159
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
2160
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
2161 2162 2163 2164 2165 2166 2167 2168 2169 2170 2171 2172 2173 2174 2175 2176 2177 2178 2179
    } 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;
        }
    }
}

2180
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2181
{
2182
    // Fly view always reloads on send complete
2183
    if (!error && _flyView) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2184 2185 2186 2187
        showPlanFromManagerVehicle();
    }
}

2188
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
2189
{
2190 2191 2192 2193
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2194
}
2195 2196 2197 2198 2199 2200 2201 2202 2203 2204 2205 2206 2207 2208 2209 2210 2211 2212 2213 2214 2215 2216 2217 2218 2219 2220 2221 2222 2223 2224

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

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

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

void MissionController::_updateTimeout()
{
Gus Grubba's avatar
Gus Grubba committed
2228
    QGeoCoordinate firstCoordinate;
2229
    QGeoCoordinate takeoffCoordinate;
2230
    QGCGeoBoundingCube boundingCube;
2231 2232 2233 2234
    double north = 0.0;
    double south = 180.0;
    double east  = 0.0;
    double west  = 360.0;
2235 2236
    double minAlt = QGCGeoBoundingCube::MaxAlt;
    double maxAlt = QGCGeoBoundingCube::MinAlt;
2237 2238 2239 2240 2241 2242
    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()) {
2243
                case MAV_CMD_NAV_TAKEOFF:
2244 2245 2246
                case MAV_CMD_NAV_WAYPOINT:
                case MAV_CMD_NAV_LAND:
                if(pSimpleItem->coordinate().isValid()) {
2247
                    if((MAV_CMD)pSimpleItem->command() == MAV_CMD_NAV_TAKEOFF) {
Gus Grubba's avatar
Gus Grubba committed
2248 2249 2250 2251
                        takeoffCoordinate = pSimpleItem->coordinate();
                    } else if(!firstCoordinate.isValid()) {
                        firstCoordinate = pSimpleItem->coordinate();
                    }
2252 2253
                    double lat = pSimpleItem->coordinate().latitude()  + 90.0;
                    double lon = pSimpleItem->coordinate().longitude() + 180.0;
2254
                    double alt = pSimpleItem->coordinate().altitude();
2255 2256 2257 2258
                    north  = fmax(north, lat);
                    south  = fmin(south, lat);
                    east   = fmax(east,  lon);
                    west   = fmin(west,  lon);
2259 2260
                    minAlt = fmin(minAlt, alt);
                    maxAlt = fmax(maxAlt, alt);
2261 2262 2263 2264 2265 2266 2267 2268 2269
                }
                break;
                default:
                    break;
                }
            }
        } else {
            ComplexMissionItem* pComplexItem = qobject_cast<ComplexMissionItem*>(item);
            if(pComplexItem) {
2270 2271
                QGCGeoBoundingCube bc = pComplexItem->boundingCube();
                if(bc.isValid()) {
Gus Grubba's avatar
Gus Grubba committed
2272 2273 2274
                    if(!firstCoordinate.isValid() && pComplexItem->coordinate().isValid()) {
                        firstCoordinate = pComplexItem->coordinate();
                    }
2275 2276 2277 2278 2279 2280
                    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());
2281 2282 2283 2284
                }
            }
        }
    }
Gus Grubba's avatar
Gus Grubba committed
2285 2286 2287 2288 2289 2290 2291 2292 2293
    //-- Figure out where this thing is taking off from
    if(!takeoffCoordinate.isValid()) {
        if(firstCoordinate.isValid()) {
            takeoffCoordinate = firstCoordinate;
        } else {
            takeoffCoordinate = plannedHomePosition();
        }
    }
    //-- Build bounding "cube"
2294 2295 2296
    boundingCube = QGCGeoBoundingCube(
        QGeoCoordinate(north - 90.0, west - 180.0, minAlt),
        QGeoCoordinate(south - 90.0, east - 180.0, maxAlt));
2297 2298
    if(_travelBoundingCube != boundingCube || _takeoffCoordinate != takeoffCoordinate) {
        _takeoffCoordinate  = takeoffCoordinate;
2299
        _travelBoundingCube = boundingCube;
2300
        emit missionBoundingCubeChanged();
2301
        qCDebug(MissionControllerLog) << "Bounding cube:" << _travelBoundingCube.pointNW << _travelBoundingCube.pointSE;
2302 2303 2304 2305 2306 2307 2308
    }
}

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