MissionController.cc 76.1 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 "JsonHelper.h"
23
#include "ParameterManager.h"
24
#include "QGroundControlQmlGlobal.h"
25
#include "SettingsManager.h"
26
#include "AppSettings.h"
27
#include "MissionSettingsItem.h"
28
#include "QGCQGeoCoordinate.h"
29
#include "PlanMasterController.h"
30
#include "KML.h"
31

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

37 38
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

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

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

77 78
}

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

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

105 106 107 108
    _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);
109
    }
110 111 112 113 114 115 116 117 118 119 120

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

121 122
}

123 124
void MissionController::start(bool editMode)
{
125 126
    qCDebug(MissionControllerLog) << "start editMode" << editMode;

127
    PlanElementController::start(editMode);
128 129 130 131 132
    _init();
}

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

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

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

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

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

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

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

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

190
        if (_editMode) {
191
            MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
192
        }
193

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

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

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

232 233 234 235 236
/// 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
237 238 239 240
    if (visualMissionItems->count() == 0) {
        return false;
    }

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

    return endActionSet;
}

265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289
void MissionController::convertToKMLDocument(QDomDocument& document)
{
    QJsonObject missionJson;
    QmlObjectListModel* visualItems = new QmlObjectListModel();
    QList<MissionItem*> missionItens;
    QString error;
    save(missionJson);
    _loadItemsFromJson(missionJson, visualItems, error);
    _convertToMissionItems(visualItems, missionItens, this);

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

    QString coord;
    QStringList coords;
    // Drop home position
    bool dropPoint = true;
    for(const auto& item : missionItens) {
        if(dropPoint) {
            dropPoint = false;
            continue;
        }
        const MissionCommandUIInfo* uiInfo = \
            qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, item->command());

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

Don Gagne's avatar
Don Gagne committed
303 304 305
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
306
        QList<MissionItem*> rgMissionItems;
307

308
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
309

310
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
311

312 313
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
314
        }
315 316
    }
}
317

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

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

345 346 347
        if (_findPreviousAltitude(i, &prevAltitude, &prevFrame)) {
            newItem->missionItem().setFrame(prevFrame);
            newItem->missionItem().setParam7(prevAltitude);
348
        }
349
    }
350
    _visualItems->insert(i, newItem);
351 352 353

    _recalcAll();

354
    return newItem->sequenceNumber();
355 356
}

357
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
358
{
359 360
    ComplexMissionItem* newItem;

361
    int sequenceNumber = _nextSequenceNumber();
362
    if (itemName == _surveyMissionItemName) {
363
        newItem = new SurveyMissionItem(_controllerVehicle, _visualItems);
364
        newItem->setCoordinate(mapCenterCoordinate);
365 366 367 368
        // If the vehicle is known to have a gimbal then we automatically point the gimbal straight down if not already set
        bool rollSupported = false;
        bool pitchSupported = false;
        bool yawSupported = false;
369 370 371
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
        CameraSection* cameraSection = settingsItem->cameraSection();
        // Set camera to photo mode (leave alone if user already specified)
372
        if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
373
            cameraSection->setSpecifyCameraMode(true);
374
            cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
375 376
        }
        // Point gimbal straight down
377
        if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
378 379 380
            // If the user already specified a gimbal angle leave it alone
            if (!cameraSection->specifyGimbal()) {
                cameraSection->setSpecifyGimbal(true);
381
                cameraSection->gimbalPitch()->setRawValue(-90.0);
382 383
            }
        }
384
    } else if (itemName == _fwLandingMissionItemName) {
385
        newItem = new FixedWingLandingComplexItem(_controllerVehicle, _visualItems);
386 387
    } else if (itemName == _structureScanMissionItemName) {
        newItem = new StructureScanComplexItem(_controllerVehicle, _visualItems);
388 389 390 391
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }
392
    newItem->setSequenceNumber(sequenceNumber);
393
    _initVisualItem(newItem);
394

395
    _visualItems->insert(i, newItem);
396 397 398

    _recalcAll();

399
    return newItem->sequenceNumber();
400 401
}

