MissionController.cc 47.7 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
#include "SimpleMissionItem.h"
18
#include "SurveyMissionItem.h"
19
#include "JsonHelper.h"
20
#include "ParameterManager.h"
21
#include "QGroundControlQmlGlobal.h"
22

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

28 29
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

32 33
const char* MissionController::_settingsGroup =                 "MissionController";
const char* MissionController::_jsonMavAutopilotKey =           "MAV_AUTOPILOT";
34
const char* MissionController::_jsonComplexItemsKey =           "complexItems";
35
const char* MissionController::_jsonPlannedHomePositionKey =    "plannedHomePosition";
36 37

MissionController::MissionController(QObject *parent)
38
    : PlanElementController(parent)
39 40
    , _visualItems(NULL)
    , _complexItems(NULL)
41
    , _firstItemsFromVehicle(false)
42 43
    , _missionItemsRequested(false)
    , _queuedSend(false)
44 45 46 47
    , _missionDistance(0.0)
    , _missionMaxTelemetry(0.0)
    , _cruiseDistance(0.0)
    , _hoverDistance(0.0)
48
{
49 50 51 52 53

}

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

55 56 57 58
}

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

61
    PlanElementController::start(editMode);
62

63
    // We start with an empty mission
64 65 66
    _visualItems = new QmlObjectListModel(this);
    _addPlannedHomePosition(_visualItems, false /* addToCenter */);
    _initAllVisualItems();
67 68
}

69
// Called when new mission items have completed downloading from Vehicle
70
void MissionController::_newMissionItemsAvailableFromVehicle(void)
71
{
72 73
    qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle";

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

81 82
        QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
        const QList<MissionItem*>& newMissionItems = _activeVehicle->missionManager()->missionItems();
83

84 85 86 87 88 89 90 91 92 93 94 95
        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 */);
96 97
        }

98
        _missionItemsRequested = false;
99

100
        _initAllVisualItems();
101
        emit newItemsFromVehicle();
102 103 104
    }
}

105
void MissionController::loadFromVehicle(void)
106
{
107
    Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
108

109 110 111 112 113 114
    if (activeVehicle) {
        _missionItemsRequested = true;
        activeVehicle->missionManager()->requestMissionItems();
    }
}

115
void MissionController::sendToVehicle(void)
116
{
117 118 119 120 121 122 123
    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()) {
124
                missionItems.append(new MissionItem(qobject_cast<SimpleMissionItem*>(visualItem)->missionItem()));
125
            } else {
126
                ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
127 128 129
                QmlObjectListModel* complexMissionItems = complexItem->getMissionItems();
                for (int j=0; j<complexMissionItems->count(); j++) {
                    missionItems.append(new MissionItem(*qobject_cast<MissionItem*>(complexMissionItems->get(j))));
130
                }
131
                delete complexMissionItems;
132 133 134 135 136
            }
        }

        _activeVehicle->missionManager()->writeMissionItems(missionItems);
        _visualItems->setDirty(false);
137 138 139 140

        for (int i=0; i<missionItems.count(); i++) {
            delete missionItems[i];
        }
141 142
    }
}
143

144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159
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;
        }
    }
}

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

        if (_findLastAcceptanceRadius(&lastValue)) {
177
            newItem->missionItem().setParam2(lastValue);
178
        }
179 180
        if (_findLastAltitude(&lastValue, &lastFrame)) {
            newItem->missionItem().setFrame(lastFrame);
181
            newItem->missionItem().setParam7(lastValue);
182
        }
183
    }
184
    _visualItems->insert(i, newItem);
185 186 187

    _recalcAll();

188
    return newItem->sequenceNumber();
189 190
}

191 192
int MissionController::insertComplexMissionItem(QGeoCoordinate coordinate, int i)
{
193
    int sequenceNumber = _nextSequenceNumber();
194
    SurveyMissionItem* newItem = new SurveyMissionItem(_activeVehicle, this);
195
    newItem->setSequenceNumber(sequenceNumber);
196
    newItem->setCoordinate(coordinate);
197
    _initVisualItem(newItem);
198

199 200
    _visualItems->insert(i, newItem);
    _complexItems->append(newItem);
201 202 203

    _recalcAll();

204
    return newItem->sequenceNumber();
205 206
}

