MissionController.cc 42.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 12 13 14


#include "MissionController.h"
#include "MultiVehicleManager.h"
#include "MissionManager.h"
#include "CoordinateVector.h"
15
#include "FirmwarePlugin.h"
16
#include "QGCApplication.h"
17 18
#include "SimpleMissionItem.h"
#include "ComplexMissionItem.h"
19
#include "JsonHelper.h"
20
#include "ParameterLoader.h"
21

22 23 24 25
#ifndef __mobile__
#include "QGCFileDialog.h"
#endif

26 27
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

28 29
const char* MissionController::jsonSimpleItemsKey = "items";

30 31 32 33
const char* MissionController::_settingsGroup =                 "MissionController";
const char* MissionController::_jsonVersionKey =                "version";
const char* MissionController::_jsonGroundStationKey =          "groundStation";
const char* MissionController::_jsonMavAutopilotKey =           "MAV_AUTOPILOT";
34
const char* MissionController::_jsonComplexItemsKey =           "complexItems";
35
const char* MissionController::_jsonPlannedHomePositionKey =    "plannedHomePosition";
36 37 38

MissionController::MissionController(QObject *parent)
    : QObject(parent)
39
    , _editMode(false)
40 41
    , _visualItems(NULL)
    , _complexItems(NULL)
42
    , _activeVehicle(NULL)
43
    , _autoSync(false)
44
    , _firstItemsFromVehicle(false)
45 46
    , _missionItemsRequested(false)
    , _queuedSend(false)
47
{
48 49 50 51 52

}

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

54 55 56 57
}

void MissionController::start(bool editMode)
{
58 59
    qCDebug(MissionControllerLog) << "start editMode" << editMode;

60 61
    _editMode = editMode;

62
    MultiVehicleManager* multiVehicleMgr = qgcApp()->toolbox()->multiVehicleManager();
63

64
    connect(multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &MissionController::_activeVehicleChanged);
65
    _activeVehicleChanged(multiVehicleMgr->activeVehicle());
66

67
    // We start with an empty mission
68 69 70
    _visualItems = new QmlObjectListModel(this);
    _addPlannedHomePosition(_visualItems, false /* addToCenter */);
    _initAllVisualItems();
71 72
}

73
// Called when new mission items have completed downloading from Vehicle
74
void MissionController::_newMissionItemsAvailableFromVehicle(void)
75
{
76 77
    qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle";

78
    if (!_editMode || _missionItemsRequested || _visualItems->count() == 1) {
79
        // Fly Mode:
Don Gagne's avatar
Don Gagne committed
80
        //      - Always accepts new items from the vehicle so Fly view is kept up to date
81 82
        // Edit Mode:
        //      - Either a load from vehicle was manually requested or
Don Gagne's avatar
Don Gagne committed
83
        //      - The initial automatic load from a vehicle completed and the current editor is empty
84

85 86
        QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
        const QList<MissionItem*>& newMissionItems = _activeVehicle->missionManager()->missionItems();
87

88 89 90 91 92 93 94 95 96 97 98 99
        qCDebug(MissionControllerLog) << "loading from vehicle: count"<< _visualItems->count();
        foreach(const MissionItem* missionItem, newMissionItems) {
            newControllerMissionItems->append(new SimpleMissionItem(_activeVehicle, *missionItem, this));
        }

        _deinitAllVisualItems();

        _visualItems->deleteListAndContents();
        _visualItems = newControllerMissionItems;

        if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
            _addPlannedHomePosition(_visualItems,true /* addToCenter */);
100 101
        }

102
        _missionItemsRequested = false;
103

104
        _initAllVisualItems();
105
        emit newItemsFromVehicle();
106 107 108
    }
}

109
void MissionController::getMissionItems(void)
110
{
111
    Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
112

113 114 115 116 117 118 119 120
    if (activeVehicle) {
        _missionItemsRequested = true;
        activeVehicle->missionManager()->requestMissionItems();
    }
}

