MissionController.cc 46.9 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
#include "QGroundControlQmlGlobal.h"
22

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

27 28
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

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

MissionController::MissionController(QObject *parent)
    : QObject(parent)
40
    , _editMode(false)
41 42
    , _visualItems(NULL)
    , _complexItems(NULL)
43
    , _activeVehicle(NULL)
44
    , _autoSync(false)
45
    , _firstItemsFromVehicle(false)
46 47
    , _missionItemsRequested(false)
    , _queuedSend(false)
48 49 50 51
    , _missionDistance(0.0)
    , _missionMaxTelemetry(0.0)
    , _cruiseDistance(0.0)
    , _hoverDistance(0.0)
52
{
53 54 55 56 57

}

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

59 60 61 62
}

void MissionController::start(bool editMode)
{
63 64
    qCDebug(MissionControllerLog) << "start editMode" << editMode;

65 66
    _editMode = editMode;

67
    MultiVehicleManager* multiVehicleMgr = qgcApp()->toolbox()->multiVehicleManager();
68

69
    connect(multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &MissionController::_activeVehicleChanged);
70
    _activeVehicleChanged(multiVehicleMgr->activeVehicle());
71

72
    // We start with an empty mission
73 74 75
    _visualItems = new QmlObjectListModel(this);
    _addPlannedHomePosition(_visualItems, false /* addToCenter */);
    _initAllVisualItems();
76 77
}

78
// Called when new mission items have completed downloading from Vehicle
79
void MissionController::_newMissionItemsAvailableFromVehicle(void)
80
{
81 82
    qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle";

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

90 91
        QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
        const QList<MissionItem*>& newMissionItems = _activeVehicle->missionManager()->missionItems();
92

93 94 95 96 97 98 99 100 101 102 103 104
        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 */);
105 106
        }

107
        _missionItemsRequested = false;
108

109
        _initAllVisualItems();
110
        emit newItemsFromVehicle();
111 112 113
    }
}

114
void MissionController::getMissionItems(void)
115
{
116
    Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
117

118 119 120 121 122 123 124 125
    if (activeVehicle) {
        _missionItemsRequested = true;
        activeVehicle->missionManager()->requestMissionItems();
    }
}

void MissionController::sendMissionItems(void)
{
126 127 128 129 130 131 132
    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()) {
133
                missionItems.append(new MissionItem(qobject_cast<SimpleMissionItem*>(visualItem)->missionItem()));
134
            } else {
135
                ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
136 137 138
                QmlObjectListModel* complexMissionItems = complexItem->getMissionItems();
                for (int j=0; j<complexMissionItems->count(); j++) {
                    missionItems.append(new MissionItem(*qobject_cast<MissionItem*>(complexMissionItems->get(j))));
139
                }
140
                delete complexMissionItems;
141 142 143 144 145
            }
        }

        _activeVehicle->missionManager()->writeMissionItems(missionItems);
        _visualItems->setDirty(false);
146 147 148 149

        for (int i=0; i<missionItems.count(); i++) {
            delete missionItems[i];
        }
150 151
    }
}
152

153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168
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;
        }
    }
}

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

        if (_findLastAcceptanceRadius(&lastValue)) {
186
            newItem->missionItem().setParam2(lastValue);
187
        }
188 189
        if (_findLastAltitude(&lastValue, &lastFrame)) {
            newItem->missionItem().setFrame(lastFrame);
190
            newItem->missionItem().setParam7(lastValue);
191
        }
192
    }
193
    _visualItems->insert(i, newItem);
194 195 196

    _recalcAll();

197
    return newItem->sequenceNumber();
198 199
}

200 201
int MissionController::insertComplexMissionItem(QGeoCoordinate coordinate, int i)
{
202
    int sequenceNumber = _nextSequenceNumber();
203
    ComplexMissionItem* newItem = new ComplexMissionItem(_activeVehicle, this);
204
    newItem->setSequenceNumber(sequenceNumber);
205
    newItem->setCoordinate(coordinate);
206
    _initVisualItem(newItem);
207

208 209
    _visualItems->insert(i, newItem);
    _complexItems->append(newItem);
210 211 212

    _recalcAll();

213
    return newItem->sequenceNumber();
214 215
}

