MissionController.cc 80.8 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 "SurveyMissionItem.h"
20
#include "FixedWingLandingComplexItem.h"
21
#include "StructureScanComplexItem.h"
22
#include "CorridorScanComplexItem.h"
23
#include "JsonHelper.h"
24
#include "ParameterManager.h"
25
#include "QGroundControlQmlGlobal.h"
26
#include "SettingsManager.h"
27
#include "AppSettings.h"
28
#include "MissionSettingsItem.h"
29
#include "QGCQGeoCoordinate.h"
30
#include "PlanMasterController.h"
31
#include "KML.h"
32

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

38 39
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

56 57 58
MissionController::MissionController(PlanMasterController* masterController, QObject *parent)
    : PlanElementController(masterController, parent)
    , _missionManager(_managerVehicle->missionManager())
59
    , _visualItems(NULL)
60
    , _settingsItem(NULL)
61
    , _firstItemsFromVehicle(false)
DonLakeFlyer's avatar
DonLakeFlyer committed
62
    , _itemsRequested(false)
63 64
    , _surveyMissionItemName(tr("Survey"))
    , _fwLandingMissionItemName(tr("Fixed Wing Landing"))
65
    , _structureScanMissionItemName(tr("Structure Scan"))
66
    , _corridorScanMissionItemName(tr("Corridor Scan"))
67
    , _appSettings(qgcApp()->toolbox()->settingsManager()->appSettings())
68
    , _progressPct(0)
69 70
    , _currentPlanViewIndex(-1)
    , _currentPlanViewItem(NULL)
71
{
72
    _resetMissionFlightStatus();
73
    managerVehicleChanged(_managerVehicle);
74 75 76 77
}

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

79 80
}

81 82 83 84 85 86 87 88 89
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;
90 91 92
    _missionFlightStatus.cruiseSpeed =          _controllerVehicle->defaultCruiseSpeed();
    _missionFlightStatus.hoverSpeed =           _controllerVehicle->defaultHoverSpeed();
    _missionFlightStatus.vehicleSpeed =         _controllerVehicle->multiRotor() || _managerVehicle->vtol() ? _missionFlightStatus.hoverSpeed : _missionFlightStatus.cruiseSpeed;
93
    _missionFlightStatus.vehicleYaw =           0.0;
94
    _missionFlightStatus.gimbalYaw =            std::numeric_limits<double>::quiet_NaN();
95
    _missionFlightStatus.gimbalPitch =          std::numeric_limits<double>::quiet_NaN();
96 97 98 99 100 101 102 103 104 105 106 107

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

108 109 110 111
    _controllerVehicle->firmwarePlugin()->batteryConsumptionData(_controllerVehicle, _missionFlightStatus.mAhBattery, _missionFlightStatus.hoverAmps, _missionFlightStatus.cruiseAmps);
    if (_missionFlightStatus.mAhBattery != 0) {
        double batteryPercentRemainingAnnounce = qgcApp()->toolbox()->settingsManager()->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toDouble();
        _missionFlightStatus.ampMinutesAvailable = (double)_missionFlightStatus.mAhBattery / 1000.0 * 60.0 * ((100.0 - batteryPercentRemainingAnnounce) / 100.0);
112
    }
113 114 115 116 117 118 119 120 121 122 123

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

124 125
}

126 127
void MissionController::start(bool editMode)
{
128 129
    qCDebug(MissionControllerLog) << "start editMode" << editMode;

130
    PlanElementController::start(editMode);
131 132 133 134 135
    _init();
}

void MissionController::_init(void)
{
136
    // We start with an empty mission
137
    _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
138
    _addMissionSettings(_visualItems, false /* addToCenter */);
139
    _initAllVisualItems();
140 141
}