void MissionController::sendMissionItems(void)
{
121 122 123 124 125 126 127
    if (_activeVehicle) {
        // Convert to MissionItems so we can send to vehicle
        QList<MissionItem*> missionItems;

        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
            if (visualItem->isSimpleItem()) {
128
                missionItems.append(new MissionItem(qobject_cast<SimpleMissionItem*>(visualItem)->missionItem()));
129
            } else {
130
                ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
131 132 133
                QmlObjectListModel* complexMissionItems = complexItem->getMissionItems();
                for (int j=0; j<complexMissionItems->count(); j++) {
                    missionItems.append(new MissionItem(*qobject_cast<MissionItem*>(complexMissionItems->get(j))));
134
                }
135
                delete complexMissionItems;
136 137 138 139 140
            }
        }

        _activeVehicle->missionManager()->writeMissionItems(missionItems);
        _visualItems->setDirty(false);
141 142 143 144

        for (int i=0; i<missionItems.count(); i++) {
            delete missionItems[i];
        }
145 146
    }
}
147

148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
        VisualMissionItem* lastItem = qobject_cast<VisualMissionItem*>(_visualItems->get(_visualItems->count() - 1));

        if (lastItem->isSimpleItem()) {
            return lastItem->sequenceNumber() + 1;
        } else {
            return qobject_cast<ComplexMissionItem*>(lastItem)->lastSequenceNumber() + 1;
        }
    }
}

164
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
165
{
166
    int sequenceNumber = _nextSequenceNumber();
167
    SimpleMissionItem * newItem = new SimpleMissionItem(_activeVehicle, this);
168
    newItem->setSequenceNumber(sequenceNumber);
169
    newItem->setCoordinate(coordinate);
170 171 172
    newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
    _initVisualItem(newItem);
    if (_visualItems->count() == 1) {
173 174
        newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
    }
175
    newItem->setDefaultsForCommand();
Don Gagne's avatar
Don Gagne committed
176
    if ((MAV_CMD)newItem->command() == MAV_CMD_NAV_WAYPOINT) {
177
        double lastValue;
178
        MAV_FRAME lastFrame;
179 180

        if (_findLastAcceptanceRadius(&lastValue)) {
181
            newItem->missionItem().setParam2(lastValue);
182
        }
183 184
        if (_findLastAltitude(&lastValue, &lastFrame)) {
            newItem->missionItem().setFrame(lastFrame);
185
            newItem->missionItem().setParam7(lastValue);
186
        }
187
    }
188
    _visualItems->insert(i, newItem);
189 190 191

    _recalcAll();

192
    return newItem->sequenceNumber();
193 194
}

195 196
int MissionController::insertComplexMissionItem(QGeoCoordinate coordinate, int i)
{
197
    int sequenceNumber = _nextSequenceNumber();
198
    ComplexMissionItem* newItem = new ComplexMissionItem(_activeVehicle, this);
199
    newItem->setSequenceNumber(sequenceNumber);
200
    newItem->setCoordinate(coordinate);
201
    _initVisualItem(newItem);
202

203 204
    _visualItems->insert(i, newItem);
    _complexItems->append(newItem);
205 206 207

    _recalcAll();

208
    return newItem->sequenceNumber();
209 210
}

211 212
void MissionController::removeMissionItem(int index)
{
213
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
214

215 216 217 218 219 220 221 222 223
    _deinitVisualItem(item);
    if (!item->isSimpleItem()) {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(_complexItems->removeOne(item));
        if (complexItem) {
            complexItem->deleteLater();
        } else {
            qWarning() << "Complex item missing";
        }
    }
224
    item->deleteLater();
225 226 227 228 229

    _recalcAll();

    // Set the new current item

230
    if (index >= _visualItems->count()) {
231 232
        index--;
    }
233
    for (int i=0; i<_visualItems->count(); i++) {
Don Gagne's avatar
Don Gagne committed
234
        VisualMissionItem* item =  qobject_cast<VisualMissionItem*>(_visualItems->get(i));
235 236
        item->setIsCurrentItem(i == index);
    }
237
    _visualItems->setDirty(true);
238 239
}

240 241
void MissionController::removeAllMissionItems(void)
{
242 243 244 245 246 247
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteListAndContents();
        _visualItems = new QmlObjectListModel(this);
        _addPlannedHomePosition(_visualItems, false /* addToCenter */);
        _initAllVisualItems();
Don Gagne's avatar
Don Gagne committed
248
        _visualItems->setDirty(true);
249
    }
250
}
251