216 217
void MissionController::removeMissionItem(int index)
{
218
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
219

220 221 222 223 224 225 226 227 228
    _deinitVisualItem(item);
    if (!item->isSimpleItem()) {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(_complexItems->removeOne(item));
        if (complexItem) {
            complexItem->deleteLater();
        } else {
            qWarning() << "Complex item missing";
        }
    }
229
    item->deleteLater();
230 231 232 233 234

    _recalcAll();

    // Set the new current item

235
    if (index >= _visualItems->count()) {
236 237
        index--;
    }
238
    for (int i=0; i<_visualItems->count(); i++) {
Don Gagne's avatar
Don Gagne committed
239
        VisualMissionItem* item =  qobject_cast<VisualMissionItem*>(_visualItems->get(i));
240 241
        item->setIsCurrentItem(i == index);
    }
242
    _visualItems->setDirty(true);
243 244
}

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

257
bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString)
258 259 260 261 262 263 264 265 266 267 268
{
    QJsonParseError jsonParseError;
    QJsonDocument   jsonDoc(QJsonDocument::fromJson(bytes, &jsonParseError));

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

    QJsonObject json = jsonDoc.object();

269 270 271 272 273 274 275 276 277 278 279 280 281
    // 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)) {
282 283
        return false;
    }
284 285

    // Version check
286 287 288 289 290
    if (json[_jsonVersionKey].toString() != "1.0") {
        errorString = QStringLiteral("QGroundControl does not support this file version");
        return false;
    }

291 292 293 294 295
    // 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];
296

297 298 299 300 301 302 303 304 305 306 307
        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;
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 334 335 336 337 338
    // 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++];

339 340 341 342 343
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

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

            nextSequenceNumber++;
353
        }
Don Gagne's avatar
Don Gagne committed
354
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < complexItems->count());
355 356

    if (json.contains(_jsonPlannedHomePositionKey)) {
357
        SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
358 359

        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), errorString)) {
360
            visualItems->insert(0, item);
361 362 363 364
        } else {
            return false;
        }
    } else {
365
        _addPlannedHomePosition(visualItems, true /* addToCenter */);
366 367 368 369 370
    }

    return true;
}

371
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391
{
    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()) {
392
            SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
393 394

            if (item->load(stream)) {
395
                visualItems->append(item);
396 397 398 399 400 401 402 403 404 405
            } 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;
    }

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

409 410 411 412 413
        // 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
414 415
            }
        }
416 417 418
    }

    return true;
419 420
}

Don Gagne's avatar
Don Gagne committed
421
void MissionController::loadMissionFromFile(const QString& filename)
422 423 424 425 426 427 428
{
    QString errorString;

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

429 430
    QmlObjectListModel* newVisualItems = new QmlObjectListModel(this);
    QmlObjectListModel* newComplexItems = new QmlObjectListModel(this);
431 432 433 434 435 436

    QFile file(filename);

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

440 441 442
        QString firstLine = stream.readLine();
        if (firstLine.contains(QRegExp("QGC.*WPL"))) {
            stream.seek(0);
443
            _loadTextMissionFile(stream, newVisualItems, errorString);
444
        } else {
445
            _loadJsonMissionFile(bytes, newVisualItems, newComplexItems, errorString);
446 447
        }
    }
448

449
    if (!errorString.isEmpty()) {
450 451 452 453 454 455 456 457 458
        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;

459
        qgcApp()->showMessage(errorString);
460
        return;
461 462
    }

463 464 465
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteListAndContents();
466
    }
467 468 469 470 471 472 473
    if (_complexItems) {
        _complexItems->deleteLater();
    }

    _visualItems = newVisualItems;
    _complexItems = newComplexItems;

474 475
    if (_visualItems->count() == 0) {
        _addPlannedHomePosition(_visualItems, true /* addToCenter */);
476 477
    }

478
    _initAllVisualItems();
479 480
}

Don Gagne's avatar
Don Gagne committed
481
void MissionController::loadMissionFromFilePicker(void)
482
{
483
#ifndef __mobile__
484 485 486 487 488
    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
489
    loadMissionFromFile(filename);
490 491 492
#endif
}

