MissionController.cc 29.4 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27
/*=====================================================================

QGroundControl Open Source Ground Control Station

(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>

This file is part of the QGROUNDCONTROL project

    QGROUNDCONTROL is free software: you can redistribute it and/or modify
    it under the terms of the GNU General Public License as published by
    the Free Software Foundation, either version 3 of the License, or
    (at your option) any later version.

    QGROUNDCONTROL is distributed in the hope that it will be useful,
    but WITHOUT ANY WARRANTY; without even the implied warranty of
    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
    GNU General Public License for more details.

    You should have received a copy of the GNU General Public License
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.

======================================================================*/

#include "MissionController.h"
#include "MultiVehicleManager.h"
#include "MissionManager.h"
#include "CoordinateVector.h"
28
#include "FirmwarePlugin.h"
29
#include "QGCApplication.h"
30

31 32 33 34
#ifndef __mobile__
#include "QGCFileDialog.h"
#endif

35 36
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

37 38 39 40 41 42
const char* MissionController::_settingsGroup =                 "MissionController";
const char* MissionController::_jsonVersionKey =                "version";
const char* MissionController::_jsonGroundStationKey =          "groundStation";
const char* MissionController::_jsonMavAutopilotKey =           "MAV_AUTOPILOT";
const char* MissionController::_jsonItemsKey =                  "items";
const char* MissionController::_jsonPlannedHomePositionKey =    "plannedHomePosition";
43 44 45

MissionController::MissionController(QObject *parent)
    : QObject(parent)
46
    , _editMode(false)
47 48
    , _missionItems(NULL)
    , _activeVehicle(NULL)
49
    , _autoSync(false)
50
    , _firstItemsFromVehicle(false)
51 52
    , _missionItemsRequested(false)
    , _queuedSend(false)
53
{
54 55 56 57 58

}

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

60 61 62 63
}

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

66 67
    _editMode = editMode;

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

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

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

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

84 85 86 87 88 89 90 91
    if (!_editMode || _missionItemsRequested || _missionItems->count() == 1) {
        // Fly Mode:
        //      - Always accepts new items fromthe vehicle so Fly view is kept up to date
        // Edit Mode:
        //      - Either a load from vehicle was manually requested or
        //      - The initial automatic load from a vehicle completed and the current editor it empty
        _deinitAllMissionItems();
        _missionItems->deleteLater();
92

93 94
        _missionItems = _activeVehicle->missionManager()->copyMissionItems();
        qCDebug(MissionControllerLog) << "loading from vehicle count"<< _missionItems->count();
95

96
        if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _missionItems->count() == 0) {
97
            _addPlannedHomePosition(_missionItems,true /* addToCenter */);
98 99
        }

100
        _missionItemsRequested = false;
101

102 103
        _initAllMissionItems();
        emit newItemsFromVehicle();
104 105 106
    }
}

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

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

void MissionController::sendMissionItems(void)
{
119
    Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
120

121 122 123 124 125
    if (activeVehicle) {
        activeVehicle->missionManager()->writeMissionItems(*_missionItems);
        _missionItems->setDirty(false);
    }
}
126

127
int MissionController::insertMissionItem(QGeoCoordinate coordinate, int i)
128
{
129
    MissionItem * newItem = new MissionItem(_activeVehicle, this);
130 131 132
    newItem->setSequenceNumber(_missionItems->count());
    newItem->setCoordinate(coordinate);
    newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
133 134 135 136
    _initMissionItem(newItem);
    if (_missionItems->count() == 1) {
        newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
    }
137
    newItem->setDefaultsForCommand();
Don Gagne's avatar
Don Gagne committed
138
    if ((MAV_CMD)newItem->command() == MAV_CMD_NAV_WAYPOINT) {
139 140 141 142 143 144 145 146
        double lastValue;

        if (_findLastAcceptanceRadius(&lastValue)) {
            newItem->setParam2(lastValue);
        }
        if (_findLastAltitude(&lastValue)) {
            newItem->setParam7(lastValue);
        }
147
    }
148
    _missionItems->insert(i, newItem);
149 150 151 152 153 154 155 156 157 158 159

    _recalcAll();

    return _missionItems->count() - 1;
}