252
bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString)
253 254 255 256 257 258 259 260 261 262 263
{
    QJsonParseError jsonParseError;
    QJsonDocument   jsonDoc(QJsonDocument::fromJson(bytes, &jsonParseError));

    if (jsonParseError.error != QJsonParseError::NoError) {
        errorString = jsonParseError.errorString();
        return false;
    }

    QJsonObject json = jsonDoc.object();

264 265 266 267 268 269 270 271 272 273 274 275 276
    // Check for required keys
    QStringList requiredKeys;
    requiredKeys << _jsonVersionKey << _jsonPlannedHomePositionKey;
    if (!JsonHelper::validateRequiredKeys(json, requiredKeys, errorString)) {
        return false;
    }

    // Validate base key types
    QStringList             keyList;
    QList<QJsonValue::Type> typeList;
    keyList << jsonSimpleItemsKey << _jsonVersionKey << _jsonGroundStationKey << _jsonMavAutopilotKey << _jsonComplexItemsKey << _jsonPlannedHomePositionKey;
    typeList << QJsonValue::Array << QJsonValue::String << QJsonValue::String << QJsonValue::Double << QJsonValue::Array << QJsonValue::Object;
    if (!JsonHelper::validateKeyTypes(json, keyList, typeList, errorString)) {
277 278
        return false;
    }
279 280

    // Version check
281 282 283 284 285
    if (json[_jsonVersionKey].toString() != "1.0") {
        errorString = QStringLiteral("QGroundControl does not support this file version");
        return false;
    }

286 287 288 289 290
    // Read complex items
    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];
291

292 293 294 295 296 297 298 299 300 301 302
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

        ComplexMissionItem* item = new ComplexMissionItem(_activeVehicle, this);
        if (item->load(itemValue.toObject(), errorString)) {
            qCDebug(MissionControllerLog) << "Json load: complex item start:stop" << item->sequenceNumber() << item->lastSequenceNumber();
            complexItems->append(item);
        } else {
            return false;
303
        }
304
    }
305

306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333
    // 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
    QJsonArray itemArray(json[jsonSimpleItemsKey].toArray());

    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << complexItems->count();
    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
        if (nextComplexItemIndex < complexItems->count()) {
            ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(complexItems->get(nextComplexItemIndex));

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

334 335 336 337 338
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

339
            SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
340
            if (item->load(itemValue.toObject(), errorString)) {
341 342
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
                visualItems->append(item);
343 344 345
            } else {
                return false;
            }
346 347

            nextSequenceNumber++;
348
        }
Don Gagne's avatar
Don Gagne committed
349
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < complexItems->count());
350 351

    if (json.contains(_jsonPlannedHomePositionKey)) {
352
        SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
353 354

        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), errorString)) {
355
            visualItems->insert(0, item);
356 357 358 359
        } else {
            return false;
        }
    } else {
360
        _addPlannedHomePosition(visualItems, true /* addToCenter */);
361 362 363 364 365
    }

    return true;
}

366
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386
{
    bool addPlannedHomePosition = false;

    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;
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
            addPlannedHomePosition = true;
        }
    }

    if (versionOk) {
        while (!stream.atEnd()) {
387
            SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
388 389

            if (item->load(stream)) {
390
                visualItems->append(item);
391 392 393 394 395 396 397 398 399 400
            } else {
                errorString = QStringLiteral("The mission file is corrupted.");
                return false;
            }
        }
    } else {
        errorString = QStringLiteral("The mission file is not compatible with this version of QGroundControl.");
        return false;
    }

401 402
    if (addPlannedHomePosition || visualItems->count() == 0) {
        _addPlannedHomePosition(visualItems, true /* addToCenter */);
Don Gagne's avatar
Don Gagne committed
403

404 405 406 407 408
        // 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
409 410
            }
        }
411 412 413
    }

    return true;
414 415
}

Don Gagne's avatar
Don Gagne committed
416
void MissionController::loadMissionFromFile(const QString& filename)
417 418 419 420 421 422 423
{
    QString errorString;

    if (filename.isEmpty()) {
        return;
    }

424 425
    QmlObjectListModel* newVisualItems = new QmlObjectListModel(this);
    QmlObjectListModel* newComplexItems = new QmlObjectListModel(this);
426 427 428 429 430 431

    QFile file(filename);

    if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
        errorString = file.errorString();
    } else {
432 433
        QByteArray  bytes = file.readAll();
        QTextStream stream(&bytes);
434

435 436 437
        QString firstLine = stream.readLine();
        if (firstLine.contains(QRegExp("QGC.*WPL"))) {
            stream.seek(0);
438
            _loadTextMissionFile(stream, newVisualItems, errorString);
439
        } else {
440
            _loadJsonMissionFile(bytes, newVisualItems, newComplexItems, errorString);
441 442
        }
    }