207 208
void MissionController::removeMissionItem(int index)
{
209
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
210

211 212 213
    _deinitVisualItem(item);
    if (!item->isSimpleItem()) {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(_complexItems->removeOne(item));
214
        if (!complexItem) {
215 216 217
            qWarning() << "Complex item missing";
        }
    }
218
    item->deleteLater();
219 220 221 222 223

    _recalcAll();

    // Set the new current item

224
    if (index >= _visualItems->count()) {
225 226
        index--;
    }
227
    for (int i=0; i<_visualItems->count(); i++) {
Don Gagne's avatar
Don Gagne committed
228
        VisualMissionItem* item =  qobject_cast<VisualMissionItem*>(_visualItems->get(i));
229 230
        item->setIsCurrentItem(i == index);
    }
231
    _visualItems->setDirty(true);
232 233
}

234
void MissionController::removeAll(void)
235
{
236 237 238 239 240 241
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteListAndContents();
        _visualItems = new QmlObjectListModel(this);
        _addPlannedHomePosition(_visualItems, false /* addToCenter */);
        _initAllVisualItems();
Don Gagne's avatar
Don Gagne committed
242
        _visualItems->setDirty(true);
243
    }
244
}
245

246
bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString)
247 248 249 250 251 252 253 254 255 256 257
{
    QJsonParseError jsonParseError;
    QJsonDocument   jsonDoc(QJsonDocument::fromJson(bytes, &jsonParseError));

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

    QJsonObject json = jsonDoc.object();

258 259
    // Check for required keys
    QStringList requiredKeys;
260
    requiredKeys << JsonHelper::jsonVersionKey << _jsonPlannedHomePositionKey;
261 262 263 264 265 266 267
    if (!JsonHelper::validateRequiredKeys(json, requiredKeys, errorString)) {
        return false;
    }

    // Validate base key types
    QStringList             keyList;
    QList<QJsonValue::Type> typeList;
268
    keyList << jsonSimpleItemsKey << JsonHelper::jsonVersionKey << JsonHelper::jsonGroundStationKey << _jsonMavAutopilotKey << _jsonComplexItemsKey << _jsonPlannedHomePositionKey;
269 270
    typeList << QJsonValue::Array << QJsonValue::String << QJsonValue::String << QJsonValue::Double << QJsonValue::Array << QJsonValue::Object;
    if (!JsonHelper::validateKeyTypes(json, keyList, typeList, errorString)) {
271 272
        return false;
    }
273 274

    // Version check
275
    if (json[JsonHelper::jsonVersionKey].toString() != "1.0") {
276 277 278 279
        errorString = QStringLiteral("QGroundControl does not support this file version");
        return false;
    }

280 281 282 283 284
    // 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];
285

286 287 288 289 290
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

291
        SurveyMissionItem* item = new SurveyMissionItem(_activeVehicle, this);
292 293 294 295 296
        if (item->load(itemValue.toObject(), errorString)) {
            qCDebug(MissionControllerLog) << "Json load: complex item start:stop" << item->sequenceNumber() << item->lastSequenceNumber();
            complexItems->append(item);
        } else {
            return false;
297
        }
298
    }
299

300 301 302 303 304 305 306 307 308 309 310 311 312
    // 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()) {
313
            SurveyMissionItem* complexItem = qobject_cast<SurveyMissionItem*>(complexItems->get(nextComplexItemIndex));
314 315 316 317 318 319 320 321 322 323 324 325 326 327

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

328 329 330 331 332
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

333
            SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
334
            if (item->load(itemValue.toObject(), errorString)) {
335 336
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
                visualItems->append(item);
337 338 339
            } else {
                return false;
            }
340 341

            nextSequenceNumber++;
342
        }
Don Gagne's avatar
Don Gagne committed
343
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < complexItems->count());
344 345

    if (json.contains(_jsonPlannedHomePositionKey)) {
346
        SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
347 348

        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), errorString)) {
349
            visualItems->insert(0, item);
350 351 352 353
        } else {
            return false;
        }
    } else {
354
        _addPlannedHomePosition(visualItems, true /* addToCenter */);
355 356 357 358 359
    }

    return true;
}

