MissionController.cc 35 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 50
    , _visualItems(NULL)
    , _complexItems(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
    // We start with an empty mission
77 78 79
    _visualItems = new QmlObjectListModel(this);
    _addPlannedHomePosition(_visualItems, false /* addToCenter */);
    _initAllVisualItems();
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
    if (!_editMode || _missionItemsRequested || _visualItems->count() == 1) {
88 89 90 91 92
        // 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
93

94 95
        QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
        const QList<MissionItem*>& newMissionItems = _activeVehicle->missionManager()->missionItems();
96

97 98 99 100 101 102 103 104 105 106 107 108
        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 */);
109 110
        }

111
        _missionItemsRequested = false;
112

113
        _initAllVisualItems();
114
        emit newItemsFromVehicle();
115 116 117
    }
}

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

122 123 124 125 126 127 128 129
    if (activeVehicle) {
        _missionItemsRequested = true;
        activeVehicle->missionManager()->requestMissionItems();
    }
}

void MissionController::sendMissionItems(void)
{
130 131
    if (_activeVehicle) {
        // Convert to MissionItems so we can send to vehicle
132

133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151
        QList<MissionItem*> missionItems;

        int sequenceNumber = 0;
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
            if (visualItem->isSimpleItem()) {
                MissionItem& missionItem = qobject_cast<SimpleMissionItem*>(visualItem)->missionItem();
                missionItem.setSequenceNumber(sequenceNumber++);
                missionItems.append(&missionItem);
            } else {
                foreach (MissionItem* missionItem, qobject_cast<ComplexMissionItem*>(visualItem)->missionItems()) {
                    missionItem->setSequenceNumber(sequenceNumber++);
                    missionItems.append(missionItem);
                }
            }
        }

        _activeVehicle->missionManager()->writeMissionItems(missionItems);
        _visualItems->setDirty(false);
152 153
    }
}
154

155
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
156
{
157 158
    SimpleMissionItem * newItem = new SimpleMissionItem(_activeVehicle, this);
    newItem->setSequenceNumber(_visualItems->count());
159
    newItem->setCoordinate(coordinate);
160 161 162
    newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
    _initVisualItem(newItem);
    if (_visualItems->count() == 1) {
163 164
        newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
    }
165
    newItem->setDefaultsForCommand();
Don Gagne's avatar
Don Gagne committed
166
    if ((MAV_CMD)newItem->command() == MAV_CMD_NAV_WAYPOINT) {
167 168 169
        double lastValue;

        if (_findLastAcceptanceRadius(&lastValue)) {
170
            newItem->missionItem().setParam2(lastValue);
171 172
        }
        if (_findLastAltitude(&lastValue)) {
173
            newItem->missionItem().setParam7(lastValue);
174
        }
175
    }
176
    _visualItems->insert(i, newItem);
177 178 179

    _recalcAll();

180
    return _visualItems->count() - 1;
181 182
}

183 184
int MissionController::insertComplexMissionItem(QGeoCoordinate coordinate, int i)
{
185 186
    ComplexMissionItem* newItem = new ComplexMissionItem(_activeVehicle, this);
    newItem->setSequenceNumber(_visualItems->count());
187
    newItem->setCoordinate(coordinate);
188
    _initVisualItem(newItem);
189

190 191
    _visualItems->insert(i, newItem);
    _complexItems->append(newItem);
192 193 194

    _recalcAll();

195
    return _visualItems->count() - 1;
196 197
}

198 199
void MissionController::removeMissionItem(int index)
{
200
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
201

202 203 204 205 206 207 208 209 210
    _deinitVisualItem(item);
    if (!item->isSimpleItem()) {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(_complexItems->removeOne(item));
        if (complexItem) {
            complexItem->deleteLater();
        } else {
            qWarning() << "Complex item missing";
        }
    }
211
    item->deleteLater();
212 213 214 215 216

    _recalcAll();

    // Set the new current item

217
    if (index >= _visualItems->count()) {
218 219
        index--;
    }
220 221
    for (int i=0; i<_visualItems->count(); i++) {
        MissionItem* item =  qobject_cast<MissionItem*>(_visualItems->get(i));
222 223
        item->setIsCurrentItem(i == index);
    }
224
    _visualItems->setDirty(true);
225 226
}

227 228
void MissionController::removeAllMissionItems(void)
{
229 230 231 232 233 234
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteListAndContents();
        _visualItems = new QmlObjectListModel(this);
        _addPlannedHomePosition(_visualItems, false /* addToCenter */);
        _initAllVisualItems();
235
    }
236
}
237

238
bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectListModel* missionItems, QString& errorString)
239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271
{
    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;
            }