443

444
    if (!errorString.isEmpty()) {
445 446 447 448 449 450 451 452 453
        for (int i=0; i<newVisualItems->count(); i++) {
            newVisualItems->get(i)->deleteLater();
        }
        for (int i=0; i<newComplexItems->count(); i++) {
            newComplexItems->get(i)->deleteLater();
        }
        delete newVisualItems;
        delete newComplexItems;

454
        qgcApp()->showMessage(errorString);
455
        return;
456 457
    }

458 459 460
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteListAndContents();
461
    }
462 463 464 465 466 467 468
    if (_complexItems) {
        _complexItems->deleteLater();
    }

    _visualItems = newVisualItems;
    _complexItems = newComplexItems;

469 470
    if (_visualItems->count() == 0) {
        _addPlannedHomePosition(_visualItems, true /* addToCenter */);
471 472
    }

473
    _initAllVisualItems();
474 475
}

Don Gagne's avatar
Don Gagne committed
476
void MissionController::loadMissionFromFilePicker(void)
477
{
478
#ifndef __mobile__
479 480 481 482 483
    QString filename = QGCFileDialog::getOpenFileName(NULL, "Select Mission File to load", QString(), "Mission file (*.mission);;All Files (*.*)");

    if (filename.isEmpty()) {
        return;
    }
Don Gagne's avatar
Don Gagne committed
484
    loadMissionFromFile(filename);
485 486 487
#endif
}

Don Gagne's avatar
Don Gagne committed
488
void MissionController::saveMissionToFile(const QString& filename)
489 490
{
    qDebug() << filename;
491 492 493 494

    if (filename.isEmpty()) {
        return;
    }
495

496
    QString missionFilename = filename;
497
    if (!QFileInfo(filename).fileName().contains(".")) {
Don Gagne's avatar
Don Gagne committed
498
        missionFilename += QString(".%1").arg(QGCApplication::missionFileExtension);
499 500
    }

501
    QFile file(missionFilename);
502

503
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
504
        qgcApp()->showMessage(file.errorString());
505
    } else {
506 507 508
        QJsonObject missionFileObject;      // top level json object
        QJsonArray  simpleItemsObject;
        QJsonArray  complexItemsObject;
509

510 511
        missionFileObject[_jsonVersionKey] =        "1.0";
        missionFileObject[_jsonGroundStationKey] =  "QGroundControl";
512

513 514 515 516 517 518 519 520 521 522
        MAV_AUTOPILOT firmwareType = MAV_AUTOPILOT_GENERIC;
        if (_activeVehicle) {
            firmwareType = _activeVehicle->firmwareType();
        } else {
            // FIXME: Hack duplicated code from QGroundControlQmlGlobal. Had to do this for now since
            // QGroundControlQmlGlobal is not available from C++ side.

            QSettings settings;
            firmwareType = (MAV_AUTOPILOT)settings.value("OfflineEditingFirmwareType", MAV_AUTOPILOT_ARDUPILOTMEGA).toInt();
        }
523
        missionFileObject[_jsonMavAutopilotKey] = firmwareType;
524

525
        // Save planned home position
526
        QJsonObject homePositionObject;
527 528 529 530 531 532 533
        SimpleMissionItem* homeItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(0));
        if (homeItem) {
            homeItem->missionItem().save(homePositionObject);
        } else {
            qgcApp()->showMessage(QStringLiteral("Internal error: VisualMissionItem at index 0 not SimpleMissionItem"));
            return;
        }
534
        missionFileObject[_jsonPlannedHomePositionKey] = homePositionObject;
535

536
        // Save the visual items
537
        for (int i=1; i<_visualItems->count(); i++) {
538 539
            QJsonObject itemObject;

540
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
541 542 543 544 545 546
            visualItem->save(itemObject);

            if (visualItem->isSimpleItem()) {
                simpleItemsObject.append(itemObject);
            } else {
                complexItemsObject.append(itemObject);
547
            }
548
        }
549

550 551 552 553
        missionFileObject[jsonSimpleItemsKey] = simpleItemsObject;
        missionFileObject[_jsonComplexItemsKey] = complexItemsObject;

        QJsonDocument saveDoc(missionFileObject);