402 403
void MissionController::removeMissionItem(int index)
{
404 405 406 407 408 409
    if (index <= 0 || index >= _visualItems->count()) {
        qWarning() << "MissionController::removeMissionItem called with bad index - count:index" << _visualItems->count() << index;
        return;
    }

    bool surveyRemoved = _visualItems->value<SurveyMissionItem*>(index);
410
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
411

412
    _deinitVisualItem(item);
413
    item->deleteLater();
414

415 416 417 418 419 420 421 422 423 424
    if (surveyRemoved) {
        // Determine if the mission still has another survey in it
        bool foundSurvey = false;
        for (int i=1; i<_visualItems->count(); i++) {
            if (_visualItems->value<SurveyMissionItem*>(i)) {
                foundSurvey = true;
                break;
            }
        }

425
        // If there is no longer a survey item in the mission remove added commands
426 427 428 429
        if (!foundSurvey) {
            bool rollSupported = false;
            bool pitchSupported = false;
            bool yawSupported = false;
430 431
            MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
            CameraSection* cameraSection = settingsItem->cameraSection();
432
            if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
433
                if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
434 435 436
                    cameraSection->setSpecifyGimbal(false);
                }
            }
437
            if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
438 439
                cameraSection->setSpecifyCameraMode(false);
            }
440 441 442
        }
    }

443
    _recalcAll();
444
    setDirty(true);
445 446
}

447
void MissionController::removeAll(void)
448
{
449 450
    if (_visualItems) {
        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
451
        _visualItems->deleteLater();
452
        _settingsItem = NULL;
453
        _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
454
        _addMissionSettings(_visualItems, false /* addToCenter */);
455
        _initAllVisualItems();
456
        setDirty(true);
457
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
458 459 460
    }
}

461
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
462 463 464 465 466 467 468 469 470
{
    // 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)) {
471 472 473
        return false;
    }

474
    // Read complex items
475
    QList<SurveyMissionItem*> surveyItems;
476 477 478 479
    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];
480

481 482 483 484 485
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

486
        SurveyMissionItem* item = new SurveyMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
487 488
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
489
            surveyItems.append(item);
490 491
        } else {
            return false;
492
        }
493
    }
494

495 496 497 498 499
    // 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
500
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
501

502
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
503 504 505 506
    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
507 508
        if (nextComplexItemIndex < surveyItems.count()) {
            SurveyMissionItem* complexItem = surveyItems[nextComplexItemIndex];
509 510 511 512 513 514 515 516 517 518 519 520 521 522

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

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

Don Gagne's avatar
Don Gagne committed
528
            const QJsonObject itemObject = itemValue.toObject();
529
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
530
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
531
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
532
                nextSequenceNumber = item->lastSequenceNumber() + 1;
533
                visualItems->append(item);
534 535 536 537
            } else {
                return false;
            }
        }
538
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
539 540

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

Don Gagne's avatar
Don Gagne committed
543
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
544
            MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
545 546 547
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
548 549 550 551
        } else {
            return false;
        }
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
552
        _addMissionSettings(visualItems, true /* addToCenter */);
553 554 555 556 557
    }

    return true;
}

558
bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
559 560 561 562 563 564
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
565
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
566 567
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
568 569 570 571 572 573 574
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

575
    // Mission Settings
576
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
577

578 579
    if (_masterController->offline()) {
        // We only update if offline since if we are online we use the online vehicle settings
580 581 582 583
        appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType((MAV_AUTOPILOT)json[_jsonFirmwareTypeKey].toInt()));
        if (json.contains(_jsonVehicleTypeKey)) {
            appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType((MAV_TYPE)json[_jsonVehicleTypeKey].toInt()));
        }
584
    }
585
    if (json.contains(_jsonCruiseSpeedKey)) {
586
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
587 588
    }
    if (json.contains(_jsonHoverSpeedKey)) {
589
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
590 591
    }

592 593 594 595 596
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
597 598
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624
    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) {
625
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, visualItems);
626
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
627
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
628
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
629 630 631 632 633 634 635 636 637 638 639 640 641 642 643
                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;
644
                SurveyMissionItem* surveyItem = new SurveyMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
645 646 647 648 649 650
                if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(surveyItem);
651
            } else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
652
                qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
653
                FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(_controllerVehicle, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
654 655 656 657 658 659
                if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(landingItem);
660
            } else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
661
                qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
662
                MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
663 664 665 666 667 668
                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
669 670 671 672 673 674 675 676 677 678 679 680 681
            } 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
682
            if ((MAV_CMD)doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705
                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;
}

706 707 708 709 710 711 712 713
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;
714 715 716 717 718 719
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
720 721

    if (fileVersion == 1) {
722
        return _loadJsonMissionFileV1(json, visualItems, errorString);
723
    } else {
724
        return _loadJsonMissionFileV2(json, visualItems, errorString);
725 726 727
    }
}