void MissionController::removeMissionItem(int index)
{
    MissionItem* item = qobject_cast<MissionItem*>(_missionItems->removeAt(index));

    _deinitMissionItem(item);
160
    item->deleteLater();
161 162 163 164 165 166 167 168 169 170 171 172

    _recalcAll();

    // Set the new current item

    if (index >= _missionItems->count()) {
        index--;
    }
    for (int i=0; i<_missionItems->count(); i++) {
        MissionItem* item =  qobject_cast<MissionItem*>(_missionItems->get(i));
        item->setIsCurrentItem(i == index);
    }
173
    _missionItems->setDirty(true);
174 175
}

176 177 178
void MissionController::removeAllMissionItems(void)
{
    if (_missionItems) {
179 180 181 182 183
        QmlObjectListModel* oldItems = _missionItems;
        _missionItems = new QmlObjectListModel(this);
        _addPlannedHomePosition(_missionItems, false /* addToCenter */);
        _initAllMissionItems();
        oldItems->deleteLater();
184
    }
185
}
186

187
bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectListModel* missionItems, QString& errorString)
188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222
{
    QJsonParseError jsonParseError;
    QJsonDocument   jsonDoc(QJsonDocument::fromJson(bytes, &jsonParseError));

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

    QJsonObject json = jsonDoc.object();

    if (!json.contains(_jsonVersionKey)) {
        errorString = QStringLiteral("File is missing version key");
        return false;
    }
    if (json[_jsonVersionKey].toString() != "1.0") {
        errorString = QStringLiteral("QGroundControl does not support this file version");
        return false;
    }

    if (json.contains(_jsonItemsKey)) {
        if (!json[_jsonItemsKey].isArray()) {
            errorString = QStringLiteral("items values must be array");
            return false;
        }

        QJsonArray itemArray(json[_jsonItemsKey].toArray());
        foreach (const QJsonValue& itemValue, itemArray) {
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

            MissionItem* item = new MissionItem(_activeVehicle, this);
            if (item->load(itemValue.toObject(), errorString)) {
223
                missionItems->append(item);
224 225 226 227 228 229 230 231 232 233
            } else {
                return false;
            }
        }
    }

    if (json.contains(_jsonPlannedHomePositionKey)) {
        MissionItem* item = new MissionItem(_activeVehicle, this);

        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), errorString)) {
234
            missionItems->insert(0, item);
235 236 237 238
        } else {
            return false;
        }
    } else {
239
        _addPlannedHomePosition(missionItems, true /* addToCenter */);
240 241 242 243 244
    }

    return true;
}

245
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* missionItems, QString& errorString)
246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268
{
    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()) {
            MissionItem* item = new MissionItem(_activeVehicle, this);

            if (item->load(stream)) {
269
                missionItems->append(item);
270 271 272 273 274 275 276 277 278 279
            } 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;
    }

280 281
    if (addPlannedHomePosition || missionItems->count() == 0) {
        _addPlannedHomePosition(missionItems, true /* addToCenter */);
Don Gagne's avatar
Don Gagne committed
282 283

        // Update sequence numbers in DO_JUMP commands to take into account added home position
284 285
        for (int i=1; i<missionItems->count(); i++) {
            MissionItem* item = qobject_cast<MissionItem*>(missionItems->get(i));
Don Gagne's avatar
Don Gagne committed
286 287 288 289 290
            if (item->command() == MavlinkQmlSingleton::MAV_CMD_DO_JUMP) {
                // Home is in position 0
                item->setParam1((int)item->param1() + 1);
            }
        }
291 292 293
    }

    return true;
294 295
}