272
            SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
273
            if (item->load(itemValue.toObject(), errorString)) {
274
                missionItems->append(item);
275 276 277 278 279 280 281
            } else {
                return false;
            }
        }
    }

    if (json.contains(_jsonPlannedHomePositionKey)) {
282
        SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
283 284

        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), errorString)) {
285
            missionItems->insert(0, item);
286 287 288 289
        } else {
            return false;
        }
    } else {
290
        _addPlannedHomePosition(missionItems, true /* addToCenter */);
291 292 293 294 295
    }

    return true;
}

296
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316
{
    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()) {
317
            SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
318 319

            if (item->load(stream)) {
320
                visualItems->append(item);
321 322 323 324 325 326 327 328 329 330
            } 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;
    }

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

334 335 336 337 338
        // 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
339 340
            }
        }
341 342 343
    }

    return true;
344 345
}

346
void MissionController::_loadMissionFromFile(const QString& filename)
347 348 349 350 351 352 353
{
    QString errorString;

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

354
    QmlObjectListModel* newMissionItems = new QmlObjectListModel(this);
355 356 357 358 359 360

    QFile file(filename);

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

364 365 366
        QString firstLine = stream.readLine();
        if (firstLine.contains(QRegExp("QGC.*WPL"))) {
            stream.seek(0);
367
            _loadTextMissionFile(stream, newMissionItems, errorString);
368
        } else {
369
            _loadJsonMissionFile(bytes, newMissionItems, errorString);
370 371
        }
    }
372

373
    if (!errorString.isEmpty()) {
374
        delete newMissionItems;
375
        qgcApp()->showMessage(errorString);
376
        return;
377 378
    }

379 380 381
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteListAndContents();
382
    }
383 384 385
    _visualItems = newMissionItems;
    if (_visualItems->count() == 0) {
        _addPlannedHomePosition(_visualItems, true /* addToCenter */);
386 387
    }

388
    _initAllVisualItems();
389 390
}

391
void MissionController::loadMissionFromFile(void)
392
{
393
#ifndef __mobile__
394 395 396 397 398 399 400 401 402 403 404 405
    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;
406 407 408 409

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

411
    QString missionFilename = filename;
412
    if (!QFileInfo(filename).fileName().contains(".")) {
413
        missionFilename += ".mission";
414 415
    }

416
    QFile file(missionFilename);
417

418
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
419
        qgcApp()->showMessage(file.errorString());
420
    } else {
421 422 423
        QJsonObject missionObject;      // top level json object
        QJsonArray missionItemArray;    // array of mission items
        QString errorString;
424

425 426
        missionObject[_jsonVersionKey] = "1.0";
        missionObject[_jsonGroundStationKey] = "QGroundControl";
427

428 429 430 431 432 433 434 435 436 437 438 439
        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;

440
        // Save planned home position
441
        QJsonObject homePositionObject;
442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457
        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;
        }
        missionObject[_jsonPlannedHomePositionKey] = homePositionObject;

        // Save the remainder of the visual items
        for (int i=1; i<_visualItems->count(); i++) {
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
            if (!visualItem->save(missionObject, missionItemArray, errorString)) {
                qgcApp()->showMessage(errorString);
                return;
            }
458
        }
459
        missionObject["items"] = missionItemArray;
460 461 462

        QJsonDocument saveDoc(missionObject);
        file.write(saveDoc.toJson());
463 464
    }

465
    _visualItems->setDirty(false);
466 467 468 469 470 471 472 473 474 475
}

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
476
    _saveMissionToFile(filename);
477
#endif
478 479
}

480 481 482 483 484 485 486 487
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
488
    _saveMissionToFile(docDirs.at(0) + QDir::separator() + filename);
489 490 491 492 493 494 495 496 497 498 499 500
}

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

501
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
502
{
Don Gagne's avatar
Don Gagne committed
503
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
504
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
505 506 507 508
    bool            distanceOk =    false;

    // Convert to fixed altitudes

509
    qCDebug(MissionControllerLog) << homeAlt
510 511
                                  << currentItem->coordinateHasRelativeAltitude() << currentItem->coordinate().altitude()
                                  << prevItem->exitCoordinateHasRelativeAltitude() << prevItem->exitCoordinate().altitude();
512

513
    distanceOk = true;
514
    if (currentItem->coordinateHasRelativeAltitude()) {
515 516
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
517
    if (prevItem->exitCoordinateHasRelativeAltitude()) {
518
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
519 520 521 522 523
    }

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

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
524 525 526
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
527
    } else {
Don Gagne's avatar
Don Gagne committed
528
        *altDifference = 0.0;
529
        *azimuth = 0.0;
Don Gagne's avatar
Don Gagne committed
530
        *distance = -1.0;   // Signals no values
531 532 533
    }
}