Don Gagne's avatar
Don Gagne committed
493
void MissionController::saveMissionToFile(const QString& filename)
494 495
{
    qDebug() << filename;
496 497 498 499

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

501
    QString missionFilename = filename;
502
    if (!QFileInfo(filename).fileName().contains(".")) {
Don Gagne's avatar
Don Gagne committed
503
        missionFilename += QString(".%1").arg(QGCApplication::missionFileExtension);
504 505
    }

506
    QFile file(missionFilename);
507

508
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
509
        qgcApp()->showMessage(file.errorString());
510
    } else {
511 512 513
        QJsonObject missionFileObject;      // top level json object
        QJsonArray  simpleItemsObject;
        QJsonArray  complexItemsObject;
514

515 516
        missionFileObject[_jsonVersionKey] =        "1.0";
        missionFileObject[_jsonGroundStationKey] =  "QGroundControl";
517

518 519 520 521 522 523 524 525 526 527
        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();
        }
528
        missionFileObject[_jsonMavAutopilotKey] = firmwareType;
529

530
        // Save planned home position
531
        QJsonObject homePositionObject;
532 533 534 535 536 537 538
        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;
        }
539
        missionFileObject[_jsonPlannedHomePositionKey] = homePositionObject;
540

541
        // Save the visual items
542
        for (int i=1; i<_visualItems->count(); i++) {
543 544
            QJsonObject itemObject;

545
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
546 547 548 549 550 551
            visualItem->save(itemObject);

            if (visualItem->isSimpleItem()) {
                simpleItemsObject.append(itemObject);
            } else {
                complexItemsObject.append(itemObject);
552
            }
553
        }
554

555 556 557 558
        missionFileObject[jsonSimpleItemsKey] = simpleItemsObject;
        missionFileObject[_jsonComplexItemsKey] = complexItemsObject;

        QJsonDocument saveDoc(missionFileObject);
559
        file.write(saveDoc.toJson());
560 561
    }

562
    _visualItems->setDirty(false);
563 564
}

Don Gagne's avatar
Don Gagne committed
565
void MissionController::saveMissionToFilePicker(void)
566 567 568 569 570 571 572
{
#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
573
    saveMissionToFile(filename);
574
#endif
575 576
}

577
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
578
{
Don Gagne's avatar
Don Gagne committed
579
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
580
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
581 582 583 584
    bool            distanceOk =    false;

    // Convert to fixed altitudes

585
    qCDebug(MissionControllerLog) << homeAlt
586 587
                                  << currentItem->coordinateHasRelativeAltitude() << currentItem->coordinate().altitude()
                                  << prevItem->exitCoordinateHasRelativeAltitude() << prevItem->exitCoordinate().altitude();
588

589
    distanceOk = true;
590
    if (currentItem->coordinateHasRelativeAltitude()) {
591 592
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
593
    if (prevItem->exitCoordinateHasRelativeAltitude()) {
594
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
595 596 597 598 599
    }

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

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
600 601 602
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
603
    } else {
Don Gagne's avatar
Don Gagne committed
604
        *altDifference = 0.0;
605
        *azimuth = 0.0;
606
        *distance = 0.0;
607 608 609
    }
}

610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626
void MissionController::_calcHomeDist(VisualMissionItem* currentItem, VisualMissionItem* homeItem, double* distance)
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

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

    if (distanceOk) {
        *distance = homeCoord.distanceTo(currentCoord);
    } else {
        *distance = 0.0;
    }
}

627 628
void MissionController::_recalcWaypointLines(void)
{
629 630 631 632 633 634 635
    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";
636 637
    } else {
        connect(homeItem, &VisualMissionItem::coordinateChanged, this, &MissionController::_recalcAltitudeRangeBearing);
638 639 640
    }

    bool    showHomePosition =  homeItem->showHomePosition();
641 642 643

    qCDebug(MissionControllerLog) << "_recalcWaypointLines";

Nate Weibley's avatar
Nate Weibley committed
644 645
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666
    _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
667
                        _linesTable[pair] = old_table.take(pair);
668 669 670 671 672 673 674 675 676 677 678 679
                    } 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
680
                        _linesTable[pair] = linevect;
681 682 683 684 685 686 687 688 689 690 691
                    }
                }
                lastCoordinateItem = item;
            }
        }
    }


    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
692 693
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726
            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";

727 728 729
    // 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.
730

731
    // No values for first item
732
    lastCoordinateItem->setAltDifference(0.0);
733
    lastCoordinateItem->setAzimuth(0.0);
734
    lastCoordinateItem->setDistance(0.0);
735

736 737
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
738
    const double homePositionAltitude = homeItem->coordinate().altitude();