728
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
729
{
730 731
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
732 733 734 735 736 737 738 739 740

    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;
741
            plannedHomePositionInFile = true;
742 743 744
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
745
            plannedHomePositionInFile = false;
746 747 748 749
        }
    }

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

754
        while (!stream.atEnd()) {
755
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
756 757

            if (item->load(stream)) {
758 759 760 761 762 763
                if (firstItem && plannedHomePositionInFile) {
                    settingsItem->setCoordinate(item->coordinate());
                } else {
                    visualItems->append(item);
                }
                firstItem = false;
764
            } else {
765
                errorString = tr("The mission file is corrupted.");
766 767 768 769
                return false;
            }
        }
    } else {
770
        errorString = tr("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
771 772 773
        return false;
    }

774
    if (!plannedHomePositionInFile) {
775 776 777 778 779
        // 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
780 781
            }
        }
782 783 784
    }

    return true;
785 786
}

787
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
788
{
Don Gagne's avatar
Don Gagne committed
789 790 791
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
792
        _settingsItem = NULL;
Don Gagne's avatar
Don Gagne committed
793 794
    }

795
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
796 797

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

801
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
802

Don Gagne's avatar
Don Gagne committed
803
    _initAllVisualItems();
804
}
805

806 807 808 809 810 811
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

812
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837
        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;
838
    }
839

840 841 842 843 844 845 846 847 848 849 850 851 852
    _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);
853
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
854 855 856 857 858 859
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
860
    return true;
861 862
}

863
void MissionController::save(QJsonObject& json)
864
{
865
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
866

867
    // Mission settings
868

869 870 871 872 873 874 875 876
    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;
877 878 879 880
    json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
881

882
    // Save the visual items
883

884 885 886
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
887

888 889
        visualItem->save(rgJsonMissionItems);
    }
890

891 892 893
    // Mission settings has a special case for end mission action
    if (settingsItem) {
        QList<MissionItem*> rgMissionItems;
894

895 896 897 898 899
        if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
900
        }
901 902
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
903 904 905
        }
    }

906
    json[_jsonItemsKey] = rgJsonMissionItems;
907 908
}

909
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
910
{
Don Gagne's avatar
Don Gagne committed
911
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
912
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
913 914 915 916
    bool            distanceOk =    false;

    // Convert to fixed altitudes

917
    distanceOk = true;
918
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
919 920
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
921
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
922
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
923 924 925
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
926 927 928
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
929
    } else {
Don Gagne's avatar
Don Gagne committed
930
        *altDifference = 0.0;
931
        *azimuth = 0.0;
932
        *distance = 0.0;
933 934 935
    }
}

936
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
937 938 939 940 941 942 943
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

944
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
945 946
}

947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968
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;
    }
}

969 970
void MissionController::_recalcWaypointLines(void)
{
971 972 973
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

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

976
    qCDebug(MissionControllerLog) << "_recalcWaypointLines showHomePosition" << showHomePosition;
977

Nate Weibley's avatar
Nate Weibley committed
978 979
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
980 981
    _waypointLines.clear();

982 983 984 985 986 987 988 989 990
    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;
991 992 993 994
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));


995
        // If we still haven't found the first coordinate item and we hit a takeoff command, link back to home
996 997
        if (firstCoordinateItem &&
                item->isSimpleItem() &&
998 999
                (qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF ||
                 qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) {
1000
            linkStartToHome = true;
1001 1002 1003 1004 1005 1006
        }

        if (item->specifiesCoordinate()) {
            if (!item->isStandaloneCoordinate()) {
                firstCoordinateItem = false;
                VisualItemPair pair(lastCoordinateItem, item);
1007 1008
                if (lastCoordinateItem != _settingsItem || (showHomePosition && linkStartToHome)) {
                    _addWaypointLineSegment(old_table, pair);
1009 1010 1011 1012 1013
                }
                lastCoordinateItem = item;
            }
        }
    }
1014 1015 1016 1017
    if (linkEndToHome && lastCoordinateItem != _settingsItem && showHomePosition) {
        VisualItemPair pair(lastCoordinateItem, _settingsItem);
        _addWaypointLineSegment(old_table, pair);
    }
1018 1019 1020 1021

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
1022 1023
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
1024 1025 1026 1027 1028 1029 1030 1031 1032 1033
            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