296
void MissionController::_loadMissionFromFile(const QString& filename)
297 298 299 300 301 302 303
{
    QString errorString;

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

304
    QmlObjectListModel* newMissionItems = new QmlObjectListModel(this);
305 306 307 308 309 310

    QFile file(filename);

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

314 315 316
        QString firstLine = stream.readLine();
        if (firstLine.contains(QRegExp("QGC.*WPL"))) {
            stream.seek(0);
317
            _loadTextMissionFile(stream, newMissionItems, errorString);
318
        } else {
319
            _loadJsonMissionFile(bytes, newMissionItems, errorString);
320 321
        }
    }
322

323
    if (!errorString.isEmpty()) {
324
        delete newMissionItems;
325
        qgcApp()->showMessage(errorString);
326
        return;
327 328
    }

329 330 331 332 333
    if (_missionItems) {
        _deinitAllMissionItems();
        _missionItems->deleteLater();
    }
    _missionItems = newMissionItems;
334
    if (_missionItems->count() == 0) {
335
        _addPlannedHomePosition(_missionItems, true /* addToCenter */);
336 337
    }

338
    _initAllMissionItems();
339 340
}

341
void MissionController::loadMissionFromFile(void)
342
{
343
#ifndef __mobile__
344 345 346 347 348 349 350 351 352 353 354 355
    QString filename = QGCFileDialog::getOpenFileName(NULL, "Select Mission File to load", QString(), "Mission file (*.mission);;All Files (*.*)");

    if (filename.isEmpty()) {
        return;
    }
    _loadMissionFromFile(filename);
#endif
}

void MissionController::_saveMissionToFile(const QString& filename)
{
    qDebug() << filename;
356 357 358 359

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

361
    QString missionFilename = filename;
362
    if (!QFileInfo(filename).fileName().contains(".")) {
363
        missionFilename += ".mission";
364 365
    }

366
    QFile file(missionFilename);
367

368
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
369
        qgcApp()->showMessage(file.errorString());
370
    } else {
371
        QJsonObject missionObject;
372

373 374
        missionObject[_jsonVersionKey] = "1.0";
        missionObject[_jsonGroundStationKey] = "QGroundControl";
375

376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392
        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();
        }
        missionObject[_jsonMavAutopilotKey] = firmwareType;

        QJsonObject homePositionObject;
        qobject_cast<MissionItem*>(_missionItems->get(0))->save(homePositionObject);
        missionObject["plannedHomePosition"] = homePositionObject;

        QJsonArray itemArray;
393
        for (int i=1; i<_missionItems->count(); i++) {
394 395 396
            QJsonObject itemObject;
            qobject_cast<MissionItem*>(_missionItems->get(i))->save(itemObject);
            itemArray.append(itemObject);
397
        }
398 399 400 401
        missionObject["items"] = itemArray;

        QJsonDocument saveDoc(missionObject);
        file.write(saveDoc.toJson());
402 403 404
    }

    _missionItems->setDirty(false);
405 406 407 408 409 410 411 412 413 414
}

void MissionController::saveMissionToFile(void)
{
#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
415
    _saveMissionToFile(filename);
416
#endif
417 418
}

419 420 421 422 423 424 425 426
void MissionController::saveMobileMissionToFile(const QString& filename)
{
    QStringList docDirs = QStandardPaths::standardLocations(QStandardPaths::DocumentsLocation);
    if (docDirs.count() <= 0) {
        qWarning() << "No Documents location";
        return;
    }

Don Gagne's avatar
Don Gagne committed
427
    _saveMissionToFile(docDirs.at(0) + QDir::separator() + filename);
428 429 430 431 432 433 434 435 436 437 438 439
}

void MissionController::loadMobileMissionFromFile(const QString& filename)
{
    QStringList docDirs = QStandardPaths::standardLocations(QStandardPaths::DocumentsLocation);
    if (docDirs.count() <= 0) {
        qWarning() << "No Documents location";
        return;
    }
    _loadMissionFromFile(docDirs.at(0) + QDir::separator() + filename);
}