142
// Called when new mission items have completed downloading from Vehicle
143
void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllRequested)
144
{
145 146
    qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle";

DonLakeFlyer's avatar
DonLakeFlyer committed
147 148 149
    // Fly view always reloads on _loadComplete
    // Plan view only reloads on _loadComplete if specifically requested
    if (!_editMode || removeAllRequested || _itemsRequested) {
150
        // Fly Mode (accept if):
Don Gagne's avatar
Don Gagne committed
151
        //      - Always accepts new items from the vehicle so Fly view is kept up to date
152
        // Edit Mode (accept if):
153
        //      - Either a load from vehicle was manually requested or
Don Gagne's avatar
Don Gagne committed
154
        //      - The initial automatic load from a vehicle completed and the current editor is empty
155
        //      - Remove all way requested from Fly view (clear mission on flight end)
156

157
        QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
158
        const QList<MissionItem*>& newMissionItems = _missionManager->missionItems();
159 160 161
        qCDebug(MissionControllerLog) << "loading from vehicle: count"<< newMissionItems.count();

        int i = 0;
162
        if (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() && newMissionItems.count() != 0) {
163
            // First item is fake home position
DonLakeFlyer's avatar
DonLakeFlyer committed
164
            _addMissionSettings(newControllerMissionItems, false /* addToCenter */);
165
            MissionSettingsItem* settingsItem = newControllerMissionItems->value<MissionSettingsItem*>(0);
166 167 168 169
            if (!settingsItem) {
                qWarning() << "First item is not settings item";
                return;
            }
170 171 172 173
            MissionItem* fakeHomeItem = newMissionItems[0];
            if (fakeHomeItem->coordinate().latitude() != 0 || fakeHomeItem->coordinate().longitude() != 0) {
                settingsItem->setCoordinate(fakeHomeItem->coordinate());
            }
174 175
            i = 1;
        }
176

177 178
        for (; i<newMissionItems.count(); i++) {
            const MissionItem* missionItem = newMissionItems[i];
179
            newControllerMissionItems->append(new SimpleMissionItem(_controllerVehicle, _editMode, *missionItem, this));
180 181 182
        }

        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
183
        _visualItems->deleteLater();
184
        _settingsItem = NULL;
185 186
        _visualItems = NULL;
        _updateContainsItems(); // This will clear containsItems which will be set again below. This will re-pop Start Mission confirmation.
187 188
        _visualItems = newControllerMissionItems;

189
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
DonLakeFlyer's avatar
DonLakeFlyer committed
190
            _addMissionSettings(_visualItems, _editMode && _visualItems->count() > 0 /* addToCenter */);
191 192
        }

193
        MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
194

195
        _initAllVisualItems();
196
        _updateContainsItems();
197
        emit newItemsFromVehicle();
198
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
199
    _itemsRequested = false;
200 201
}

202
void MissionController::loadFromVehicle(void)
203
{
DonLakeFlyer's avatar
DonLakeFlyer committed
204 205 206 207 208 209 210 211
    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();
    }
212 213
}

214
void MissionController::sendToVehicle(void)
215
{
DonLakeFlyer's avatar
DonLakeFlyer committed
216 217 218 219 220
    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
221
        qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
DonLakeFlyer's avatar
DonLakeFlyer committed
222 223 224 225 226 227 228 229 230
        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
231 232
}

233 234 235 236 237
/// Converts from visual items to MissionItems
///     @param missionItemParent QObject parent for newly allocated MissionItems
/// @return true: Mission end action was added to end of list
bool MissionController::_convertToMissionItems(QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
238 239 240 241
    if (visualMissionItems->count() == 0) {
        return false;
    }

242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257
    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
258
    MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
259 260 261 262 263 264 265
    if (settingsItem) {
        endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
    }

    return endActionSet;
}

266 267 268 269
void MissionController::convertToKMLDocument(QDomDocument& document)
{
    QJsonObject missionJson;
    QmlObjectListModel* visualItems = new QmlObjectListModel();
270
    QList<MissionItem*> missionItems;
271 272 273
    QString error;
    save(missionJson);
    _loadItemsFromJson(missionJson, visualItems, error);
274 275 276 277 278
    _convertToMissionItems(visualItems, missionItems, this);

    if (missionItems.count() == 0) {
        return;
    }
279 280 281 282 283 284 285

    float altitude = missionJson[_jsonPlannedHomePositionKey].toArray()[2].toDouble();

    QString coord;
    QStringList coords;
    // Drop home position
    bool dropPoint = true;
286
    for(const auto& item : missionItems) {
287 288 289 290 291
        if(dropPoint) {
            dropPoint = false;
            continue;
        }
        const MissionCommandUIInfo* uiInfo = \
292
                qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, item->command());
293 294

        if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
yaoling's avatar
yaoling committed
295
            coord = QString::number(item->param6(),'f',7) \
296 297 298 299
                    + "," \
                    + QString::number(item->param5(),'f',7) \
                    + "," \
                    + QString::number(item->param7() + altitude,'f',2);
300 301 302 303 304 305 306 307
            coords.append(coord);
        }
    }
    Kml kml;
    kml.points(coords);
    kml.save(document);
}

Don Gagne's avatar
Don Gagne committed
308 309 310
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
311
        QList<MissionItem*> rgMissionItems;
312

313
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
314

315
        // PlanManager takes control of MissionItems so no need to delete
316
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
317 318
    }
}
319

320 321 322 323 324 325
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
326 327
        VisualMissionItem* lastItem = _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1);
        return lastItem->lastSequenceNumber() + 1;
328 329 330
    }
}

331
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
332
{
333
    int sequenceNumber = _nextSequenceNumber();
334
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, this);
335
    newItem->setSequenceNumber(sequenceNumber);
336
    newItem->setCoordinate(coordinate);
337 338 339
    newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
    _initVisualItem(newItem);
    if (_visualItems->count() == 1) {
340 341 342 343
        MavlinkQmlSingleton::Qml_MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF : MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF;
        if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains((MAV_CMD)takeoffCmd)) {
            newItem->setCommand(takeoffCmd);
        }