1034
    _recalcMissionFlightStatus();
1035 1036 1037 1038

    emit waypointLinesChanged();
}

1039 1040 1041 1042 1043 1044
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);
1045
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068
            _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);
}

1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115
/// 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
1116
void MissionController::_recalcMissionFlightStatus()
1117
{
1118
    if (!_visualItems->count()) {
1119
        return;
1120
    }
1121 1122 1123 1124

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

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1127
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1128

1129 1130 1131
    // 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.
1132

1133
    // No values for first item
1134
    lastCoordinateItem->setAltDifference(0.0);
1135
    lastCoordinateItem->setAzimuth(0.0);
1136
    lastCoordinateItem->setDistance(0.0);
1137

1138 1139
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1140 1141
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1142

1143
    _resetMissionFlightStatus();
1144

DonLakeFlyer's avatar
DonLakeFlyer committed
1145
    bool vtolInHover = true;
1146
    bool linkStartToHome = false;
1147 1148 1149 1150 1151 1152 1153 1154 1155 1156
    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();
        }
    }
1157

DonLakeFlyer's avatar
DonLakeFlyer committed
1158
    for (int i=0; i<_visualItems->count(); i++) {
1159
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1160 1161 1162
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1163 1164
        // Assume the worst
        item->setAzimuth(0.0);
1165
        item->setDistance(0.0);
1166

DonLakeFlyer's avatar
DonLakeFlyer committed
1167 1168 1169
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1170
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1171
                _missionFlightStatus.hoverSpeed = newSpeed;
1172
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1173 1174
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1175
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1176
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1177
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1178 1179
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1180
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1181 1182 1183 1184
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1185
        if (_managerVehicle->vehicleYawsToNextWaypointInMission()) {
1186 1187 1188 1189 1190
            // We current only support gimbal display in this mode
            double gimbalYaw = item->specifiedGimbalYaw();
            if (!qIsNaN(gimbalYaw)) {
                _missionFlightStatus.gimbalYaw = gimbalYaw;
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1191 1192 1193 1194 1195
        }

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

1198 1199 1200
        // 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) {
1201
                linkStartToHome = true;
1202 1203 1204 1205 1206 1207 1208
                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);
                }
1209 1210 1211 1212
            }
        }

        // Update VTOL state
1213
        if (simpleItem && _controllerVehicle->vtol()) {
1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227
            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;
1228 1229
                }
            }
1230 1231 1232
                break;
            default:
                break;
1233
            }
Don Gagne's avatar
Don Gagne committed
1234 1235
        }

1236 1237 1238
        // Check for command specific time delays
        _addCommandTimeDelay(simpleItem, vtolInHover);

1239
        if (item->specifiesCoordinate()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1240 1241
            // Update vehicle yaw assuming direction to next waypoint
            if (item != lastCoordinateItem) {
1242 1243
                _missionFlightStatus.vehicleYaw = lastCoordinateItem->exitCoordinate().azimuthTo(item->coordinate());
                lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
DonLakeFlyer's avatar
DonLakeFlyer committed
1244 1245
            }

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

1248
            double absoluteAltitude = item->coordinate().altitude();
1249
            if (item->coordinateHasRelativeAltitude()) {
1250 1251 1252 1253 1254
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1255 1256 1257 1258
            double terrainAltitude = item->terrainAltitude();
            if (!qIsNaN(terrainAltitude)) {
                minAltSeen = std::min(minAltSeen, terrainAltitude);
                maxAltSeen = std::max(maxAltSeen, terrainAltitude);
1259 1260 1261
            }

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

1267
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1268 1269 1270
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1271

1272
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1273

DonLakeFlyer's avatar
DonLakeFlyer committed
1274 1275 1276
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1277
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1278
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1279

1280
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1281 1282
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1283
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1284

1285 1286
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1287 1288
                    double extraTime = complexItem->additionalTimeDelay();
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, extraTime, distance, item->sequenceNumber());
1289
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1290 1291

                item->setMissionFlightStatus(_missionFlightStatus);
1292
            }
1293 1294

            lastCoordinateItem = item;
1295 1296
        }
    }
1297
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1298

1299 1300 1301 1302 1303 1304 1305 1306
    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();
1307
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1308 1309
    }

1310 1311 1312
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1313

DonLakeFlyer's avatar
DonLakeFlyer committed
1314 1315 1316 1317 1318 1319 1320
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1321 1322
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1323