360
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380
{
    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()) {
381
            SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
382 383

            if (item->load(stream)) {
384
                visualItems->append(item);
385 386 387 388 389 390 391 392 393 394
            } 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;
    }

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

398 399 400 401 402
        // 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
403 404
            }
        }
405 406 407
    }

    return true;
408 409
}

410
void MissionController::loadFromFile(const QString& filename)
411 412 413 414 415 416 417
{
    QString errorString;

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

418 419
    QmlObjectListModel* newVisualItems = new QmlObjectListModel(this);
    QmlObjectListModel* newComplexItems = new QmlObjectListModel(this);
420 421 422 423 424 425

    QFile file(filename);

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

429 430 431
        QString firstLine = stream.readLine();
        if (firstLine.contains(QRegExp("QGC.*WPL"))) {
            stream.seek(0);
432
            _loadTextMissionFile(stream, newVisualItems, errorString);
433
        } else {
434
            _loadJsonMissionFile(bytes, newVisualItems, newComplexItems, errorString);
435 436
        }
    }
437

438
    if (!errorString.isEmpty()) {
439 440 441 442 443 444 445 446 447
        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;

448
        qgcApp()->showMessage(errorString);
449
        return;
450 451
    }

452 453 454
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteListAndContents();
455
    }
456 457 458 459 460 461 462
    if (_complexItems) {
        _complexItems->deleteLater();
    }

    _visualItems = newVisualItems;
    _complexItems = newComplexItems;

463 464
    if (_visualItems->count() == 0) {
        _addPlannedHomePosition(_visualItems, true /* addToCenter */);
465 466
    }

467
    _initAllVisualItems();
468 469
}

470
void MissionController::loadFromFilePicker(void)
471
{
472
#ifndef __mobile__
473
    QString filename = QGCFileDialog::getOpenFileName(MainWindow::instance(), "Select Mission File to load", QString(), "Mission file (*.mission);;All Files (*.*)");
474 475 476 477

    if (filename.isEmpty()) {
        return;
    }
478
    loadFromFile(filename);
479 480 481
#endif
}

482
void MissionController::saveToFile(const QString& filename)
483 484
{
    qDebug() << filename;
485 486 487 488

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

490
    QString missionFilename = filename;
491
    if (!QFileInfo(filename).fileName().contains(".")) {
Don Gagne's avatar
Don Gagne committed
492
        missionFilename += QString(".%1").arg(QGCApplication::missionFileExtension);
493 494
    }

495
    QFile file(missionFilename);
496

497
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
498
        qgcApp()->showMessage(file.errorString());
499
    } else {
500 501 502
        QJsonObject missionFileObject;      // top level json object
        QJsonArray  simpleItemsObject;
        QJsonArray  complexItemsObject;
503

504 505
        missionFileObject[JsonHelper::jsonVersionKey] =         "1.0";
        missionFileObject[JsonHelper::jsonGroundStationKey] =   JsonHelper::jsonGroundStationValue;
506

507 508 509 510 511 512 513 514 515 516
        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();
        }
517
        missionFileObject[_jsonMavAutopilotKey] = firmwareType;
518

519
        // Save planned home position
520
        QJsonObject homePositionObject;
521 522 523 524 525 526 527
        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;
        }
528
        missionFileObject[_jsonPlannedHomePositionKey] = homePositionObject;
529

530
        // Save the visual items
531
        for (int i=1; i<_visualItems->count(); i++) {
532 533
            QJsonObject itemObject;

534
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
535 536 537 538 539 540
            visualItem->save(itemObject);

            if (visualItem->isSimpleItem()) {
                simpleItemsObject.append(itemObject);
            } else {
                complexItemsObject.append(itemObject);
541
            }
542
        }
543

544 545 546 547
        missionFileObject[jsonSimpleItemsKey] = simpleItemsObject;
        missionFileObject[_jsonComplexItemsKey] = complexItemsObject;

        QJsonDocument saveDoc(missionFileObject);
548
        file.write(saveDoc.toJson());
549 550
    }

551
    _visualItems->setDirty(false);
552 553
}

554
void MissionController::saveToFilePicker(void)
555 556
{
#ifndef __mobile__
557
    QString filename = QGCFileDialog::getSaveFileName(MainWindow::instance(), "Select file to save mission to", QString(), "Mission file (*.mission);;All Files (*.*)");
558 559 560 561

    if (filename.isEmpty()) {
        return;
    }
562
    saveToFile(filename);
563
#endif
564 565
}