344
    }
345
    newItem->setDefaultsForCommand();
Don Gagne's avatar
Don Gagne committed
346
    if ((MAV_CMD)newItem->command() == MAV_CMD_NAV_WAYPOINT) {
347 348
        double      prevAltitude;
        MAV_FRAME   prevFrame;
349

350 351 352
        if (_findPreviousAltitude(i, &prevAltitude, &prevFrame)) {
            newItem->missionItem().setFrame(prevFrame);
            newItem->missionItem().setParam7(prevAltitude);
353
        }
354
    }
355
    newItem->setMissionFlightStatus(_missionFlightStatus);
356
    _visualItems->insert(i, newItem);
357 358 359

    _recalcAll();

360
    return newItem->sequenceNumber();
361 362
}

363 364 365 366 367
int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
{
    int sequenceNumber = _nextSequenceNumber();
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, this);
    newItem->setSequenceNumber(sequenceNumber);
368 369 370
    newItem->setCommand((MavlinkQmlSingleton::Qml_MAV_CMD)(_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains((MAV_CMD)MAV_CMD_DO_SET_ROI_LOCATION) ?
        MAV_CMD_DO_SET_ROI_LOCATION :
        MAV_CMD_DO_SET_ROI));
371 372
    _initVisualItem(newItem);
    newItem->setDefaultsForCommand();
373
    newItem->setCoordinate(coordinate);
374 375 376 377 378 379 380 381 382 383 384 385 386 387 388

    double      prevAltitude;
    MAV_FRAME   prevFrame;

    if (_findPreviousAltitude(i, &prevAltitude, &prevFrame)) {
        newItem->missionItem().setFrame(prevFrame);
        newItem->missionItem().setParam7(prevAltitude);
    }
    _visualItems->insert(i, newItem);

    _recalcAll();

    return newItem->sequenceNumber();
}

389
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
390
{
391
    ComplexMissionItem* newItem;
392
    bool surveyStyleItem = false;
393

394
    int sequenceNumber = _nextSequenceNumber();
395
    if (itemName == _surveyMissionItemName) {
396
        newItem = new SurveyMissionItem(_controllerVehicle, _visualItems);
397
        newItem->setCoordinate(mapCenterCoordinate);
398 399 400 401 402 403 404 405 406 407 408 409 410 411
        surveyStyleItem = true;
    } else if (itemName == _fwLandingMissionItemName) {
        newItem = new FixedWingLandingComplexItem(_controllerVehicle, _visualItems);
    } else if (itemName == _structureScanMissionItemName) {
        newItem = new StructureScanComplexItem(_controllerVehicle, _visualItems);
    } else if (itemName == _corridorScanMissionItemName) {
        newItem = new CorridorScanComplexItem(_controllerVehicle, _visualItems);
        surveyStyleItem = true;
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }

    if (surveyStyleItem) {
412 413 414
        bool rollSupported = false;
        bool pitchSupported = false;
        bool yawSupported = false;
415 416 417

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

418 419
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
        CameraSection* cameraSection = settingsItem->cameraSection();
420

421
        // Set camera to photo mode (leave alone if user already specified)
422
        if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
423
            cameraSection->setSpecifyCameraMode(true);
424
            cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
425
        }
426

427
        // Point gimbal straight down
428
        if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
429 430 431
            // If the user already specified a gimbal angle leave it alone
            if (!cameraSection->specifyGimbal()) {
                cameraSection->setSpecifyGimbal(true);
432
                cameraSection->gimbalPitch()->setRawValue(-90.0);
433 434
            }
        }
435
    }
436

437
    newItem->setSequenceNumber(sequenceNumber);
438
    _initVisualItem(newItem);
439

440
    _visualItems->insert(i, newItem);
441 442 443

    _recalcAll();

444
    return newItem->sequenceNumber();
445 446
}

447 448
void MissionController::removeMissionItem(int index)
{
449 450 451 452 453
    if (index <= 0 || index >= _visualItems->count()) {
        qWarning() << "MissionController::removeMissionItem called with bad index - count:index" << _visualItems->count() << index;
        return;
    }

454
    bool removeSurveyStyle = _visualItems->value<SurveyMissionItem*>(index) || _visualItems->value<CorridorScanComplexItem*>(index);
455
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
456

457
    _deinitVisualItem(item);
458
    item->deleteLater();
459

460 461
    if (removeSurveyStyle) {
        // Determine if the mission still has another survey style item in it
462 463
        bool foundSurvey = false;
        for (int i=1; i<_visualItems->count(); i++) {
464
            if (_visualItems->value<SurveyMissionItem*>(i) || _visualItems->value<CorridorScanComplexItem*>(index)) {
465 466 467 468 469
                foundSurvey = true;
                break;
            }
        }

470
        // If there is no longer a survey item in the mission remove added commands
471 472 473 474
        if (!foundSurvey) {
            bool rollSupported = false;
            bool pitchSupported = false;
            bool yawSupported = false;
475 476
            MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
            CameraSection* cameraSection = settingsItem->cameraSection();
477
            if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
478
                if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
479 480 481
                    cameraSection->setSpecifyGimbal(false);
                }
            }
482
            if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
483 484
                cameraSection->setSpecifyCameraMode(false);
            }