1324 1325
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1326 1327
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1328 1329 1330

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1331
            if (item->coordinateHasRelativeAltitude()) {
1332 1333 1334 1335
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
1336
                item->setTerrainPercent(qQNaN());
1337 1338
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1339 1340 1341
                if (!qIsNaN(item->terrainAltitude())) {
                    item->setTerrainPercent((item->terrainAltitude() - minAltSeen) / altRange);
                }
1342
            }
1343 1344 1345 1346
        }
    }
}

1347 1348 1349
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1350 1351 1352 1353 1354 1355
    // 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));

1356 1357
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1358 1359 1360
    }
}

1361 1362 1363
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1364
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1365 1366 1367

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

1368 1369
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1370 1371 1372 1373 1374

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1375
        } else if (item->isSimpleItem()) {
1376 1377 1378 1379 1380
            currentParentItem->childItems()->append(item);
        }
    }
}

1381 1382 1383 1384 1385 1386
void MissionController::_setPlannedHomePositionFromFirstCoordinate(void)
{
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1387
    // Set the planned home position to be a delta from first coordinate
1388 1389 1390 1391 1392 1393 1394 1395 1396 1397
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

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


1398 1399
void MissionController::_recalcAll(void)
{
1400 1401 1402
    if (_editMode) {
        _setPlannedHomePositionFromFirstCoordinate();
    }
1403
    _recalcSequence();
1404 1405 1406 1407
    _recalcChildItems();
    _recalcWaypointLines();
}

1408
/// Initializes a new set of mission items
1409
void MissionController::_initAllVisualItems(void)
1410
{
1411 1412
    // Setup home position at index 0

1413 1414 1415
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1416 1417
        return;
    }
1418 1419 1420
    if (_editMode) {
        _settingsItem->setIsCurrentItem(true);
    }
1421

1422
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1423
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1424
    }
1425

1426 1427 1428
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1429

1430 1431 1432 1433
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1434

1435
    _recalcAll();
1436

1437
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1438 1439 1440
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1441
    emit containsItemsChanged(containsItems());
1442
    emit plannedHomePositionChanged(plannedHomePosition());
1443

1444
    setDirty(false);
1445 1446
}

1447
void MissionController::_deinitAllVisualItems(void)
1448
{
1449 1450 1451
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1452 1453
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1454 1455
    }

1456
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1457
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1458 1459
}

1460
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1461
{
1462
    setDirty(false);
1463

1464
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1465 1466
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1467 1468
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1469
    connect(visualItem, &VisualMissionItem::terrainAltitudeChanged,                     this, &MissionController::_recalcMissionFlightStatus);
1470
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1471

1472 1473 1474 1475 1476 1477 1478 1479
    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";
        }
1480 1481
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1482
        if (complexItem) {
1483
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
1484
            connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged,    this, &MissionController::_recalcMissionFlightStatus);
1485
            connect(complexItem, &ComplexMissionItem::additionalTimeDelayChanged,   this, &MissionController::_recalcMissionFlightStatus);
1486 1487 1488
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1489
    }
1490 1491
}

1492
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1493
{
1494 1495
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1496 1497
}

1498
void MissionController::_itemCommandChanged(void)
1499
{
1500 1501
    _recalcChildItems();
    _recalcWaypointLines();
1502 1503
}

1504
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1505
{
1506 1507 1508 1509 1510 1511
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1512

1513 1514
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1515
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1516 1517
        return;
    }
1518

1519 1520
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1521 1522
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1523 1524 1525 1526 1527
    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);
1528
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1529 1530 1531 1532
    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);
1533

1534 1535
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1536
    }
1537

1538
    emit complexMissionItemNamesChanged();
1539
    emit resumeMissionIndexChanged();
1540 1541
}

1542
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1543
{
1544 1545
    if (_visualItems) {
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1546
        if (settingsItem) {
1547
            settingsItem->setHomePositionFromVehicle(homePosition);
1548
        } else {
1549
            qWarning() << "First item is not MissionSettingsItem";
1550
        }
1551 1552 1553
        // Don't let this trip the dirty bit. Otherwise plan will keep getting marked dirty if vehicle home
        // changes.
        _visualItems->setDirty(false);
1554
    }
1555 1556 1557
}

void MissionController::_inProgressChanged(bool inProgress)
1558
{
1559
    emit syncInProgressChanged(inProgress);
1560
}
1561

