MissionController.cc 47.4 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 "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
    SurveyMissionItem* newItem = new SurveyMissionItem(_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
    _deinitVisualItem(item);
    if (!item->isSimpleItem()) {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(_complexItems->removeOne(item));
223
        if (!complexItem) {
224 225 226
            qWarning() << "Complex item missing";
        }
    }
227
    item->deleteLater();
228 229 230 231 232

    _recalcAll();

    // Set the new current item

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

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

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

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

    QJsonObject json = jsonDoc.object();

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

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

289 290 291 292 293
    // 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];
294

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

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

309 310 311 312 313 314 315 316 317 318 319 320 321
    // 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()) {
322
            SurveyMissionItem* complexItem = qobject_cast<SurveyMissionItem*>(complexItems->get(nextComplexItemIndex));
323 324 325 326 327 328 329 330 331 332 333 334 335 336

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

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

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

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

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

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

    return true;
}

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

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

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

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

    return true;
417 418
}

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

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

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

    QFile file(filename);

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

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

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

457
        qgcApp()->showMessage(errorString);
458
        return;
459 460
    }

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

    _visualItems = newVisualItems;
    _complexItems = newComplexItems;

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

476
    _initAllVisualItems();
477 478
}

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

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

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

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

504
    QFile file(missionFilename);
505

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

513 514
        missionFileObject[_jsonVersionKey] =        "1.0";
        missionFileObject[_jsonGroundStationKey] =  "QGroundControl";
515

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

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

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

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

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

553 554 555 556
        missionFileObject[jsonSimpleItemsKey] = simpleItemsObject;
        missionFileObject[_jsonComplexItemsKey] = complexItemsObject;

        QJsonDocument saveDoc(missionFileObject);
557
        file.write(saveDoc.toJson());
558 559
    }

560
    _visualItems->setDirty(false);
561 562
}

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

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

    // Convert to fixed altitudes

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

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

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

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

608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624
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;
    }
}

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

    bool    showHomePosition =  homeItem->showHomePosition();
639 640 641

    qCDebug(MissionControllerLog) << "_recalcWaypointLines";

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


    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
690 691
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
692 693 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
            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";

725 726 727
    // 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.
728

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

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

739 740 741 742 743 744 745 746 747 748 749
    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
750
    bool linkBackToHome = false;
751 752


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

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

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

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

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

                    // Subsequent coordinate items link to last coordinate item. If the last coordinate item
                    // is an invalid home position we skip the line
811
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
812 813 814
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832

                    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 {
833
                        missionDistance += qobject_cast<ComplexMissionItem*>(item)->complexDistance();
834 835 836
                        telemetryDistance = qobject_cast<ComplexMissionItem*>(item)->greatestDistanceTo(homeItem->exitCoordinate());

                        if (vtolCalc){
837
                            cruiseDistance += qobject_cast<ComplexMissionItem*>(item)->complexDistance(); //assume all survey missions undertaken in cruise
838 839 840 841 842 843
                        }
                    }

                    if (telemetryDistance > missionMaxTelemetry) {
                        missionMaxTelemetry = telemetryDistance;
                    }
844
                }
845
                else if (lastCoordinateItem == homeItem && !item->isSimpleItem()){
846
                    missionDistance += qobject_cast<ComplexMissionItem*>(item)->complexDistance();
847 848 849
                    missionMaxTelemetry = qobject_cast<ComplexMissionItem*>(item)->greatestDistanceTo(homeItem->exitCoordinate());

                    if (vtolCalc){
850
                        cruiseDistance += qobject_cast<ComplexMissionItem*>(item)->complexDistance(); //assume all survey missions undertaken in cruise
851 852
                    }
                }
853 854 855 856 857
                lastCoordinateItem = item;
            }
        }
    }

858 859 860 861 862
    setMissionDistance(missionDistance);
    setMissionMaxTelemetry(missionMaxTelemetry);
    setCruiseDistance(cruiseDistance);
    setHoverDistance(hoverDistance);

863 864
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
865 866
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
867 868 869

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
870
            if (item->coordinateHasRelativeAltitude()) {
871 872 873 874 875 876
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
877
            }
878 879 880 881
        }
    }
}

882 883 884
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
885 886 887 888 889 890 891 892 893
    // 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);
894

895
            if (complexItem) {
896
                 sequenceNumber = complexItem->lastSequenceNumber() + 1;
897 898 899 900
            } else {
                qWarning() << "isSimpleItem == false, yet not ComplexMissionItem";
            }
        }
901 902 903
    }
}

904 905 906
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
907
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
908 909 910

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

911 912
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
913 914 915 916 917

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
918
        } else if (item->isSimpleItem()) {
919 920 921 922 923
            currentParentItem->childItems()->append(item);
        }
    }
}

924 925
void MissionController::_recalcAll(void)
{
926
    _recalcSequence();
927 928 929 930
    _recalcChildItems();
    _recalcWaypointLines();
}

931
/// Initializes a new set of mission items
932
void MissionController::_initAllVisualItems(void)
933
{
934 935 936 937 938 939 940 941 942
    SimpleMissionItem* homeItem = NULL;

    // Setup home position at index 0

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

Don Gagne's avatar
Don Gagne committed
944
    homeItem->setHomePositionSpecialCase(true);
945
    homeItem->setShowHomePosition(_editMode);
946 947
    homeItem->missionItem().setCommand(MAV_CMD_NAV_WAYPOINT);
    homeItem->missionItem().setFrame(MAV_FRAME_GLOBAL);
948 949 950 951 952
    homeItem->setIsCurrentItem(true);

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

955
    QmlObjectListModel* newComplexItems = new QmlObjectListModel(this);
956 957 958
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
959

960 961 962
        // Set up complex item list
        if (!item->isSimpleItem()) {
            ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);
963

964 965 966 967 968
            if (complexItem) {
                newComplexItems->append(item);
            } else {
                qWarning() << "isSimpleItem == false, but not ComplexMissionItem";
            }
969
        }