440
void MissionController::_calcPrevWaypointValues(double homeAlt, MissionItem* currentItem, MissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
441
{
Don Gagne's avatar
Don Gagne committed
442 443
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  prevCoord =     prevItem->coordinate();
444 445 446 447
    bool            distanceOk =    false;

    // Convert to fixed altitudes

448
    qCDebug(MissionControllerLog) << homeAlt
Don Gagne's avatar
Don Gagne committed
449 450
                                  << currentItem->relativeAltitude() << currentItem->coordinate().altitude()
                                  << prevItem->relativeAltitude() << prevItem->coordinate().altitude();
451

452 453 454 455 456 457
    distanceOk = true;
    if (currentItem->relativeAltitude()) {
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
    if (prevItem->relativeAltitude()) {
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
458 459 460 461 462
    }

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

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
463 464 465
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
466
    } else {
Don Gagne's avatar
Don Gagne committed
467
        *altDifference = 0.0;
468
        *azimuth = 0.0;
Don Gagne's avatar
Don Gagne committed
469
        *distance = -1.0;   // Signals no values
470 471 472
    }
}

473 474 475
void MissionController::_recalcWaypointLines(void)
{
    MissionItem*    lastCoordinateItem =    qobject_cast<MissionItem*>(_missionItems->get(0));
476
    MissionItem*    homeItem =              lastCoordinateItem;
477
    bool            firstCoordinateItem =   true;
478
    bool            showHomePosition =      homeItem->showHomePosition();
479 480 481 482 483 484 485
    double          homeAlt =               homeItem->coordinate().altitude();

    qCDebug(MissionControllerLog) << "_recalcWaypointLines";

    // 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.
486

487
    // No values for first item
488
    lastCoordinateItem->setAltDifference(0.0);
489
    lastCoordinateItem->setAzimuth(0.0);
490 491
    lastCoordinateItem->setDistance(-1.0);

492 493 494 495 496
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
    double homePositionAltitude = homeItem->coordinate().altitude();
    minAltSeen = maxAltSeen = homeItem->coordinate().altitude();

497 498
    _waypointLines.clear();

Don Gagne's avatar
Don Gagne committed
499
    bool linkBackToHome = false;
500 501 502
    for (int i=1; i<_missionItems->count(); i++) {
        MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));

503 504 505
        // Assume the worst
        item->setAzimuth(0.0);
        item->setDistance(-1.0);
506

Don Gagne's avatar
Don Gagne committed
507 508 509 510
        if (firstCoordinateItem && item->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) {
            linkBackToHome = true;
        }

511 512
        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
513
            if (item->relativeAltitude()) {
514 515 516 517 518 519
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

            if (!item->standaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
520 521
                firstCoordinateItem = false;
                if (!lastCoordinateItem->homePosition() || (showHomePosition && linkBackToHome)) {
522 523 524 525
                    double azimuth, distance, altDifference;

                    // Subsequent coordinate items link to last coordinate item. If the last coordinate item
                    // is an invalid home position we skip the line
526
                    _calcPrevWaypointValues(homeAlt, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
527 528 529 530
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
                    _waypointLines.append(new CoordinateVector(lastCoordinateItem->coordinate(), item->coordinate()));
531
                }
532 533 534 535 536 537 538 539 540 541 542 543
                lastCoordinateItem = item;
            }
        }
    }

    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
    for (int i=0; i<_missionItems->count(); i++) {
        MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
544
            if (item->relativeAltitude()) {
545 546 547 548 549 550
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
551
            }
552 553
        }
    }
554 555

    emit waypointLinesChanged();
556 557
}

558 559 560 561 562 563 564 565 566 567 568
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
    for (int i=0; i<_missionItems->count(); i++) {
        MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));

        // Setup ascending sequence numbers
        item->setSequenceNumber(i);
    }
}

569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
    MissionItem* currentParentItem = qobject_cast<MissionItem*>(_missionItems->get(0));

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

    for (int i=1; i<_missionItems->count(); i++) {
        MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
        } else {
            currentParentItem->childItems()->append(item);
        }
    }
}

589 590
void MissionController::_recalcAll(void)
{
591
    _recalcSequence();
592 593 594 595
    _recalcChildItems();
    _recalcWaypointLines();
}