566
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
567
{
Don Gagne's avatar
Don Gagne committed
568
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
569
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
570 571 572 573
    bool            distanceOk =    false;

    // Convert to fixed altitudes

574
    qCDebug(MissionControllerLog) << homeAlt
575 576
                                  << currentItem->coordinateHasRelativeAltitude() << currentItem->coordinate().altitude()
                                  << prevItem->exitCoordinateHasRelativeAltitude() << prevItem->exitCoordinate().altitude();
577

578
    distanceOk = true;
579
    if (currentItem->coordinateHasRelativeAltitude()) {
580 581
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
582
    if (prevItem->exitCoordinateHasRelativeAltitude()) {
583
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
584 585 586 587 588
    }

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

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
589 590 591
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
592
    } else {
Don Gagne's avatar
Don Gagne committed
593
        *altDifference = 0.0;
594
        *azimuth = 0.0;
595
        *distance = 0.0;
596 597 598
    }
}

599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615
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;
    }
}

616 617
void MissionController::_recalcWaypointLines(void)
{
618 619 620 621 622 623 624 625 626 627
    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();
628 629 630

    qCDebug(MissionControllerLog) << "_recalcWaypointLines";

Nate Weibley's avatar
Nate Weibley committed
631 632
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
633 634 635 636 637 638 639 640 641 642
    _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() &&
643 644
                (qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF ||
                 qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) {
645 646 647 648 649 650 651 652 653 654
            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
655
                        _linesTable[pair] = old_table.take(pair);
656 657 658 659 660 661 662 663 664 665 666 667
                    } 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
668
                        _linesTable[pair] = linevect;
669 670 671 672 673 674 675 676 677 678 679
                    }
                }
                lastCoordinateItem = item;
            }
        }
    }


    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
680 681
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714
            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";

715 716 717
    // 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.
718

719
    // No values for first item
720
    lastCoordinateItem->setAltDifference(0.0);
721
    lastCoordinateItem->setAzimuth(0.0);
722
    lastCoordinateItem->setDistance(0.0);
723

724 725
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
726
    const double homePositionAltitude = homeItem->coordinate().altitude();
727 728
    minAltSeen = maxAltSeen = homeItem->coordinate().altitude();

729 730 731 732 733 734 735 736 737 738 739
    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
740
    bool linkBackToHome = false;
741 742


743 744
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
745 746
        // Assume the worst
        item->setAzimuth(0.0);
747
        item->setDistance(0.0);
748

749
        // If we still haven't found the first coordinate item and we hit a takeoff command link back to home
750 751 752
        if (firstCoordinateItem &&
                item->isSimpleItem() &&
                qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) {
Don Gagne's avatar
Don Gagne committed
753
            linkBackToHome = true;
754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772
            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
773 774
        }

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

778
            double absoluteAltitude = item->coordinate().altitude();
779
            if (item->coordinateHasRelativeAltitude()) {
780 781 782 783 784
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

785 786 787 788 789 790 791 792 793 794
            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
795
                firstCoordinateItem = false;
796
                if (lastCoordinateItem != homeItem || (showHomePosition && linkBackToHome)) {
797
                    double azimuth, distance, altDifference, telemetryDistance;
798 799 800

                    // Subsequent coordinate items link to last coordinate item. If the last coordinate item
                    // is an invalid home position we skip the line
801
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
802 803 804
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822

                    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 {
823
                        missionDistance += qobject_cast<ComplexMissionItem*>(item)->complexDistance();
824 825 826
                        telemetryDistance = qobject_cast<ComplexMissionItem*>(item)->greatestDistanceTo(homeItem->exitCoordinate());

                        if (vtolCalc){
827
                            cruiseDistance += qobject_cast<ComplexMissionItem*>(item)->complexDistance(); //assume all survey missions undertaken in cruise
828 829 830 831 832 833
                        }
                    }

                    if (telemetryDistance > missionMaxTelemetry) {
                        missionMaxTelemetry = telemetryDistance;
                    }
834
                }
835
                else if (lastCoordinateItem == homeItem && !item->isSimpleItem()){
836
                    missionDistance += qobject_cast<ComplexMissionItem*>(item)->complexDistance();
837 838 839
                    missionMaxTelemetry = qobject_cast<ComplexMissionItem*>(item)->greatestDistanceTo(homeItem->exitCoordinate());

                    if (vtolCalc){
840
                        cruiseDistance += qobject_cast<ComplexMissionItem*>(item)->complexDistance(); //assume all survey missions undertaken in cruise
841 842
                    }
                }
843 844 845 846 847
                lastCoordinateItem = item;
            }
        }
    }