739 740
    minAltSeen = maxAltSeen = homeItem->coordinate().altitude();

741 742 743 744 745 746 747 748 749 750 751
    double missionDistance = 0.0;
    double missionMaxTelemetry = 0.0;

    bool vtolCalc = (QGroundControlQmlGlobal::offlineEditingVehicleType()->enumStringValue() == "VTOL" || (_activeVehicle && _activeVehicle->vtol())) ? true : false ;
    double cruiseDistance = 0.0;
    double hoverDistance = 0.0;
    bool hoverDistanceCalc = false;
    bool hoverTransition = false;
    bool cruiseTransition = false;
    bool hoverDistanceReset = false;

Don Gagne's avatar
Don Gagne committed
752
    bool linkBackToHome = false;
753 754


755 756
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
757 758
        // Assume the worst
        item->setAzimuth(0.0);
759
        item->setDistance(0.0);
760

761
        // If we still haven't found the first coordinate item and we hit a takeoff command link back to home
762 763 764
        if (firstCoordinateItem &&
                item->isSimpleItem() &&
                qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) {
Don Gagne's avatar
Don Gagne committed
765
            linkBackToHome = true;
766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784
            hoverDistanceCalc = true;
        }

        if (item->isSimpleItem() && vtolCalc) {
            SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
            if (simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_DO_VTOL_TRANSITION){  //transition waypoint value
                if (simpleItem->missionItem().param1() == 3){ //hover mode value
                    hoverDistanceCalc = true;
                    hoverTransition = true;
                }
                else if (simpleItem->missionItem().param1() == 4){
                    hoverDistanceCalc = false;
                    cruiseTransition = true;
                }
            }
            if(!hoverTransition && cruiseTransition && !hoverDistanceReset && !linkBackToHome){
                hoverDistance = missionDistance;
                hoverDistanceReset = true;
            }
Don Gagne's avatar
Don Gagne committed
785 786
        }

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

790
            double absoluteAltitude = item->coordinate().altitude();
791
            if (item->coordinateHasRelativeAltitude()) {
792 793 794 795 796
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

797 798 799 800 801 802 803 804 805 806
            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
807
                firstCoordinateItem = false;
808
                if (lastCoordinateItem != homeItem || (showHomePosition && linkBackToHome)) {
809
                    double azimuth, distance, altDifference, telemetryDistance;
810 811 812

                    // Subsequent coordinate items link to last coordinate item. If the last coordinate item
                    // is an invalid home position we skip the line
813
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
814 815 816
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845

                    missionDistance += distance;

                    if (item->isSimpleItem()) {
                        _calcHomeDist(item, homeItem, &telemetryDistance);

                        if (vtolCalc) {
                            SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
                            if (simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF || hoverDistanceCalc){
                                hoverDistance += distance;
                            }
                            cruiseDistance = missionDistance - hoverDistance;
                            if(simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_NAV_LAND && !linkBackToHome && !cruiseTransition && !hoverTransition){
                                hoverDistance = cruiseDistance;
                                cruiseDistance = missionDistance - hoverDistance;
                            }
                        }
                    } else {
                        missionDistance += qobject_cast<ComplexMissionItem*>(item)->surveyDistance();
                        telemetryDistance = qobject_cast<ComplexMissionItem*>(item)->greatestDistanceTo(homeItem->exitCoordinate());

                        if (vtolCalc){
                            cruiseDistance += qobject_cast<ComplexMissionItem*>(item)->surveyDistance(); //assume all survey missions undertaken in cruise
                        }
                    }

                    if (telemetryDistance > missionMaxTelemetry) {
                        missionMaxTelemetry = telemetryDistance;
                    }
846
                }
847 848 849 850 851
                lastCoordinateItem = item;
            }
        }
    }

852 853 854 855 856
    setMissionDistance(missionDistance);
    setMissionMaxTelemetry(missionMaxTelemetry);
    setCruiseDistance(cruiseDistance);
    setHoverDistance(hoverDistance);

857 858
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
859 860
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
861 862 863

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
864
            if (item->coordinateHasRelativeAltitude()) {
865 866 867 868 869 870
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
871
            }
872 873 874 875
        }
    }
}

876 877 878
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
879 880 881 882 883 884 885 886 887
    // 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);
888

