MissionController.cc 30.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
#include "SimpleMissionItem.h"
#include "ComplexMissionItem.h"
32

33 34 35 36
#ifndef __mobile__
#include "QGCFileDialog.h"
#endif

37 38
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

39 40 41 42 43 44
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";
45 46 47

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

}

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

63 64 65 66
}

void MissionController::start(bool editMode)
{
67 68
    qCDebug(MissionControllerLog) << "start editMode" << editMode;

69 70
    _editMode = editMode;

71
    MultiVehicleManager* multiVehicleMgr = qgcApp()->toolbox()->multiVehicleManager();
72

73
    connect(multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &MissionController::_activeVehicleChanged);
74
    _activeVehicleChanged(multiVehicleMgr->activeVehicle());
75

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

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

87 88 89 90 91 92 93 94
    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();
95

96 97
        _missionItems = _activeVehicle->missionManager()->copyMissionItems();
        qCDebug(MissionControllerLog) << "loading from vehicle count"<< _missionItems->count();
98

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

103
        _missionItemsRequested = false;
104

105 106
        _initAllMissionItems();
        emit newItemsFromVehicle();
107 108 109
    }
}

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

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

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

124 125 126 127 128
    if (activeVehicle) {
        activeVehicle->missionManager()->writeMissionItems(*_missionItems);
        _missionItems->setDirty(false);
    }
}
129

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

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

    _recalcAll();

    return _missionItems->count() - 1;
}

158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173
int MissionController::insertComplexMissionItem(QGeoCoordinate coordinate, int i)
{
    ComplexMissionItem * newItem = new ComplexMissionItem(_activeVehicle, this);
    newItem->setSequenceNumber(_missionItems->count());
    newItem->setCoordinate(coordinate);
    newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
    _initMissionItem(newItem);

    _missionItems->insert(i, newItem);
    _complexMissionItems->append(newItem);

    _recalcAll();

    return _missionItems->count() - 1;
}

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

    _deinitMissionItem(item);
179
    item->deleteLater();
180 181 182 183 184 185 186 187 188 189 190 191

    _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);
    }
192
    _missionItems->setDirty(true);
193 194
}

195 196 197
void MissionController::removeAllMissionItems(void)
{
    if (_missionItems) {
198 199 200 201 202
        QmlObjectListModel* oldItems = _missionItems;
        _missionItems = new QmlObjectListModel(this);
        _addPlannedHomePosition(_missionItems, false /* addToCenter */);
        _initAllMissionItems();
        oldItems->deleteLater();
203
    }
204
}
205

206
bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectListModel* missionItems, QString& errorString)
207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239
{
    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;
            }

240
            MissionItem* item = new SimpleMissionItem(_activeVehicle, this);
241
            if (item->load(itemValue.toObject(), errorString)) {
242
                missionItems->append(item);
243 244 245 246 247 248 249
            } else {
                return false;
            }
        }
    }

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

        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), errorString)) {
253
            missionItems->insert(0, item);
254 255 256 257
        } else {
            return false;
        }
    } else {
258
        _addPlannedHomePosition(missionItems, true /* addToCenter */);
259 260 261 262 263
    }

    return true;
}

264
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* missionItems, QString& errorString)
265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284
{
    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()) {
285
            MissionItem* item = new SimpleMissionItem(_activeVehicle, this);
286 287

            if (item->load(stream)) {
288
                missionItems->append(item);
289 290 291 292 293 294 295 296 297 298
            } 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;
    }

299 300
    if (addPlannedHomePosition || missionItems->count() == 0) {
        _addPlannedHomePosition(missionItems, true /* addToCenter */);
Don Gagne's avatar
Don Gagne committed
301 302

        // Update sequence numbers in DO_JUMP commands to take into account added home position
303 304
        for (int i=1; i<missionItems->count(); i++) {
            MissionItem* item = qobject_cast<MissionItem*>(missionItems->get(i));
Don Gagne's avatar
Don Gagne committed
305 306 307 308 309
            if (item->command() == MavlinkQmlSingleton::MAV_CMD_DO_JUMP) {
                // Home is in position 0
                item->setParam1((int)item->param1() + 1);
            }
        }
310 311 312
    }

    return true;