848 849 850 851 852
    setMissionDistance(missionDistance);
    setMissionMaxTelemetry(missionMaxTelemetry);
    setCruiseDistance(cruiseDistance);
    setHoverDistance(hoverDistance);

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

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

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

885
            if (complexItem) {
886
                 sequenceNumber = complexItem->lastSequenceNumber() + 1;
887 888 889 890
            } else {
                qWarning() << "isSimpleItem == false, yet not ComplexMissionItem";
            }
        }
891 892 893
    }
}

894 895 896
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
897
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
898 899 900

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

901 902
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
903 904 905 906 907

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
908
        } else if (item->isSimpleItem()) {
909 910 911 912 913
            currentParentItem->childItems()->append(item);
        }
    }
}

914 915
void MissionController::_recalcAll(void)
{
916
    _recalcSequence();
917 918 919 920
    _recalcChildItems();
    _recalcWaypointLines();
}

921
/// Initializes a new set of mission items
922
void MissionController::_initAllVisualItems(void)
923
{
924 925 926 927 928 929 930 931 932
    SimpleMissionItem* homeItem = NULL;

    // Setup home position at index 0

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

Don Gagne's avatar
Don Gagne committed
934
    homeItem->setHomePositionSpecialCase(true);
935
    homeItem->setShowHomePosition(_editMode);
936 937
    homeItem->missionItem().setCommand(MAV_CMD_NAV_WAYPOINT);
    homeItem->missionItem().setFrame(MAV_FRAME_GLOBAL);
938 939 940 941 942
    homeItem->setIsCurrentItem(true);

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

945 946 947 948
    emit plannedHomePositionChanged(plannedHomePosition());

    connect(homeItem, &VisualMissionItem::coordinateChanged, this, &MissionController::_homeCoordinateChanged);

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
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
977

978
    _visualItems->setDirty(false);
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
    disconnect(_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::complexDistanceChanged, 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
void MissionController::_activeVehicleBeingRemoved(void)
1027
{
1028
    qCDebug(MissionControllerLog) << "MissionController::_activeVehicleBeingRemoved";
1029

1030
    MissionManager* missionManager = _activeVehicle->missionManager();
1031 1032 1033 1034

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

Don Gagne's avatar
Don Gagne committed
1038 1039
    // 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
1040 1041
    removeAll();
}
Don Gagne's avatar
Don Gagne committed
1042

1043 1044 1045 1046 1047
void MissionController::_activeVehicleSet(void)
{
    // 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
    removeAll();
1048

1049 1050 1051 1052 1053 1054 1055
    MissionManager* missionManager = _activeVehicle->missionManager();

    connect(missionManager, &MissionManager::newMissionItemsAvailable,  this, &MissionController::_newMissionItemsAvailableFromVehicle);
    connect(missionManager, &MissionManager::inProgressChanged,         this, &MissionController::_inProgressChanged);
    connect(missionManager, &MissionManager::currentItemChanged,        this, &MissionController::_currentMissionItemChanged);
    connect(_activeVehicle, &Vehicle::homePositionAvailableChanged,     this, &MissionController::_activeVehicleHomePositionAvailableChanged);
    connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);
1056

1057
    if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
1058 1059 1060
        // 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.
        loadFromVehicle();
1061
    }
1062

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

void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
1069 1070 1071 1072 1073
    if (!_editMode && _visualItems) {
        SimpleMissionItem* homeItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(0));

        if (homeItem) {
            homeItem->setShowHomePosition(homePositionAvailable);
1074
            emit plannedHomePositionChanged(plannedHomePosition());
1075 1076 1077 1078
            _recalcWaypointLines();
        } else {
            qWarning() << "Unabled to cast home item to SimpleMissionItem";
        }
1079
    }