554
        file.write(saveDoc.toJson());
555 556
    }

557
    _visualItems->setDirty(false);
558 559
}

Don Gagne's avatar
Don Gagne committed
560
void MissionController::saveMissionToFilePicker(void)
561 562 563 564 565 566 567
{
#ifndef __mobile__
    QString filename = QGCFileDialog::getSaveFileName(NULL, "Select file to save mission to", QString(), "Mission file (*.mission);;All Files (*.*)");

    if (filename.isEmpty()) {
        return;
    }
Don Gagne's avatar
Don Gagne committed
568
    saveMissionToFile(filename);
569
#endif
570 571
}

572
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
573
{
Don Gagne's avatar
Don Gagne committed
574
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
575
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
576 577 578 579
    bool            distanceOk =    false;

    // Convert to fixed altitudes

580
    qCDebug(MissionControllerLog) << homeAlt
581 582
                                  << currentItem->coordinateHasRelativeAltitude() << currentItem->coordinate().altitude()
                                  << prevItem->exitCoordinateHasRelativeAltitude() << prevItem->exitCoordinate().altitude();
583

584
    distanceOk = true;
585
    if (currentItem->coordinateHasRelativeAltitude()) {
586 587
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
588
    if (prevItem->exitCoordinateHasRelativeAltitude()) {
589
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
590 591 592 593 594
    }

    qCDebug(MissionControllerLog) << "distanceOk" << distanceOk;

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
595 596 597
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
598
    } else {
Don Gagne's avatar
Don Gagne committed
599
        *altDifference = 0.0;
600
        *azimuth = 0.0;
601
        *distance = 0.0;
602 603 604
    }
}

605 606
void MissionController::_recalcWaypointLines(void)
{
607 608 609 610 611 612 613
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

    SimpleMissionItem*  homeItem = qobject_cast<SimpleMissionItem*>(lastCoordinateItem);

    if (!homeItem) {
        qWarning() << "Home item is not SimpleMissionItem";
614 615
    } else {
        connect(homeItem, &VisualMissionItem::coordinateChanged, this, &MissionController::_recalcAltitudeRangeBearing);
616 617 618
    }

    bool    showHomePosition =  homeItem->showHomePosition();
619 620 621

    qCDebug(MissionControllerLog) << "_recalcWaypointLines";

Nate Weibley's avatar
Nate Weibley committed
622 623
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644
    _waypointLines.clear();

    bool linkBackToHome = false;
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));


        // If we still haven't found the first coordinate item and we hit a a takeoff command link back to home
        if (firstCoordinateItem &&
                item->isSimpleItem() &&
                qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) {
            linkBackToHome = true;
        }

        if (item->specifiesCoordinate()) {
            if (!item->isStandaloneCoordinate()) {
                firstCoordinateItem = false;
                VisualItemPair pair(lastCoordinateItem, item);
                if (lastCoordinateItem != homeItem || (showHomePosition && linkBackToHome)) {
                    if (old_table.contains(pair)) {
                        // Do nothing, this segment already exists and is wired up
Nate Weibley's avatar
Nate Weibley committed
645
                        _linesTable[pair] = old_table.take(pair);
646 647 648 649 650 651 652 653 654 655 656 657
                    } else {
                        // Create a new segment and wire update notifiers
                        auto linevect       = new CoordinateVector(lastCoordinateItem->isSimpleItem() ? lastCoordinateItem->coordinate() : lastCoordinateItem->exitCoordinate(), item->coordinate(), this);
                        auto originNotifier = lastCoordinateItem->isSimpleItem() ? &VisualMissionItem::coordinateChanged : &VisualMissionItem::exitCoordinateChanged,
                             endNotifier    = &VisualMissionItem::coordinateChanged;
                        // Use signals/slots to update the coordinate endpoints
                        connect(lastCoordinateItem, originNotifier, linevect, &CoordinateVector::setCoordinate1);
                        connect(item,               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(item, &VisualMissionItem::coordinateChanged, this, &MissionController::_recalcAltitudeRangeBearing);
Nate Weibley's avatar
Nate Weibley committed
658
                        _linesTable[pair] = linevect;
659 660 661 662 663 664 665 666 667 668 669
                    }
                }
                lastCoordinateItem = item;
            }
        }
    }


    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