485 486 487
        }
    }

488
    _recalcAll();
489
    setDirty(true);
490 491
}

492
void MissionController::removeAll(void)
493
{
494 495
    if (_visualItems) {
        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
496
        _visualItems->deleteLater();
497
        _settingsItem = NULL;
498
        _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
499
        _addMissionSettings(_visualItems, false /* addToCenter */);
500
        _initAllVisualItems();
501
        setDirty(true);
502
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
503 504 505
    }
}

506
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
507 508 509 510 511 512 513 514 515
{
    // 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)) {
516 517 518
        return false;
    }

519
    // Read complex items
520
    QList<SurveyMissionItem*> surveyItems;
521 522 523 524
    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];
525

526 527 528 529 530
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

531
        SurveyMissionItem* item = new SurveyMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
532 533
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
534
            surveyItems.append(item);
535 536
        } else {
            return false;
537
        }
538
    }
539

540 541 542 543 544
    // 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
545
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
546

547
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
548 549 550 551
    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
552 553
        if (nextComplexItemIndex < surveyItems.count()) {
            SurveyMissionItem* complexItem = surveyItems[nextComplexItemIndex];
554 555 556 557 558 559 560 561 562 563 564 565 566 567

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

568 569 570 571 572
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
573
            const QJsonObject itemObject = itemValue.toObject();
574
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
575
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
576
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
577
                nextSequenceNumber = item->lastSequenceNumber() + 1;
578
                visualItems->append(item);
579 580 581 582
            } else {
                return false;
            }
        }
583
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
584 585

    if (json.contains(_jsonPlannedHomePositionKey)) {
586
        SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
587

Don Gagne's avatar
Don Gagne committed
588
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
589
            MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
590 591 592
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
593 594 595 596
        } else {
            return false;
        }
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
597
        _addMissionSettings(visualItems, true /* addToCenter */);
598 599 600 601 602
    }

    return true;
}

603
bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
604 605 606 607 608 609
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
610
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
611 612
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
613 614 615 616 617 618 619
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

620
    // Mission Settings
621
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
622

623 624
    if (_masterController->offline()) {
        // We only update if offline since if we are online we use the online vehicle settings
625 626 627 628
        appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType((MAV_AUTOPILOT)json[_jsonFirmwareTypeKey].toInt()));
        if (json.contains(_jsonVehicleTypeKey)) {
            appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType((MAV_TYPE)json[_jsonVehicleTypeKey].toInt()));
        }
629
    }
630
    if (json.contains(_jsonCruiseSpeedKey)) {
631
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
632 633
    }
    if (json.contains(_jsonHoverSpeedKey)) {
634
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
635 636
    }

637 638 639 640 641
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
642 643
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669
    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) {
670
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, visualItems);
671
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
672
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
673
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
674 675 676 677 678 679 680 681 682 683 684 685 686 687 688
                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();

            if (complexItemType == SurveyMissionItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Survey: nextSequenceNumber" << nextSequenceNumber;
689
                SurveyMissionItem* surveyItem = new SurveyMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
690 691 692 693 694 695
                if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(surveyItem);
696
            } else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
697
                qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
698
                FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(_controllerVehicle, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
699 700 701 702 703 704
                if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(landingItem);
705 706 707 708 709 710 711 712 713
            } else if (complexItemType == StructureScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Structure Scan: nextSequenceNumber" << nextSequenceNumber;
                StructureScanComplexItem* structureItem = new StructureScanComplexItem(_controllerVehicle, visualItems);
                if (!structureItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = structureItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Structure Scan load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(structureItem);
714 715 716 717 718 719 720 721 722
            } else if (complexItemType == CorridorScanComplexItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Corridor Scan: nextSequenceNumber" << nextSequenceNumber;
                CorridorScanComplexItem* corridorItem = new CorridorScanComplexItem(_controllerVehicle, visualItems);
                if (!corridorItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = corridorItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Corridor Scan load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(corridorItem);
723
            } else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
724
                qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
725
                MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
726 727 728 729 730 731
                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
732 733 734 735 736 737 738 739 740 741 742 743 744
            } 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);
Don Gagne's avatar
Don Gagne committed
745
            if ((MAV_CMD)doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768
                bool found = false;
                int findDoJumpId = doJumpItem->missionItem().param1();
                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;
}

769 770 771 772 773 774 775 776
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;
777 778 779 780 781 782
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
783 784

    if (fileVersion == 1) {
785
        return _loadJsonMissionFileV1(json, visualItems, errorString);
786
    } else {
787
        return _loadJsonMissionFileV2(json, visualItems, errorString);
788 789 790
    }
}