313 314
}

315
void MissionController::_loadMissionFromFile(const QString& filename)
316 317 318 319 320 321 322
{
    QString errorString;

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

323
    QmlObjectListModel* newMissionItems = new QmlObjectListModel(this);
324 325 326 327 328 329

    QFile file(filename);

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

333 334 335
        QString firstLine = stream.readLine();
        if (firstLine.contains(QRegExp("QGC.*WPL"))) {
            stream.seek(0);
336
            _loadTextMissionFile(stream, newMissionItems, errorString);
337
        } else {
338
            _loadJsonMissionFile(bytes, newMissionItems, errorString);
339 340
        }
    }
341

342
    if (!errorString.isEmpty()) {
343
        delete newMissionItems;
344
        qgcApp()->showMessage(errorString);
345
        return;
346 347
    }

348 349 350 351 352
    if (_missionItems) {
        _deinitAllMissionItems();
        _missionItems->deleteLater();
    }
    _missionItems = newMissionItems;
353
    if (_missionItems->count() == 0) {
354
        _addPlannedHomePosition(_missionItems, true /* addToCenter */);
355 356
    }

357
    _initAllMissionItems();
358 359
}

360
void MissionController::loadMissionFromFile(void)
361
{
362
#ifndef __mobile__
363 364 365 366 367 368 369 370 371 372 373 374
    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;
375 376 377 378

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

380
    QString missionFilename = filename;
381
    if (!QFileInfo(filename).fileName().contains(".")) {
382
        missionFilename += ".mission";
383 384
    }

385
    QFile file(missionFilename);
386

387
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
388
        qgcApp()->showMessage(file.errorString());
389
    } else {
390
        QJsonObject missionObject;
391

392 393
        missionObject[_jsonVersionKey] = "1.0";
        missionObject[_jsonGroundStationKey] = "QGroundControl";
394

395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411
        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;
412
        for (int i=1; i<_missionItems->count(); i++) {
413 414 415
            QJsonObject itemObject;
            qobject_cast<MissionItem*>(_missionItems->get(i))->save(itemObject);
            itemArray.append(itemObject);
416
        }
417 418 419 420
        missionObject["items"] = itemArray;

        QJsonDocument saveDoc(missionObject);
        file.write(saveDoc.toJson());
421 422 423
    }

    _missionItems->setDirty(false);
424 425 426 427 428 429 430 431 432 433
}

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
434
    _saveMissionToFile(filename);
435
#endif
436 437
}

438 439 440 441 442 443 444 445
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
446
    _saveMissionToFile(docDirs.at(0) + QDir::separator() + filename);
447 448 449 450 451 452 453 454 455 456 457 458
}

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