1562
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
1563
{
1564 1565 1566
    bool        found = false;
    double      foundAltitude;
    MAV_FRAME   foundFrame;
1567

1568 1569 1570 1571 1572 1573
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1576 1577 1578
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1579
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
1580 1581 1582
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1583
                    break;
1584 1585
                }
            }
1586 1587 1588
        }
    }

1589
    if (found) {
1590 1591
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1592 1593 1594
    }

    return found;
1595
}
1596 1597 1598 1599 1600 1601 1602 1603 1604 1605 1606 1607 1608

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

1609
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1610
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1611
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1612
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
1613

Don Gagne's avatar
Don Gagne committed
1614 1615
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1616
    visualItems->insert(0, settingsItem);
1617

1618 1619 1620 1621 1622 1623 1624 1625 1626 1627 1628 1629 1630 1631 1632 1633 1634 1635 1636 1637 1638 1639 1640 1641 1642
    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;
                    }
1643 1644
                }
            }
1645

1646 1647 1648
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1649
        }
Don Gagne's avatar
Don Gagne committed
1650 1651
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1652 1653
    }
}
1654

1655
int MissionController::resumeMissionIndex(void) const
1656
{
1657

1658
    int resumeIndex = 0;
1659

1660
    if (!_editMode) {
1661
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1662
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1663 1664
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1665 1666
        } else {
            resumeIndex = 0;
1667 1668 1669 1670 1671
        }
    }

    return resumeIndex;
}
1672

1673 1674 1675 1676 1677 1678 1679 1680 1681 1682 1683 1684 1685
int MissionController::currentMissionIndex(void) const
{
    if (_editMode) {
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

1686
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1687 1688
{
    if (!_editMode) {
1689
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1690 1691 1692
            sequenceNumber++;
        }

1693 1694
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1695 1696
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1697
        emit currentMissionIndexChanged(currentMissionIndex());
1698 1699
    }
}
1700

1701
bool MissionController::syncInProgress(void) const
1702
{
1703
    return _missionManager->inProgress();
1704 1705 1706 1707 1708 1709 1710 1711 1712 1713 1714 1715
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1716
    }
1717
}
1718

1719 1720
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1721 1722 1723
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, vehicle);

1724 1725 1726 1727 1728 1729
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1730
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
1731 1732 1733
        if (settingsItem) {
            scanIndex++;
            settingsItem->scanForMissionSettings(visualItems, scanIndex);
1734 1735 1736 1737
            continue;
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1738
        if (simpleItem) {
1739 1740 1741 1742 1743
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
1744 1745 1746
        }
    }
}
1747 1748 1749 1750 1751 1752 1753 1754 1755 1756 1757 1758 1759

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
1760 1761 1762 1763 1764 1765 1766 1767
    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();
    }
1768
}
1769 1770 1771 1772 1773 1774

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

    complexItems.append(_surveyMissionItemName);
1775
    if (_controllerVehicle->fixedWing()) {
1776 1777
        complexItems.append(_fwLandingMissionItemName);
    }
1778 1779 1780
    if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
        complexItems.append(_structureScanMissionItemName);
    }
1781 1782 1783

    return complexItems;
}
1784

1785 1786
void MissionController::resumeMission(int resumeIndex)
{
1787
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1788 1789
        resumeIndex--;
    }
1790
    _missionManager->generateResumeMission(resumeIndex);
1791
}
1792 1793 1794 1795 1796 1797 1798 1799 1800

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1801 1802 1803 1804 1805 1806 1807 1808 1809 1810

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

1812 1813 1814 1815 1816 1817 1818
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
1819 1820 1821 1822 1823 1824

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
1825 1826 1827

bool MissionController::showPlanFromManagerVehicle (void)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1828
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle" << _editMode;
DonLakeFlyer's avatar
DonLakeFlyer committed
1829 1830
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
1831
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
1832 1833 1834 1835 1836 1837 1838 1839 1840 1841 1842 1843 1844 1845 1846 1847 1848 1849 1850
    } 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;
        }
    }
}

1851
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1852
{
1853 1854
    // Fly view always reloads on send complete
    if (!error && !_editMode) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1855 1856 1857 1858
        showPlanFromManagerVehicle();
    }
}

1859
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1860
{
1861 1862 1863 1864
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1865
}
1866 1867 1868 1869 1870 1871 1872 1873 1874 1875 1876 1877 1878 1879 1880 1881 1882 1883 1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895

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