791
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
792
{
793 794
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
795 796 797 798 799 800 801 802 803

    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;
804
            plannedHomePositionInFile = true;
805 806 807
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
808
            plannedHomePositionInFile = false;
809 810 811 812
        }
    }

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

817
        while (!stream.atEnd()) {
818
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
819 820

            if (item->load(stream)) {
821 822 823 824 825 826
                if (firstItem && plannedHomePositionInFile) {
                    settingsItem->setCoordinate(item->coordinate());
                } else {
                    visualItems->append(item);
                }
                firstItem = false;
827
            } else {
828
                errorString = tr("The mission file is corrupted.");
829 830 831 832
                return false;
            }
        }
    } else {
833
        errorString = tr("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
834 835 836
        return false;
    }

837
    if (!plannedHomePositionInFile) {
838 839 840 841 842
        // 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));
            if (item && item->command() == MavlinkQmlSingleton::MAV_CMD_DO_JUMP) {
                item->missionItem().setParam1((int)item->missionItem().param1() + 1);
Don Gagne's avatar
Don Gagne committed
843 844
            }
        }
845 846 847
    }

    return true;
848 849
}

850
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
851
{
Don Gagne's avatar
Don Gagne committed
852 853 854
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
855
        _settingsItem = NULL;
Don Gagne's avatar
Don Gagne committed
856 857
    }

858
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
859 860

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

864
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
865

Don Gagne's avatar
Don Gagne committed
866
    _initAllVisualItems();
867
}
868

869 870 871 872 873 874
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

875
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900
        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;
901
    }
902

903 904 905 906 907 908 909 910 911 912 913 914 915
    _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);
916
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
917 918 919 920 921 922
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
923
    return true;
924 925
}

926
void MissionController::save(QJsonObject& json)
927
{
928
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
929

930
    // Mission settings
931

932 933 934 935 936 937 938 939
    MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsItem";
        return;
    }
    QJsonValue coordinateValue;
    JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
    json[_jsonPlannedHomePositionKey] = coordinateValue;
940 941 942 943
    json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
944

945
    // Save the visual items
946

947 948 949
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
950

951 952
        visualItem->save(rgJsonMissionItems);
    }
953

954 955 956
    // Mission settings has a special case for end mission action
    if (settingsItem) {
        QList<MissionItem*> rgMissionItems;
957

958 959 960 961 962
        if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
963
        }
964 965
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
966 967 968
        }
    }

969
    json[_jsonItemsKey] = rgJsonMissionItems;
970 971
}

972
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
973
{
Don Gagne's avatar
Don Gagne committed
974
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
975
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
976 977 978 979
    bool            distanceOk =    false;

    // Convert to fixed altitudes

980
    distanceOk = true;
981
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
982 983
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
984
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
985
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
986 987 988
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
989 990 991
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
992
    } else {
Don Gagne's avatar
Don Gagne committed
993
        *altDifference = 0.0;
994
        *azimuth = 0.0;
995
        *distance = 0.0;
996 997 998
    }
}

999
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
1000 1001 1002 1003 1004 1005 1006
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

1007
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
1008 1009
}

1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031
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;
    }
}

1032 1033
void MissionController::_recalcWaypointLines(void)
{
1034 1035 1036
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

1037
    bool homePositionValid = _settingsItem->coordinate().isValid();
1038

1039
    qCDebug(MissionControllerLog) << "_recalcWaypointLines homePositionValid" << homePositionValid;
1040

Nate Weibley's avatar
Nate Weibley committed
1041 1042
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
1043
    _waypointLines.clear();
1044
    _waypointPath.clear();
1045

1046 1047 1048 1049 1050 1051 1052 1053 1054
    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;
1055 1056 1057
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));

1058 1059 1060 1061 1062 1063
        // 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;
1064
            }
1065 1066
        }

1067 1068 1069 1070 1071 1072
        if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
            firstCoordinateItem = false;
            if (lastCoordinateItem != _settingsItem || (homePositionValid && linkStartToHome)) {
                if (_editMode) {
                    VisualItemPair pair(lastCoordinateItem, item);
                    _addWaypointLineSegment(old_table, pair);
1073 1074
                }
            }
1075 1076
            _waypointPath.append(QVariant::fromValue(item->coordinate()));
            lastCoordinateItem = item;
1077 1078
        }
    }
1079 1080 1081 1082 1083 1084

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

    if (linkEndToHome && lastCoordinateItem != _settingsItem && homePositionValid) {
1085 1086 1087 1088 1089 1090
        if (_editMode) {
            VisualItemPair pair(lastCoordinateItem, _settingsItem);
            _addWaypointLineSegment(old_table, pair);
        } else {
            _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
        }
1091
    }