459
void MissionController::_calcPrevWaypointValues(double homeAlt, MissionItem* currentItem, MissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
460
{
Don Gagne's avatar
Don Gagne committed
461 462
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  prevCoord =     prevItem->coordinate();
463 464 465 466
    bool            distanceOk =    false;

    // Convert to fixed altitudes

467
    qCDebug(MissionControllerLog) << homeAlt
Don Gagne's avatar
Don Gagne committed
468 469
                                  << currentItem->relativeAltitude() << currentItem->coordinate().altitude()
                                  << prevItem->relativeAltitude() << prevItem->coordinate().altitude();
470

471 472 473 474 475 476
    distanceOk = true;
    if (currentItem->relativeAltitude()) {
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
    if (prevItem->relativeAltitude()) {
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
477 478 479 480 481
    }

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

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
482 483 484
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
485
    } else {
Don Gagne's avatar
Don Gagne committed
486
        *altDifference = 0.0;
487
        *azimuth = 0.0;
Don Gagne's avatar
Don Gagne committed
488
        *distance = -1.0;   // Signals no values
489 490 491
    }
}

492 493 494
void MissionController::_recalcWaypointLines(void)
{
    MissionItem*    lastCoordinateItem =    qobject_cast<MissionItem*>(_missionItems->get(0));
495
    MissionItem*    homeItem =              lastCoordinateItem;
496
    bool            firstCoordinateItem =   true;
497
    bool            showHomePosition =      homeItem->showHomePosition();
498 499 500 501 502 503 504
    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.
505

506
    // No values for first item
507
    lastCoordinateItem->setAltDifference(0.0);
508
    lastCoordinateItem->setAzimuth(0.0);
509 510
    lastCoordinateItem->setDistance(-1.0);

511 512 513 514 515
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
    double homePositionAltitude = homeItem->coordinate().altitude();
    minAltSeen = maxAltSeen = homeItem->coordinate().altitude();

516 517
    _waypointLines.clear();

Don Gagne's avatar
Don Gagne committed
518
    bool linkBackToHome = false;
519 520 521
    for (int i=1; i<_missionItems->count(); i++) {
        MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));

522 523 524
        // Assume the worst
        item->setAzimuth(0.0);
        item->setDistance(-1.0);
525

Don Gagne's avatar
Don Gagne committed
526 527 528 529
        if (firstCoordinateItem && item->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) {
            linkBackToHome = true;
        }

530 531
        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
532
            if (item->relativeAltitude()) {
533 534 535 536 537 538
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

            if (!item->standaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
539 540
                firstCoordinateItem = false;
                if (!lastCoordinateItem->homePosition() || (showHomePosition && linkBackToHome)) {
541 542 543 544
                    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
545
                    _calcPrevWaypointValues(homeAlt, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
546 547 548 549
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
                    _waypointLines.append(new CoordinateVector(lastCoordinateItem->coordinate(), item->coordinate()));
550
                }
551 552 553 554 555 556 557 558 559 560 561 562
                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();
563
            if (item->relativeAltitude()) {
564 565 566 567 568 569
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
570
            }
571 572
        }
    }
573 574

    emit waypointLinesChanged();
575 576
}

577 578 579 580 581 582 583 584 585 586 587
// 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);
    }
}

588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607
// 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);
        }
    }
}

608 609
void MissionController::_recalcAll(void)
{
610
    _recalcSequence();
611 612 613 614
    _recalcChildItems();
    _recalcWaypointLines();
}

615
/// Initializes a new set of mission items
616 617
void MissionController::_initAllMissionItems(void)
{
618 619
    MissionItem* homeItem = NULL;

620
    homeItem = qobject_cast<MissionItem*>(_missionItems->get(0));
Don Gagne's avatar
Don Gagne committed
621
    homeItem->setHomePositionSpecialCase(true);
622
    homeItem->setShowHomePosition(_editMode);
Don Gagne's avatar
Don Gagne committed
623 624
    homeItem->setCommand(MAV_CMD_NAV_WAYPOINT);
    homeItem->setFrame(MAV_FRAME_GLOBAL);
625 626 627 628 629
    homeItem->setIsCurrentItem(true);

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

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

634 635
    QmlObjectListModel* newComplexItems = new QmlObjectListModel(this);

636
    for (int i=0; i<_missionItems->count(); i++) {
637 638 639 640 641 642
        MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));

        if (!item->simpleItem()) {
            newComplexItems->append(item);
        }
        _initMissionItem(item);
643 644
    }

645 646 647
    delete _complexMissionItems;
    _complexMissionItems = newComplexItems;

648
    _recalcAll();
649

650
    emit missionItemsChanged();
651
    emit complexMissionItemsChanged();
652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672

    _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);
673
    connect(item, &MissionItem::frameChanged,       this, &MissionController::_itemFrameChanged);
674 675 676 677 678 679
}

void MissionController::_deinitMissionItem(MissionItem* item)
{
    disconnect(item, &MissionItem::commandChanged,     this, &MissionController::_itemCommandChanged);
    disconnect(item, &MissionItem::coordinateChanged,  this, &MissionController::_itemCoordinateChanged);
680
    disconnect(item, &MissionItem::frameChanged,       this, &MissionController::_itemFrameChanged);
681 682 683 684 685 686 687 688
}

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