889
            if (complexItem) {
890
                 sequenceNumber = complexItem->lastSequenceNumber() + 1;
891 892 893 894
            } else {
                qWarning() << "isSimpleItem == false, yet not ComplexMissionItem";
            }
        }
895 896 897
    }
}

898 899 900
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
901
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
902 903 904

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

905 906
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
907 908 909 910 911

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
912
        } else if (item->isSimpleItem()) {
913 914 915 916 917
            currentParentItem->childItems()->append(item);
        }
    }
}

918 919
void MissionController::_recalcAll(void)
{
920
    _recalcSequence();
921 922 923 924
    _recalcChildItems();
    _recalcWaypointLines();
}

925
/// Initializes a new set of mission items
926
void MissionController::_initAllVisualItems(void)
927
{
928 929 930 931 932 933 934 935 936
    SimpleMissionItem* homeItem = NULL;

    // Setup home position at index 0

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

Don Gagne's avatar
Don Gagne committed
938
    homeItem->setHomePositionSpecialCase(true);
939
    homeItem->setShowHomePosition(_editMode);
940 941
    homeItem->missionItem().setCommand(MAV_CMD_NAV_WAYPOINT);
    homeItem->missionItem().setFrame(MAV_FRAME_GLOBAL);
942 943 944 945 946
    homeItem->setIsCurrentItem(true);

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

949
    QmlObjectListModel* newComplexItems = new QmlObjectListModel(this);
950 951 952
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
953

954 955 956
        // Set up complex item list
        if (!item->isSimpleItem()) {
            ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);
957

958 959 960 961 962
            if (complexItem) {
                newComplexItems->append(item);
            } else {
                qWarning() << "isSimpleItem == false, but not ComplexMissionItem";
            }
963
        }
964 965
    }

966 967 968 969
    if (_complexItems) {
        _complexItems->deleteLater();
    }
    _complexItems = newComplexItems;
970

971
    _recalcAll();
972

973 974
    emit visualItemsChanged();
    emit complexVisualItemsChanged();
975

976
    _visualItems->setDirty(false);
977

978
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_dirtyChanged);
979 980
}

981
void MissionController::_deinitAllVisualItems(void)
982
{
983 984
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
985 986
    }

987
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_dirtyChanged);
988 989
}

990
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
991
{
992 993
    _visualItems->setDirty(false);

994
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
995 996
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
997

998 999 1000 1001 1002 1003 1004 1005
    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";
        }
1006 1007 1008 1009
    } 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);
1010
        connect(complexItem, &ComplexMissionItem::surveyDistanceChanged, this, &MissionController::_recalcAltitudeRangeBearing);
1011
    }
1012 1013
}

1014
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1015
{
1016 1017
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1018 1019
}

1020
void MissionController::_itemCommandChanged(void)
1021
{
1022 1023
    _recalcChildItems();
    _recalcWaypointLines();
1024 1025 1026 1027
}

void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
{
1028 1029
    qCDebug(MissionControllerLog) << "_activeVehicleChanged activeVehicle" << activeVehicle;

1030 1031
    if (_activeVehicle) {
        MissionManager* missionManager = _activeVehicle->missionManager();
1032

1033
        disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailableFromVehicle);
1034
        disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
1035
        disconnect(missionManager, &MissionManager::currentItemChanged,         this, &MissionController::_currentMissionItemChanged);
1036 1037
        disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged,      this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
1038
        _activeVehicle = NULL;
Don Gagne's avatar
Don Gagne committed
1039 1040
    }

Don Gagne's avatar
Don Gagne committed
1041 1042 1043 1044
    // 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();

1045
    _activeVehicle = activeVehicle;
1046

1047 1048
    if (_activeVehicle) {
        MissionManager* missionManager = activeVehicle->missionManager();
1049

1050
        connect(missionManager, &MissionManager::newMissionItemsAvailable,  this, &MissionController::_newMissionItemsAvailableFromVehicle);
1051
        connect(missionManager, &MissionManager::inProgressChanged,         this, &MissionController::_inProgressChanged);
1052
        connect(missionManager, &MissionManager::currentItemChanged,        this, &MissionController::_currentMissionItemChanged);
1053 1054 1055
        connect(_activeVehicle, &Vehicle::homePositionAvailableChanged,     this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);

1056 1057 1058
        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
1059
            getMissionItems();
1060
        }
1061 1062 1063 1064

        _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
        _activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
    }