670 671
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705
            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);

    _recalcAltitudeRangeBearing();

    emit waypointLinesChanged();
}

void MissionController::_recalcAltitudeRangeBearing()
{
    if (!_visualItems->count())
        return;

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

    SimpleMissionItem*  homeItem = qobject_cast<SimpleMissionItem*>(lastCoordinateItem);

    if (!homeItem) {
        qWarning() << "Home item is not SimpleMissionItem";
    }

    bool    showHomePosition =  homeItem->showHomePosition();

    qCDebug(MissionControllerLog) << "_recalcAltitudeRangeBearing";

706 707 708
    // 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.
709

710
    // No values for first item
711
    lastCoordinateItem->setAltDifference(0.0);
712
    lastCoordinateItem->setAzimuth(0.0);
713
    lastCoordinateItem->setDistance(0.0);
714

715 716
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
717
    const double homePositionAltitude = homeItem->coordinate().altitude();
718 719
    minAltSeen = maxAltSeen = homeItem->coordinate().altitude();

Don Gagne's avatar
Don Gagne committed
720
    bool linkBackToHome = false;
721 722
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
723

724 725
        // Assume the worst
        item->setAzimuth(0.0);
726
        item->setDistance(0.0);
727

728 729 730 731
        // If we still haven't found the first coordinate item and we hit a a takeoff command link back to home
        if (firstCoordinateItem &&
                item->isSimpleItem() &&
                qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) {
Don Gagne's avatar
Don Gagne committed
732 733 734
            linkBackToHome = true;
        }

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

738
            double absoluteAltitude = item->coordinate().altitude();
739
            if (item->coordinateHasRelativeAltitude()) {
740 741 742 743 744
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

745 746 747 748 749 750 751 752 753 754
            if (!item->exitCoordinateSameAsEntry()) {
                absoluteAltitude = item->exitCoordinate().altitude();
                if (item->exitCoordinateHasRelativeAltitude()) {
                    absoluteAltitude += homePositionAltitude;
                }
                minAltSeen = std::min(minAltSeen, absoluteAltitude);
                maxAltSeen = std::max(maxAltSeen, absoluteAltitude);
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
755
                firstCoordinateItem = false;
756
                if (lastCoordinateItem != homeItem || (showHomePosition && linkBackToHome)) {
757 758 759 760
                    double azimuth, distance, altDifference;

                    // Subsequent coordinate items link to last coordinate item. If the last coordinate item
                    // is an invalid home position we skip the line
761
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
762 763 764
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
765
                }
766 767 768 769 770 771 772
                lastCoordinateItem = item;
            }
        }
    }

    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
773 774
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
775 776 777

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
778
            if (item->coordinateHasRelativeAltitude()) {
779 780 781 782 783 784
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
785
            }
786 787 788 789
        }
    }
}

790 791 792
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
793 794 795 796 797 798 799 800 801
    // 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));

        item->setSequenceNumber(sequenceNumber++);
        if (!item->isSimpleItem()) {
            ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);
802

803
            if (complexItem) {
804
                 sequenceNumber = complexItem->lastSequenceNumber() + 1;
805 806 807 808
            } else {
                qWarning() << "isSimpleItem == false, yet not ComplexMissionItem";
            }
        }
809 810 811
    }
}

812 813 814
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
815
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
816 817 818

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

819 820
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
821 822 823 824 825

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
826
        } else if (item->isSimpleItem()) {
827 828 829 830 831
            currentParentItem->childItems()->append(item);
        }
    }
}

832 833
void MissionController::_recalcAll(void)
{
834
    _recalcSequence();
835 836 837 838
    _recalcChildItems();
    _recalcWaypointLines();
}

839
/// Initializes a new set of mission items
840
void MissionController::_initAllVisualItems(void)
841
{
842 843 844 845 846 847 848 849 850
    SimpleMissionItem* homeItem = NULL;

    // Setup home position at index 0

    homeItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(0));
    if (!homeItem) {
        qWarning() << "homeItem not SimpleMissionItem";
        return;
    }
851

Don Gagne's avatar
Don Gagne committed
852
    homeItem->setHomePositionSpecialCase(true);
853
    homeItem->setShowHomePosition(_editMode);
854 855
    homeItem->missionItem().setCommand(MAV_CMD_NAV_WAYPOINT);
    homeItem->missionItem().setFrame(MAV_FRAME_GLOBAL);