534 535
void MissionController::_recalcWaypointLines(void)
{
536 537 538 539 540 541 542 543 544 545 546
    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();
    double  homeAlt =           homeItem->coordinate().altitude();
547 548 549 550 551 552

    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.
553

554
    // No values for first item
555
    lastCoordinateItem->setAltDifference(0.0);
556
    lastCoordinateItem->setAzimuth(0.0);
557 558
    lastCoordinateItem->setDistance(-1.0);

559 560 561 562 563
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
    double homePositionAltitude = homeItem->coordinate().altitude();
    minAltSeen = maxAltSeen = homeItem->coordinate().altitude();

564 565
    _waypointLines.clear();

Don Gagne's avatar
Don Gagne committed
566
    bool linkBackToHome = false;
567 568
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
569

570 571 572
        // Assume the worst
        item->setAzimuth(0.0);
        item->setDistance(-1.0);
573

574 575 576 577
        // 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) {
Don Gagne's avatar
Don Gagne committed
578 579 580
            linkBackToHome = true;
        }

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

584
            double absoluteAltitude = item->coordinate().altitude();
585
            if (item->coordinateHasRelativeAltitude()) {
586 587 588 589 590
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

591 592 593 594 595 596 597 598 599 600
            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
601
                firstCoordinateItem = false;
602
                if (lastCoordinateItem != homeItem || (showHomePosition && linkBackToHome)) {
603 604 605 606
                    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
607
                    _calcPrevWaypointValues(homeAlt, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
608 609 610 611
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
                    _waypointLines.append(new CoordinateVector(lastCoordinateItem->coordinate(), item->coordinate()));
612
                }
613 614 615 616 617 618 619
                lastCoordinateItem = item;
            }
        }
    }

    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
620 621
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
622 623 624

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
625
            if (item->coordinateHasRelativeAltitude()) {
626 627 628 629 630 631
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
632
            }
633 634
        }
    }
635 636

    emit waypointLinesChanged();
637 638
}

639 640 641
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
642 643 644 645 646 647 648 649 650
    // 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);
651

652 653 654 655 656 657
            if (complexItem) {
                sequenceNumber = complexItem->nextSequenceNumber();
            } else {
                qWarning() << "isSimpleItem == false, yet not ComplexMissionItem";
            }
        }
658 659 660
    }
}

661 662 663
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
664
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
665 666 667

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

668 669
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
670 671 672 673 674 675 676 677 678 679 680

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

681 682
void MissionController::_recalcAll(void)
{
683
    _recalcSequence();
684 685 686 687
    _recalcChildItems();
    _recalcWaypointLines();
}

688
/// Initializes a new set of mission items
689
void MissionController::_initAllVisualItems(void)
690
{
691 692 693 694 695 696 697 698 699
    SimpleMissionItem* homeItem = NULL;

    // Setup home position at index 0

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

Don Gagne's avatar
Don Gagne committed
701
    homeItem->setHomePositionSpecialCase(true);
702
    homeItem->setShowHomePosition(_editMode);
703 704
    homeItem->missionItem().setCommand(MAV_CMD_NAV_WAYPOINT);
    homeItem->missionItem().setFrame(MAV_FRAME_GLOBAL);
705 706 707 708 709
    homeItem->setIsCurrentItem(true);

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

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

714
    QmlObjectListModel* newComplexItems = new QmlObjectListModel(this);
715 716 717
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
718

719 720 721
        // Set up complex item list
        if (!item->isSimpleItem()) {
            ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);
722

723 724 725 726 727
            if (complexItem) {
                newComplexItems->append(item);
            } else {
                qWarning() << "isSimpleItem == false, but not ComplexMissionItem";
            }
728
        }
729 730
    }

731 732 733 734
    if (_complexItems) {
        _complexItems->deleteLater();
    }
    _complexItems = newComplexItems;
735

736
    _recalcAll();
737

738 739
    emit visualItemsChanged();
    emit complexVisualItemsChanged();
740

741
    _visualItems->setDirty(false);
742

743
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_dirtyChanged);
744 745
}

746
void MissionController::_deinitAllVisualItems(void)
747
{
748 749
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
750 751
    }

752
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_dirtyChanged);
753 754
}

755
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
756
{
757 758 759 760 761
    _visualItems->setDirty(false);

    connect(visualItem, &VisualMissionItem::coordinateChanged,                          this, &MissionController::_itemCoordinateChanged);
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
762

763 764 765 766 767 768 769 770 771 772
    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";
        }
    }