1065 1066 1067

    // Whenever vehicle changes we need to update syncInProgress
    emit syncInProgressChanged(syncInProgress());
1068 1069 1070 1071
}

void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
1072 1073 1074 1075 1076 1077 1078 1079 1080
    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";
        }
1081
    }
1082 1083 1084 1085
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
1086 1087
    if (!_editMode && _visualItems) {
        qobject_cast<VisualMissionItem*>(_visualItems->get(0))->setCoordinate(homePosition);
1088 1089
        _recalcWaypointLines();
    }
1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106
}

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
}

1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138
void MissionController::setMissionDistance(double missionDistance)
{
    if (!qFuzzyCompare(_missionDistance, missionDistance)) {
        _missionDistance = missionDistance;
        emit missionDistanceChanged(_missionDistance);
    }
}

void MissionController::setMissionMaxTelemetry(double missionMaxTelemetry)
{
    if (!qFuzzyCompare(_missionMaxTelemetry, missionMaxTelemetry)) {
        _missionMaxTelemetry = missionMaxTelemetry;
        emit missionMaxTelemetryChanged(_missionMaxTelemetry);
    }
}

void MissionController::setCruiseDistance(double cruiseDistance)
{
    if (!qFuzzyCompare(_cruiseDistance, cruiseDistance)) {
        _cruiseDistance = cruiseDistance;
        emit cruiseDistanceChanged(_cruiseDistance);
    }
}

void MissionController::setHoverDistance(double hoverDistance)
{
    if (!qFuzzyCompare(_hoverDistance, hoverDistance)) {
        _hoverDistance = hoverDistance;
        emit hoverDistanceChanged(_hoverDistance);
    }
}

1139 1140 1141
void MissionController::_dirtyChanged(bool dirty)
{
    if (dirty && _autoSync) {
1142
        Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156

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

void MissionController::_autoSyncSend(void)
{
    _queuedSend = false;
1157
    if (_visualItems) {
1158
        sendMissionItems();
1159
        _visualItems->setDirty(false);
1160 1161
    }
}
1162

1163
void MissionController::_inProgressChanged(bool inProgress)
1164
{
1165
    emit syncInProgressChanged(inProgress);
1166 1167 1168 1169
    if (!inProgress && _queuedSend) {
        _autoSyncSend();
    }
}
1170

1171
bool MissionController::_findLastAltitude(double* lastAltitude, MAV_FRAME* frame)
1172
{
1173
    bool found = false;
1174
    double foundAltitude;
1175
    MAV_FRAME foundFrame;
1176

1177
    // Don't use home position
1178
    for (int i=1; i<_visualItems->count(); i++) {
1179
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1180

1181 1182 1183 1184
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {

            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1185 1186 1187 1188
                if ((MAV_CMD)simpleItem->command() != MAV_CMD_NAV_TAKEOFF) {
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1189 1190
                }
            }
1191 1192 1193
        }
    }

1194 1195
    if (found) {
        *lastAltitude = foundAltitude;
1196
        *frame = foundFrame;
1197 1198 1199 1200 1201 1202 1203 1204 1205 1206
    }

    return found;
}

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

1207 1208
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1209

1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220
        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";
            }
1221 1222 1223 1224 1225 1226 1227 1228
        }
    }

    if (found) {
        *lastAcceptanceRadius = foundAcceptanceRadius;
    }

    return found;
1229
}
1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243

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
1244
void MissionController::_addPlannedHomePosition(QmlObjectListModel* visualItems, bool addToCenter)
1245
{
1246 1247
    SimpleMissionItem* homeItem = new SimpleMissionItem(_activeVehicle, this);
    visualItems->insert(0, homeItem);
1248

1249 1250
    if (visualItems->count() > 1  && addToCenter) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(visualItems->get(1));
1251 1252 1253 1254 1255 1256

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

1257 1258
        for (int i=2; i<visualItems->count(); i++) {
            item = qobject_cast<VisualMissionItem*>(visualItems->get(i));
1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273

            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());
    }
}
1274 1275 1276 1277 1278 1279 1280 1281

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

1282 1283
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1284 1285 1286 1287
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
    }
}
1288

1289 1290
bool MissionController::syncInProgress(void)
{
1291 1292 1293 1294 1295
    if (_activeVehicle) {
        return _activeVehicle->missionManager()->inProgress();
    } else {
        return false;
    }
1296
}