596
/// Initializes a new set of mission items
597 598
void MissionController::_initAllMissionItems(void)
{
599 600
    MissionItem* homeItem = NULL;

601
    homeItem = qobject_cast<MissionItem*>(_missionItems->get(0));
Don Gagne's avatar
Don Gagne committed
602
    homeItem->setHomePositionSpecialCase(true);
603
    homeItem->setShowHomePosition(_editMode);
Don Gagne's avatar
Don Gagne committed
604 605
    homeItem->setCommand(MAV_CMD_NAV_WAYPOINT);
    homeItem->setFrame(MAV_FRAME_GLOBAL);
606 607 608 609 610
    homeItem->setIsCurrentItem(true);

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

613
    qDebug() << "home item" << homeItem->coordinate();
DonLakeFlyer's avatar
DonLakeFlyer committed
614

615 616 617 618
    for (int i=0; i<_missionItems->count(); i++) {
        _initMissionItem(qobject_cast<MissionItem*>(_missionItems->get(i)));
    }

619
    _recalcAll();
620

621
    emit missionItemsChanged();
622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642

    _missionItems->setDirty(false);

    connect(_missionItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_dirtyChanged);
}

void MissionController::_deinitAllMissionItems(void)
{
    for (int i=0; i<_missionItems->count(); i++) {
        _deinitMissionItem(qobject_cast<MissionItem*>(_missionItems->get(i)));
    }

    connect(_missionItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_dirtyChanged);
}

void MissionController::_initMissionItem(MissionItem* item)
{
    _missionItems->setDirty(false);

    connect(item, &MissionItem::commandChanged,     this, &MissionController::_itemCommandChanged);
    connect(item, &MissionItem::coordinateChanged,  this, &MissionController::_itemCoordinateChanged);
643
    connect(item, &MissionItem::frameChanged,       this, &MissionController::_itemFrameChanged);
644 645 646 647 648 649
}

void MissionController::_deinitMissionItem(MissionItem* item)
{
    disconnect(item, &MissionItem::commandChanged,     this, &MissionController::_itemCommandChanged);
    disconnect(item, &MissionItem::coordinateChanged,  this, &MissionController::_itemCoordinateChanged);
650
    disconnect(item, &MissionItem::frameChanged,       this, &MissionController::_itemFrameChanged);
651 652 653 654 655 656 657 658
}

void MissionController::_itemCoordinateChanged(const QGeoCoordinate& coordinate)
{
    Q_UNUSED(coordinate);
    _recalcWaypointLines();
}

659 660 661 662 663 664
void MissionController::_itemFrameChanged(int frame)
{
    Q_UNUSED(frame);
    _recalcWaypointLines();
}

665 666 667 668 669
void MissionController::_itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command)
{
    Q_UNUSED(command);;
    _recalcChildItems();
    _recalcWaypointLines();
670 671 672 673
}

void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
{
674 675
    qCDebug(MissionControllerLog) << "_activeVehicleChanged activeVehicle" << activeVehicle;

676 677
    if (_activeVehicle) {
        MissionManager* missionManager = _activeVehicle->missionManager();
678

679
        disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailableFromVehicle);
680
        disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
681
        disconnect(missionManager, &MissionManager::currentItemChanged,         this, &MissionController::_currentMissionItemChanged);
682 683
        disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged,      this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
684
        _activeVehicle = NULL;
Don Gagne's avatar
Don Gagne committed
685 686
    }

687
    _activeVehicle = activeVehicle;
688

689 690
    if (_activeVehicle) {
        MissionManager* missionManager = activeVehicle->missionManager();
691

692
        connect(missionManager, &MissionManager::newMissionItemsAvailable,  this, &MissionController::_newMissionItemsAvailableFromVehicle);
693
        connect(missionManager, &MissionManager::inProgressChanged,         this, &MissionController::_inProgressChanged);
694
        connect(missionManager, &MissionManager::currentItemChanged,        this, &MissionController::_currentMissionItemChanged);
695 696 697
        connect(_activeVehicle, &Vehicle::homePositionAvailableChanged,     this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);

698 699 700
        if (!_editMode) {
            removeAllMissionItems();
        }
701 702 703 704 705 706 707 708

        _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
        _activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
    }
}