970 971
    }

972 973 974 975
    if (_complexItems) {
        _complexItems->deleteLater();
    }
    _complexItems = newComplexItems;
976

977
    _recalcAll();
978

979 980
    emit visualItemsChanged();
    emit complexVisualItemsChanged();
981

982
    _visualItems->setDirty(false);
983

984
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_dirtyChanged);
985 986
}

987
void MissionController::_deinitAllVisualItems(void)
988
{
989 990
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
991 992
    }

993
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_dirtyChanged);
994 995
}

996
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
997
{
998 999
    _visualItems->setDirty(false);

1000
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1001 1002
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
1003

1004 1005 1006 1007 1008 1009 1010 1011
    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";
        }
1012 1013 1014 1015
    } 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);
1016
        connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcAltitudeRangeBearing);
1017
    }
1018 1019
}

1020
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1021
{
1022 1023
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1024 1025
}

1026
void MissionController::_itemCommandChanged(void)
1027
{
1028 1029
    _recalcChildItems();
    _recalcWaypointLines();
1030 1031 1032 1033
}

void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
{
1034 1035
    qCDebug(MissionControllerLog) << "_activeVehicleChanged activeVehicle" << activeVehicle;

1036 1037
    if (_activeVehicle) {
        MissionManager* missionManager = _activeVehicle->missionManager();
1038

1039
        disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailableFromVehicle);
1040
        disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
1041
        disconnect(missionManager, &MissionManager::currentItemChanged,         this, &MissionController::_currentMissionItemChanged);
1042 1043
        disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged,      this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
1044
        _activeVehicle = NULL;
Don Gagne's avatar
Don Gagne committed
1045 1046
    }

Don Gagne's avatar
Don Gagne committed
1047 1048 1049 1050
    // 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();

1051
    _activeVehicle = activeVehicle;
1052

1053 1054
    if (_activeVehicle) {
        MissionManager* missionManager = activeVehicle->missionManager();
1055

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

1062 1063 1064
        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
1065
            getMissionItems();
1066
        }
1067 1068 1069 1070

        _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
        _activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
    }
1071 1072 1073

    // Whenever vehicle changes we need to update syncInProgress
    emit syncInProgressChanged(syncInProgress());
1074 1075 1076 1077
}

void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
1078 1079 1080 1081 1082 1083 1084 1085 1086
    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";
        }
1087
    }
1088 1089 1090 1091
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
1092 1093
    if (!_editMode && _visualItems) {
        qobject_cast<VisualMissionItem*>(_visualItems->get(0))->setCoordinate(homePosition);
1094 1095
        _recalcWaypointLines();
    }
1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112
}

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
}

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 1139 1140 1141 1142 1143 1144
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);
    }
}

1145 1146 1147
void MissionController::_dirtyChanged(bool dirty)
{
    if (dirty && _autoSync) {
1148
        Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162

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

void MissionController::_autoSyncSend(void)
{
    _queuedSend = false;
1163
    if (_visualItems) {
1164
        sendMissionItems();
1165
        _visualItems->setDirty(false);
1166 1167
    }
}
1168

1169
void MissionController::_inProgressChanged(bool inProgress)
1170
{
1171
    emit syncInProgressChanged(inProgress);
1172 1173 1174 1175
    if (!inProgress && _queuedSend) {
        _autoSyncSend();
    }
}
1176

1177
bool MissionController::_findLastAltitude(double* lastAltitude, MAV_FRAME* frame)
1178
{
1179
    bool found = false;
1180
    double foundAltitude;
1181
    MAV_FRAME foundFrame;
1182

1183
    // Don't use home position
1184
    for (int i=1; i<_visualItems->count(); i++) {
1185
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1186

1187 1188 1189 1190
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {

            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1191 1192 1193 1194
                if ((MAV_CMD)simpleItem->command() != MAV_CMD_NAV_TAKEOFF) {
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1195 1196
                }
            }
1197 1198 1199
        }
    }

1200 1201
    if (found) {
        *lastAltitude = foundAltitude;
1202
        *frame = foundFrame;
1203 1204 1205 1206 1207 1208 1209 1210 1211 1212
    }

    return found;
}

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

1213 1214
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1215

1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226
        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";
            }
1227 1228 1229 1230 1231 1232 1233 1234
        }
    }

    if (found) {
        *lastAcceptanceRadius = foundAcceptanceRadius;
    }

    return found;
1235
}
1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249

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
1250
void MissionController::_addPlannedHomePosition(QmlObjectListModel* visualItems, bool addToCenter)
1251
{
1252 1253
    SimpleMissionItem* homeItem = new SimpleMissionItem(_activeVehicle, this);
    visualItems->insert(0, homeItem);
1254

1255 1256
    if (visualItems->count() > 1  && addToCenter) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(visualItems->get(1));
1257 1258 1259 1260 1261 1262

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

1263 1264
        for (int i=2; i<visualItems->count(); i++) {
            item = qobject_cast<VisualMissionItem*>(visualItems->get(i));
1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279

            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());
    }
}
1280 1281 1282 1283 1284 1285 1286 1287

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

1288 1289
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1290 1291 1292 1293
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
    }
}
1294

1295 1296
bool MissionController::syncInProgress(void)
{
1297 1298 1299 1300 1301
    if (_activeVehicle) {
        return _activeVehicle->missionManager()->inProgress();
    } else {
        return false;
    }
1302
}