856 857 858 859 860
    homeItem->setIsCurrentItem(true);

    if (!_editMode && _activeVehicle && _activeVehicle->homePositionAvailable()) {
        homeItem->setCoordinate(_activeVehicle->homePosition());
        homeItem->setShowHomePosition(true);
861
    }
862

863
    QmlObjectListModel* newComplexItems = new QmlObjectListModel(this);
864 865 866
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
867

868 869 870
        // Set up complex item list
        if (!item->isSimpleItem()) {
            ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);
871

872 873 874 875 876
            if (complexItem) {
                newComplexItems->append(item);
            } else {
                qWarning() << "isSimpleItem == false, but not ComplexMissionItem";
            }
877
        }
878 879
    }

880 881 882 883
    if (_complexItems) {
        _complexItems->deleteLater();
    }
    _complexItems = newComplexItems;
884

885
    _recalcAll();
886

887 888
    emit visualItemsChanged();
    emit complexVisualItemsChanged();
889

890
    _visualItems->setDirty(false);
891

892
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_dirtyChanged);
893 894
}

895
void MissionController::_deinitAllVisualItems(void)
896
{
897 898
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
899 900
    }

901
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_dirtyChanged);
902 903
}

904
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
905
{
906 907
    _visualItems->setDirty(false);

908
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
909 910
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
911

912 913 914 915 916 917 918 919
    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";
        }
920 921 922 923
    } else {
        // We need to track changes of lastSequenceNumber so we can recalc sequence numbers for subsequence items
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
        connect(complexItem, &ComplexMissionItem::lastSequenceNumberChanged, this, &MissionController::_recalcSequence);
924
    }
925 926
}

927
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
928
{
929 930
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
931 932
}

933
void MissionController::_itemCommandChanged(void)
934
{
935 936
    _recalcChildItems();
    _recalcWaypointLines();
937 938 939 940
}

void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
{
941 942
    qCDebug(MissionControllerLog) << "_activeVehicleChanged activeVehicle" << activeVehicle;

943 944
    if (_activeVehicle) {
        MissionManager* missionManager = _activeVehicle->missionManager();
945

946
        disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailableFromVehicle);
947
        disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
948
        disconnect(missionManager, &MissionManager::currentItemChanged,         this, &MissionController::_currentMissionItemChanged);
949 950
        disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged,      this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
951
        _activeVehicle = NULL;
Don Gagne's avatar
Don Gagne committed
952 953
    }

Don Gagne's avatar
Don Gagne committed
954 955 956 957
    // We always remove all items on vehicle change. This leaves a user model hole:
    //      If the user has unsaved changes in the Plan view they will lose them
    removeAllMissionItems();

958
    _activeVehicle = activeVehicle;
959

960 961
    if (_activeVehicle) {
        MissionManager* missionManager = activeVehicle->missionManager();
962

963
        connect(missionManager, &MissionManager::newMissionItemsAvailable,  this, &MissionController::_newMissionItemsAvailableFromVehicle);
964
        connect(missionManager, &MissionManager::inProgressChanged,         this, &MissionController::_inProgressChanged);
965
        connect(missionManager, &MissionManager::currentItemChanged,        this, &MissionController::_currentMissionItemChanged);
966 967 968
        connect(_activeVehicle, &Vehicle::homePositionAvailableChanged,     this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);

969 970 971
        if (_activeVehicle->getParameterLoader()->parametersAreReady() && !syncInProgress()) {
            // We are switching between two previously existing vehicles. We have to manually ask for the items from the Vehicle.
            // We don't request mission items for new vehicles since that will happen autamatically.
Don Gagne's avatar
Don Gagne committed
972
            getMissionItems();
973
        }
974 975 976 977

        _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
        _activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
    }
978 979 980

    // Whenever vehicle changes we need to update syncInProgress
    emit syncInProgressChanged(syncInProgress());
981 982 983 984
}

void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
985 986 987 988 989 990 991 992 993
    if (!_editMode && _visualItems) {
        SimpleMissionItem* homeItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(0));

        if (homeItem) {
            homeItem->setShowHomePosition(homePositionAvailable);
            _recalcWaypointLines();
        } else {
            qWarning() << "Unabled to cast home item to SimpleMissionItem";
        }
994
    }