1080 1081 1082 1083
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
1084
    if (!_editMode && _visualItems) {
1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
        if (item) {
            if (item->coordinate() != homePosition) {
                item->setCoordinate(homePosition);
                qCDebug(MissionControllerLog) << "Home position update" << homePosition;
                emit plannedHomePositionChanged(plannedHomePosition());
                _recalcWaypointLines();
            }
        } else {
            qWarning() << "Unabled to cast home item to VisualMissionItem";
        }
1096
    }
1097 1098
}

1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130
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);
    }
}

1131
void MissionController::_inProgressChanged(bool inProgress)
1132
{
1133
    emit syncInProgressChanged(inProgress);
1134
}
1135

1136
bool MissionController::_findLastAltitude(double* lastAltitude, MAV_FRAME* frame)
1137
{
1138
    bool found = false;
1139
    double foundAltitude;
1140
    MAV_FRAME foundFrame;
1141

1142
    // Don't use home position
1143
    for (int i=1; i<_visualItems->count(); i++) {
1144
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1145

1146 1147 1148 1149
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {

            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1150 1151 1152 1153
                if ((MAV_CMD)simpleItem->command() != MAV_CMD_NAV_TAKEOFF) {
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1154 1155
                }
            }
1156 1157 1158
        }
    }

1159 1160
    if (found) {
        *lastAltitude = foundAltitude;
1161
        *frame = foundFrame;
1162 1163 1164 1165 1166 1167 1168 1169 1170 1171
    }

    return found;
}

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

1172 1173
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1174

1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185
        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";
            }
1186 1187 1188 1189 1190 1191 1192 1193
        }
    }

    if (found) {
        *lastAcceptanceRadius = foundAcceptanceRadius;
    }

    return found;
1194
}
1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208

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
1209
void MissionController::_addPlannedHomePosition(QmlObjectListModel* visualItems, bool addToCenter)
1210
{
1211 1212
    bool homePositionSet = false;

1213 1214
    SimpleMissionItem* homeItem = new SimpleMissionItem(_activeVehicle, this);
    visualItems->insert(0, homeItem);
1215

1216
    if (visualItems->count() > 1  && addToCenter) {
1217 1218
        double north, south, east, west;
        bool firstCoordSet = false;
1219

1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239
        for (int i=1; i<visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(visualItems->get(i));

            if (item->specifiesCoordinate()) {
                if (firstCoordSet) {
                    double lat = _normalizeLat(item->coordinate().latitude());
                    double lon = _normalizeLon(item->coordinate().longitude());
                    north = fmax(north, lat);
                    south = fmin(south, lat);
                    east = fmax(east, lon);
                    west = fmin(west, lon);
                } else {
                    firstCoordSet = true;
                    north = _normalizeLat(item->coordinate().latitude());
                    south = north;
                    east = _normalizeLon(item->coordinate().longitude());
                    west = east;
                }
            }
        }
1240

1241 1242 1243
        if (firstCoordSet) {
            homePositionSet = true;
            homeItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
1244
        }
1245
    }
1246

1247
    if (!homePositionSet) {
1248 1249 1250
        homeItem->setCoordinate(qgcApp()->lastKnownHomePosition());
    }
}
1251 1252 1253 1254 1255 1256 1257 1258

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

1259 1260
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1261 1262 1263 1264
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
    }
}
1265

1266
bool MissionController::syncInProgress(void) const
1267
{
1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280
    return _activeVehicle ? _activeVehicle->missionManager()->inProgress() : false;
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1281
    }
1282
}
1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300

QGeoCoordinate MissionController::plannedHomePosition(void)
{
    if (_visualItems && _visualItems->count() > 0) {
        SimpleMissionItem* item = qobject_cast<SimpleMissionItem*>(_visualItems->get(0));
        if (item && item->showHomePosition()) {
            return item->coordinate();
        }
    }

    return QGeoCoordinate();
}

void MissionController::_homeCoordinateChanged(void)
{
    emit plannedHomePositionChanged(plannedHomePosition());
    _recalcAltitudeRangeBearing();
}
1301 1302 1303 1304 1305

QString MissionController::fileExtension(void) const
{
    return QGCApplication::missionFileExtension;
}