1092 1093 1094 1095

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1096 1097
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
1098 1099 1100 1101 1102 1103 1104 1105 1106 1107
            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
1108
    _recalcMissionFlightStatus();
1109

1110 1111 1112 1113 1114 1115 1116 1117
    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)));
    }

1118
    emit waypointLinesChanged();
1119
    emit waypointPathChanged();
1120 1121
}

1122 1123 1124 1125 1126 1127
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);
1128 1129 1130
        // 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.
1131
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154
            _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);
}

1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201
/// Adds additional time to a mission as specified by the command
void MissionController::_addCommandTimeDelay(SimpleMissionItem* simpleItem, bool vtolInHover)
{
    double seconds = 0;

    if (!simpleItem) {
        return;
    }

    // This routine is currently quite minimal and only handles the simple cases.
    switch ((int)simpleItem->command()) {
    case MAV_CMD_NAV_WAYPOINT:
    case MAV_CMD_CONDITION_DELAY:
        seconds = simpleItem->missionItem().param1();
        break;
    }

    _addTimeDistance(vtolInHover, 0, 0, seconds, 0, -1);
}

/// 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
1202
void MissionController::_recalcMissionFlightStatus()
1203
{
1204
    if (!_visualItems->count()) {
1205
        return;
1206
    }
1207 1208 1209 1210

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

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1213
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1214

1215 1216 1217
    // 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.
1218

1219
    // No values for first item
1220
    lastCoordinateItem->setAltDifference(0.0);
1221
    lastCoordinateItem->setAzimuth(0.0);
1222
    lastCoordinateItem->setDistance(0.0);
1223

1224 1225
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1226 1227
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1228

1229
    _resetMissionFlightStatus();
1230

DonLakeFlyer's avatar
DonLakeFlyer committed
1231
    bool vtolInHover = true;
1232
    bool linkStartToHome = false;
1233 1234 1235 1236 1237 1238 1239 1240 1241 1242
    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();
        }
    }
1243

DonLakeFlyer's avatar
DonLakeFlyer committed
1244
    for (int i=0; i<_visualItems->count(); i++) {
1245
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1246 1247 1248
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1249 1250
        // Assume the worst
        item->setAzimuth(0.0);
1251
        item->setDistance(0.0);
1252

DonLakeFlyer's avatar
DonLakeFlyer committed
1253 1254 1255
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1256
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1257
                _missionFlightStatus.hoverSpeed = newSpeed;
1258
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1259 1260
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1261
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1262
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1263
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1264 1265
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1266
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1267 1268 1269 1270
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1271 1272 1273 1274 1275 1276 1277
        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
1278 1279 1280 1281 1282
        }

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

1285 1286 1287
        // Link back to home if first item is takeoff and we have home position
        if (firstCoordinateItem && simpleItem && simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) {
            if (showHomePosition) {
1288
                linkStartToHome = true;
1289 1290 1291 1292 1293 1294 1295
                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);
                }
1296 1297 1298 1299
            }
        }

        // Update VTOL state
1300
        if (simpleItem && _controllerVehicle->vtol()) {
1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314
            switch (simpleItem->command()) {
            case MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF:
                vtolInHover = false;
                break;
            case MavlinkQmlSingleton::MAV_CMD_NAV_LAND:
                vtolInHover = false;
                break;
            case MavlinkQmlSingleton::MAV_CMD_DO_VTOL_TRANSITION:
            {
                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;
1315 1316
                }
            }
1317 1318 1319
                break;
            default:
                break;
1320
            }
Don Gagne's avatar
Don Gagne committed
1321 1322
        }

1323 1324 1325
        // Check for command specific time delays
        _addCommandTimeDelay(simpleItem, vtolInHover);

1326
        if (item->specifiesCoordinate()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1327 1328
            // Update vehicle yaw assuming direction to next waypoint
            if (item != lastCoordinateItem) {
1329 1330
                _missionFlightStatus.vehicleYaw = lastCoordinateItem->exitCoordinate().azimuthTo(item->coordinate());
                lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
DonLakeFlyer's avatar
DonLakeFlyer committed
1331 1332
            }

1333 1334
            // Keep track of the min/max altitude for all waypoints so we can show altitudes as a percentage

1335
            double absoluteAltitude = item->coordinate().altitude();
1336
            if (item->coordinateHasRelativeAltitude()) {
1337 1338 1339 1340 1341
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1342 1343 1344 1345
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1346 1347 1348
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1349
                firstCoordinateItem = false;
1350
                if (lastCoordinateItem != _settingsItem || linkStartToHome) {
1351 1352
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1353

1354
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1355 1356 1357
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1358

1359
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1360

DonLakeFlyer's avatar
DonLakeFlyer committed
1361 1362 1363
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1364
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1365
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1366

1367
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1368 1369
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1370
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1371

1372 1373
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1374 1375
                    double extraTime = complexItem->additionalTimeDelay();
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, extraTime, distance, item->sequenceNumber());
1376
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1377 1378

                item->setMissionFlightStatus(_missionFlightStatus);
1379
            }
1380 1381

            lastCoordinateItem = item;
1382 1383
        }
    }