995 996 997 998
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
999 1000
    if (!_editMode && _visualItems) {
        qobject_cast<VisualMissionItem*>(_visualItems->get(0))->setCoordinate(homePosition);
1001 1002
        _recalcWaypointLines();
    }
1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022
}

void MissionController::setAutoSync(bool autoSync)
{
    // FIXME: AutoSync temporarily turned off
#if 0
    _autoSync = autoSync;
    emit autoSyncChanged(_autoSync);

    if (_autoSync) {
        _dirtyChanged(true);
    }
#else
    Q_UNUSED(autoSync)
#endif
}

void MissionController::_dirtyChanged(bool dirty)
{
    if (dirty && _autoSync) {
1023
        Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037

        if (activeVehicle && !activeVehicle->armed()) {
            if (_activeVehicle->missionManager()->inProgress()) {
                _queuedSend = true;
            } else {
                _autoSyncSend();
            }
        }
    }
}

void MissionController::_autoSyncSend(void)
{
    _queuedSend = false;
1038
    if (_visualItems) {
1039
        sendMissionItems();
1040
        _visualItems->setDirty(false);
1041 1042
    }
}
1043

1044
void MissionController::_inProgressChanged(bool inProgress)
1045
{
1046
    emit syncInProgressChanged(inProgress);
1047 1048 1049 1050
    if (!inProgress && _queuedSend) {
        _autoSyncSend();
    }
}
1051

1052
bool MissionController::_findLastAltitude(double* lastAltitude, MAV_FRAME* frame)
1053
{
1054
    bool found = false;    
1055
    double foundAltitude;
1056
    MAV_FRAME foundFrame;
1057

1058
    // Don't use home position
1059
    for (int i=1; i<_visualItems->count(); i++) {
1060
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1061

1062 1063 1064 1065
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {

            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1066 1067 1068 1069
                if ((MAV_CMD)simpleItem->command() != MAV_CMD_NAV_TAKEOFF) {
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1070 1071
                }
            }
1072 1073 1074
        }
    }

1075 1076
    if (found) {
        *lastAltitude = foundAltitude;
1077
        *frame = foundFrame;
1078 1079 1080 1081 1082 1083 1084 1085 1086 1087
    }

    return found;
}

bool MissionController::_findLastAcceptanceRadius(double* lastAcceptanceRadius)
{
    bool found = false;
    double foundAcceptanceRadius;

1088 1089
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1090

1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101
        if (visualItem->isSimpleItem()) {
            SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);

            if (simpleItem) {
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
                    foundAcceptanceRadius = simpleItem->missionItem().param2();
                    found = true;
                }
            } else {
                qWarning() << "isSimpleItem == true, yet not SimpleMissionItem";
            }
1102 1103 1104 1105 1106 1107 1108 1109
        }
    }

    if (found) {
        *lastAcceptanceRadius = foundAcceptanceRadius;
    }

    return found;
1110
}
1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124

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

/// Add the home position item to the front of the list
1125
void MissionController::_addPlannedHomePosition(QmlObjectListModel* visualItems, bool addToCenter)
1126
{
1127 1128
    SimpleMissionItem* homeItem = new SimpleMissionItem(_activeVehicle, this);
    visualItems->insert(0, homeItem);
1129

1130 1131
    if (visualItems->count() > 1  && addToCenter) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(visualItems->get(1));
1132 1133 1134 1135 1136 1137

        double north = _normalizeLat(item->coordinate().latitude());
        double south = north;
        double east = _normalizeLon(item->coordinate().longitude());
        double west = east;

1138 1139
        for (int i=2; i<visualItems->count(); i++) {
            item = qobject_cast<VisualMissionItem*>(visualItems->get(i));
1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154

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

        homeItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
    } else {
        homeItem->setCoordinate(qgcApp()->lastKnownHomePosition());
    }
}
1155 1156 1157 1158 1159 1160 1161 1162

void MissionController::_currentMissionItemChanged(int sequenceNumber)
{
    if (!_editMode) {
        if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            sequenceNumber++;
        }

1163 1164
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1165 1166 1167 1168
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
    }
}
1169

1170 1171
bool MissionController::syncInProgress(void)
{
1172 1173 1174 1175 1176
    if (_activeVehicle) {
        return _activeVehicle->missionManager()->inProgress();
    } else {
        return false;
    }
1177
}