773 774
}

775
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
776
{
777 778
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
779 780 781 782 783 784 785 786
}

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

787
void MissionController::_itemCommandChanged(void)
788
{
789 790
    _recalcChildItems();
    _recalcWaypointLines();
791 792 793 794
}

void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
{
795 796
    qCDebug(MissionControllerLog) << "_activeVehicleChanged activeVehicle" << activeVehicle;

797 798
    if (_activeVehicle) {
        MissionManager* missionManager = _activeVehicle->missionManager();
799

800
        disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailableFromVehicle);
801
        disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
802
        disconnect(missionManager, &MissionManager::currentItemChanged,         this, &MissionController::_currentMissionItemChanged);
803 804
        disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged,      this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
805
        _activeVehicle = NULL;
Don Gagne's avatar
Don Gagne committed
806 807
    }

808
    _activeVehicle = activeVehicle;
809

810 811
    if (_activeVehicle) {
        MissionManager* missionManager = activeVehicle->missionManager();
812

813
        connect(missionManager, &MissionManager::newMissionItemsAvailable,  this, &MissionController::_newMissionItemsAvailableFromVehicle);
814
        connect(missionManager, &MissionManager::inProgressChanged,         this, &MissionController::_inProgressChanged);
815
        connect(missionManager, &MissionManager::currentItemChanged,        this, &MissionController::_currentMissionItemChanged);
816 817 818
        connect(_activeVehicle, &Vehicle::homePositionAvailableChanged,     this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);

819 820 821
        if (!_editMode) {
            removeAllMissionItems();
        }
822 823 824 825

        _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
        _activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
    }
826 827 828

    // Whenever vehicle changes we need to update syncInProgress
    emit syncInProgressChanged(syncInProgress());
829 830 831 832
}

void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
833 834 835 836 837 838 839 840 841
    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";
        }
842
    }
843 844 845 846
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
847 848
    if (!_editMode && _visualItems) {
        qobject_cast<VisualMissionItem*>(_visualItems->get(0))->setCoordinate(homePosition);
849 850
        _recalcWaypointLines();
    }
851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870
}

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) {
871
        Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
872 873 874 875 876 877 878 879 880 881 882 883 884 885 886

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

void MissionController::_autoSyncSend(void)
{
    qDebug() << "Auto-syncing with vehicle";
    _queuedSend = false;
887
    if (_visualItems) {
888
        sendMissionItems();
889
        _visualItems->setDirty(false);
890 891
    }
}
892

893
void MissionController::_inProgressChanged(bool inProgress)
894
{
895
    emit syncInProgressChanged(inProgress);
896 897 898 899
    if (!inProgress && _queuedSend) {
        _autoSyncSend();
    }
}
900

901
bool MissionController::_findLastAltitude(double* lastAltitude)
902
{
903 904
    bool found = false;
    double foundAltitude;
905

906
    // Don't use home position
907 908
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
909

910 911
        if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
            foundAltitude = item->exitCoordinate().altitude();
912
            found = true;
913 914 915
        }
    }

916 917 918 919 920 921 922 923 924 925 926 927
    if (found) {
        *lastAltitude = foundAltitude;
    }

    return found;
}

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

928 929
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
930

931 932 933 934 935 936 937 938 939 940 941
        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";
            }
942 943 944 945 946 947 948 949
        }
    }

    if (found) {
        *lastAcceptanceRadius = foundAcceptanceRadius;
    }

    return found;
950
}
951 952 953 954 955 956 957 958 959 960 961 962 963 964

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
965
void MissionController::_addPlannedHomePosition(QmlObjectListModel* visualItems, bool addToCenter)
966
{
967 968
    SimpleMissionItem* homeItem = new SimpleMissionItem(_activeVehicle, this);
    visualItems->insert(0, homeItem);
969

970 971
    if (visualItems->count() > 1  && addToCenter) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(visualItems->get(1));
972 973 974 975 976 977

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

978 979
        for (int i=2; i<visualItems->count(); i++) {
            item = qobject_cast<VisualMissionItem*>(visualItems->get(i));
980 981 982 983 984 985 986 987 988 989 990 991 992 993 994

            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());
    }
}
995 996 997 998 999 1000 1001 1002

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

1003 1004
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1005 1006 1007 1008
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
    }
}
1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028

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;
}
1029 1030 1031

bool MissionController::syncInProgress(void)
{
1032 1033 1034 1035 1036
    if (_activeVehicle) {
        return _activeVehicle->missionManager()->inProgress();
    } else {
        return false;
    }
1037
}