1384
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1385

1386 1387 1388 1389 1390 1391 1392 1393
    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();
1394
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1395 1396
    }

1397 1398 1399
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1400

DonLakeFlyer's avatar
DonLakeFlyer committed
1401 1402 1403 1404 1405 1406 1407
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1408 1409
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1410

1411 1412
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1413 1414
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1415 1416 1417

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1418
            if (item->coordinateHasRelativeAltitude()) {
1419 1420 1421 1422
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1423
                item->setTerrainPercent(qQNaN());
1424 1425
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1426 1427 1428
                if (!qIsNaN(item->terrainAltitude())) {
                    item->setTerrainPercent((item->terrainAltitude() - minAltSeen) / altRange);
                }
1429
            }
1430 1431 1432 1433
        }
    }
}

1434 1435 1436
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1437 1438 1439 1440 1441 1442
    // Setup ascending sequence numbers for all visual items

    int sequenceNumber = 0;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));

1443 1444
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1445 1446 1447
    }
}

1448 1449 1450
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1451
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1452 1453 1454

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

1455 1456
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1457 1458 1459 1460 1461

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1462
        } else if (item->isSimpleItem()) {
1463 1464 1465 1466 1467
            currentParentItem->childItems()->append(item);
        }
    }
}

1468 1469 1470 1471 1472 1473
void MissionController::_setPlannedHomePositionFromFirstCoordinate(void)
{
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1474
    // Set the planned home position to be a delta from first coordinate
1475 1476 1477 1478 1479 1480 1481 1482 1483 1484
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

        if (item->specifiesCoordinate()) {
            _settingsItem->setCoordinate(item->coordinate().atDistanceAndAzimuth(30, 0));
        }
    }
}


1485 1486
void MissionController::_recalcAll(void)
{
1487 1488 1489
    if (_editMode) {
        _setPlannedHomePositionFromFirstCoordinate();
    }
1490
    _recalcSequence();
1491 1492 1493 1494
    _recalcChildItems();
    _recalcWaypointLines();
}

1495
/// Initializes a new set of mission items
1496
void MissionController::_initAllVisualItems(void)
1497
{
1498 1499
    // Setup home position at index 0

1500 1501 1502
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1503 1504
        return;
    }
1505 1506 1507
    if (_editMode) {
        _settingsItem->setIsCurrentItem(true);
    }
1508

1509
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1510
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1511
    }
1512

1513 1514 1515
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1516

1517 1518 1519 1520
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1521

1522
    _recalcAll();
1523

1524
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1525 1526 1527
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1528
    emit containsItemsChanged(containsItems());
1529
    emit plannedHomePositionChanged(plannedHomePosition());
1530

1531
    setDirty(false);
1532 1533
}

1534
void MissionController::_deinitAllVisualItems(void)
1535
{
1536 1537 1538
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1539 1540
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1541 1542
    }

1543
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1544
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1545 1546
}

1547
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1548
{
1549
    setDirty(false);
1550

1551
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1552 1553
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1554 1555
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1556
    connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged,                this, &MissionController::_recalcMissionFlightStatus);
1557
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1558
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1559

1560 1561 1562 1563 1564 1565 1566 1567
    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";
        }
1568 1569
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1570
        if (complexItem) {
1571
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
1572
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
1573
            connect(complexItem, &ComplexMissionItem::additionalTimeDelayChanged,   this, &MissionController::_recalcMissionFlightStatus);
1574 1575 1576
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1577
    }
1578 1579
}

1580
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1581
{
1582 1583
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1584 1585
}

1586
void MissionController::_itemCommandChanged(void)
1587
{
1588 1589
    _recalcChildItems();
    _recalcWaypointLines();
1590 1591
}

1592
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1593
{
1594 1595 1596 1597 1598 1599
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1600

1601 1602
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1603
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1604 1605
        return;
    }
1606

1607 1608
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1609 1610
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1611 1612 1613 1614 1615
    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);
1616
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1617 1618 1619 1620
    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);
1621

1622 1623
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1624
    }
1625

1626
    emit complexMissionItemNamesChanged();
1627
    emit resumeMissionIndexChanged();
1628 1629
}

1630
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1631
{
1632 1633
    if (_visualItems) {
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1634
        if (settingsItem) {
1635
            settingsItem->setHomePositionFromVehicle(homePosition);
1636
        } else {
1637
            qWarning() << "First item is not MissionSettingsItem";
1638
        }
1639 1640 1641
        // Don't let this trip the dirty bit. Otherwise plan will keep getting marked dirty if vehicle home
        // changes.
        _visualItems->setDirty(false);
1642
    }
1643 1644 1645
}