void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
709 710 711 712
    if (!_editMode && _missionItems) {
        qobject_cast<MissionItem*>(_missionItems->get(0))->setShowHomePosition(homePositionAvailable);
        _recalcWaypointLines();
    }
713 714 715 716
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
717 718 719 720
    if (!_editMode && _missionItems) {
        qobject_cast<MissionItem*>(_missionItems->get(0))->setCoordinate(homePosition);
        _recalcWaypointLines();
    }
721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740
}

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

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

void MissionController::_dirtyChanged(bool dirty)
{
    if (dirty && _autoSync) {
741
        Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759

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

void MissionController::_autoSyncSend(void)
{
    qDebug() << "Auto-syncing with vehicle";
    _queuedSend = false;
    if (_missionItems) {
        sendMissionItems();
        _missionItems->setDirty(false);
760 761
    }
}
762

763
void MissionController::_inProgressChanged(bool inProgress)
764
{
765
    emit syncInProgressChanged(inProgress);
766 767 768 769
    if (!inProgress && _queuedSend) {
        _autoSyncSend();
    }
}
770

771 772 773
QmlObjectListModel* MissionController::missionItems(void)
{
    return _missionItems;
774
}
775

776
bool MissionController::_findLastAltitude(double* lastAltitude)
777
{
778 779
    bool found = false;
    double foundAltitude;
780

781 782
    // Don't use home position
    for (int i=1; i<_missionItems->count(); i++) {
783 784
        MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));

785
        if (item->specifiesCoordinate() && !item->standaloneCoordinate()) {
786 787
            foundAltitude = item->param7();
            found = true;
788 789 790
        }
    }

791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816
    if (found) {
        *lastAltitude = foundAltitude;
    }

    return found;
}

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

    for (int i=0; i<_missionItems->count(); i++) {
        MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));

        if ((MAV_CMD)item->command() == MAV_CMD_NAV_WAYPOINT) {
            foundAcceptanceRadius = item->param2();
            found = true;
        }
    }

    if (found) {
        *lastAcceptanceRadius = foundAcceptanceRadius;
    }

    return found;
817
}
818 819 820 821 822 823 824 825 826 827 828 829 830 831

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
832
void MissionController::_addPlannedHomePosition(QmlObjectListModel* missionItems, bool addToCenter)
833 834
{
    MissionItem* homeItem = new MissionItem(_activeVehicle, this);
835
    missionItems->insert(0, homeItem);
836

837 838
    if (missionItems->count() > 1  && addToCenter) {
        MissionItem* item = qobject_cast<MissionItem*>(missionItems->get(1));
839 840 841 842 843 844

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

845 846
        for (int i=2; i<missionItems->count(); i++) {
            item = qobject_cast<MissionItem*>(missionItems->get(i));
847 848 849 850 851 852 853 854 855 856 857 858 859 860 861

            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());
    }
}
862 863 864 865 866 867 868 869 870 871 872 873 874 875

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

        for (int i=0; i<_missionItems->count(); i++) {
            MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
    }
}
876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895

QStringList MissionController::getMobileMissionFiles(void)
{
    QStringList missionFiles;

    QStringList docDirs = QStandardPaths::standardLocations(QStandardPaths::DocumentsLocation);
    if (docDirs.count() <= 0) {
        qWarning() << "No Documents location";
        return QStringList();
    }
    QDir missionDir = docDirs.at(0);

    QFileInfoList missionFileInfoList = missionDir.entryInfoList(QStringList(QStringLiteral("*.mission")),  QDir::Files, QDir::Name);

    foreach (const QFileInfo& missionFileInfo, missionFileInfoList) {
        missionFiles << missionFileInfo.baseName() + ".mission";
    }

    return missionFiles;
}
896 897 898 899 900 901

bool MissionController::syncInProgress(void)
{
    qDebug() << _activeVehicle->missionManager()->inProgress();
    return _activeVehicle->missionManager()->inProgress();
}