689 690 691 692 693 694
void MissionController::_itemFrameChanged(int frame)
{
    Q_UNUSED(frame);
    _recalcWaypointLines();
}

695 696 697 698 699
void MissionController::_itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command)
{
    Q_UNUSED(command);;
    _recalcChildItems();
    _recalcWaypointLines();
700 701 702 703
}

void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
{
704 705
    qCDebug(MissionControllerLog) << "_activeVehicleChanged activeVehicle" << activeVehicle;

706 707
    if (_activeVehicle) {
        MissionManager* missionManager = _activeVehicle->missionManager();
708

709
        disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailableFromVehicle);
710
        disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
711
        disconnect(missionManager, &MissionManager::currentItemChanged,         this, &MissionController::_currentMissionItemChanged);
712 713
        disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged,      this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
714
        _activeVehicle = NULL;
Don Gagne's avatar
Don Gagne committed
715 716
    }

717
    _activeVehicle = activeVehicle;
718

719 720
    if (_activeVehicle) {
        MissionManager* missionManager = activeVehicle->missionManager();
721

722
        connect(missionManager, &MissionManager::newMissionItemsAvailable,  this, &MissionController::_newMissionItemsAvailableFromVehicle);
723
        connect(missionManager, &MissionManager::inProgressChanged,         this, &MissionController::_inProgressChanged);
724
        connect(missionManager, &MissionManager::currentItemChanged,        this, &MissionController::_currentMissionItemChanged);
725 726 727
        connect(_activeVehicle, &Vehicle::homePositionAvailableChanged,     this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);

728 729 730
        if (!_editMode) {
            removeAllMissionItems();
        }
731 732 733 734 735 736 737 738

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

void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
739 740 741 742
    if (!_editMode && _missionItems) {
        qobject_cast<MissionItem*>(_missionItems->get(0))->setShowHomePosition(homePositionAvailable);
        _recalcWaypointLines();
    }
743 744 745 746
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
747 748 749 750
    if (!_editMode && _missionItems) {
        qobject_cast<MissionItem*>(_missionItems->get(0))->setCoordinate(homePosition);
        _recalcWaypointLines();
    }
751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770
}

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) {
771
        Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789

        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);
790 791
    }
}
792

793
void MissionController::_inProgressChanged(bool inProgress)
794
{
795
    emit syncInProgressChanged(inProgress);
796 797 798 799
    if (!inProgress && _queuedSend) {
        _autoSyncSend();
    }
}
800

801 802 803
QmlObjectListModel* MissionController::missionItems(void)
{
    return _missionItems;
804
}
805

806 807 808 809 810
QmlObjectListModel* MissionController::complexMissionItems(void)
{
    return _complexMissionItems;
}

811
bool MissionController::_findLastAltitude(double* lastAltitude)
812
{
813 814
    bool found = false;
    double foundAltitude;
815

816 817
    // Don't use home position
    for (int i=1; i<_missionItems->count(); i++) {
818 819
        MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));

820
        if (item->specifiesCoordinate() && !item->standaloneCoordinate()) {
821 822
            foundAltitude = item->param7();
            found = true;
823 824 825
        }
    }

826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851
    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;
852
}
853 854 855 856 857 858 859 860 861 862 863 864 865 866

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
867
void MissionController::_addPlannedHomePosition(QmlObjectListModel* missionItems, bool addToCenter)
868
{
869
    MissionItem* homeItem = new SimpleMissionItem(_activeVehicle, this);
870
    missionItems->insert(0, homeItem);
871

872 873
    if (missionItems->count() > 1  && addToCenter) {
        MissionItem* item = qobject_cast<MissionItem*>(missionItems->get(1));
874 875 876 877 878 879

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

880 881
        for (int i=2; i<missionItems->count(); i++) {
            item = qobject_cast<MissionItem*>(missionItems->get(i));
882 883 884 885 886 887 888 889 890 891 892 893 894 895 896

            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());
    }
}
897 898 899 900 901 902 903 904 905 906 907 908 909 910

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);
        }
    }
}
911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930

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;
}
931 932 933 934 935 936

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