void MissionController::_inProgressChanged(bool inProgress)
1646
{
1647
    emit syncInProgressChanged(inProgress);
1648
}
1649

1650
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
1651
{
1652 1653 1654
    bool        found = false;
    double      foundAltitude;
    MAV_FRAME   foundFrame;
1655

1656 1657 1658 1659 1660 1661
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1664 1665 1666
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1667
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
1668 1669 1670
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1671
                    break;
1672 1673
                }
            }
1674 1675 1676
        }
    }

1677
    if (found) {
1678 1679
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1680 1681 1682
    }

    return found;
1683
}
1684 1685 1686 1687 1688 1689 1690 1691 1692 1693 1694 1695 1696

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

1697
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1698
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1699
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1700
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
1701

Don Gagne's avatar
Don Gagne committed
1702 1703
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1704
    visualItems->insert(0, settingsItem);
1705

1706 1707 1708 1709 1710 1711 1712 1713 1714 1715 1716 1717 1718 1719 1720 1721 1722 1723 1724 1725 1726 1727 1728 1729 1730
    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;
                    }
1731 1732
                }
            }
1733

1734 1735 1736
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1737
        }
Don Gagne's avatar
Don Gagne committed
1738 1739
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1740 1741
    }
}
1742

1743
int MissionController::resumeMissionIndex(void) const
1744
{
1745

1746
    int resumeIndex = 0;
1747

1748
    if (!_editMode) {
1749
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1750
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1751 1752
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1753 1754
        } else {
            resumeIndex = 0;
1755 1756 1757 1758 1759
        }
    }

    return resumeIndex;
}
1760

1761 1762 1763 1764 1765 1766 1767 1768 1769 1770 1771 1772 1773
int MissionController::currentMissionIndex(void) const
{
    if (_editMode) {
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

1774
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1775 1776
{
    if (!_editMode) {
1777
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1778 1779 1780
            sequenceNumber++;
        }

1781 1782
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1783 1784
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1785
        emit currentMissionIndexChanged(currentMissionIndex());
1786 1787
    }
}
1788

1789
bool MissionController::syncInProgress(void) const
1790
{
1791
    return _missionManager->inProgress();
1792 1793 1794 1795 1796 1797 1798 1799 1800 1801 1802 1803
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1804
    }
1805
}
1806

1807 1808
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1809 1810 1811 1812
    if (_editMode) {
        // First we look for a Fixed Wing Landing Pattern which is at the end
        FixedWingLandingComplexItem::scanForItem(visualItems, vehicle);
    }
1813

1814 1815 1816 1817 1818 1819
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1820 1821 1822 1823 1824 1825 1826
        if (_editMode) {
            MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
            if (settingsItem) {
                scanIndex++;
                settingsItem->scanForMissionSettings(visualItems, scanIndex);
                continue;
            }
1827 1828 1829
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1830
        if (simpleItem) {
1831 1832 1833 1834 1835
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
1836 1837 1838
        }
    }
}
1839 1840 1841 1842 1843 1844 1845 1846 1847 1848 1849 1850 1851

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
1852 1853 1854 1855 1856 1857 1858 1859
    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();
    }
1860
}
1861 1862 1863 1864 1865 1866

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

    complexItems.append(_surveyMissionItemName);
1867
    complexItems.append(_corridorScanMissionItemName);
1868
    if (_controllerVehicle->fixedWing()) {
1869 1870
        complexItems.append(_fwLandingMissionItemName);
    }
1871 1872 1873
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
        complexItems.append(_structureScanMissionItemName);
    }
1874 1875 1876

    return complexItems;
}
1877

1878 1879
void MissionController::resumeMission(int resumeIndex)
{
1880
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1881 1882
        resumeIndex--;
    }
1883
    _missionManager->generateResumeMission(resumeIndex);
1884
}
1885 1886 1887 1888 1889 1890 1891 1892 1893

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1894 1895 1896 1897 1898 1899 1900 1901 1902 1903

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

1905 1906 1907 1908 1909 1910 1911
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
1912 1913 1914 1915 1916 1917

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
1918 1919 1920

bool MissionController::showPlanFromManagerVehicle (void)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1921
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle" << _editMode;
DonLakeFlyer's avatar
DonLakeFlyer committed
1922 1923
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
1924
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
1925 1926 1927 1928 1929 1930 1931 1932 1933 1934 1935 1936 1937 1938 1939 1940 1941 1942 1943
    } 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;
        }
    }
}

1944
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1945
{
1946 1947
    // Fly view always reloads on send complete
    if (!error && !_editMode) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1948 1949 1950 1951
        showPlanFromManagerVehicle();
    }
}

1952
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1953
{
1954 1955 1956 1957
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1958
}
1959 1960 1961 1962 1963 1964 1965 1966 1967 1968 1969 1970 1971 1972 1973 1974 1975 1976 1977 1978 1979 1980 1981 1982 1983 1984 1985 1986 1987 1988

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