MissionController.cc 36.5 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
#include "JsonHelper.h"
33

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

38 39
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

40 41
const char* MissionController::jsonSimpleItemsKey = "items";

42 43 44 45
const char* MissionController::_settingsGroup =                 "MissionController";
const char* MissionController::_jsonVersionKey =                "version";
const char* MissionController::_jsonGroundStationKey =          "groundStation";
const char* MissionController::_jsonMavAutopilotKey =           "MAV_AUTOPILOT";
46
const char* MissionController::_jsonComplexItemsKey =           "complexItems";
47
const char* MissionController::_jsonPlannedHomePositionKey =    "plannedHomePosition";
48 49 50

MissionController::MissionController(QObject *parent)
    : QObject(parent)
51
    , _editMode(false)
52 53
    , _visualItems(NULL)
    , _complexItems(NULL)
54
    , _activeVehicle(NULL)
55
    , _autoSync(false)
56
    , _firstItemsFromVehicle(false)
57 58
    , _missionItemsRequested(false)
    , _queuedSend(false)
59
{
60 61 62 63 64

}

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

66 67 68 69
}

void MissionController::start(bool editMode)
{
70 71
    qCDebug(MissionControllerLog) << "start editMode" << editMode;

72 73
    _editMode = editMode;

74
    MultiVehicleManager* multiVehicleMgr = qgcApp()->toolbox()->multiVehicleManager();
75

76
    connect(multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &MissionController::_activeVehicleChanged);
77
    _activeVehicleChanged(multiVehicleMgr->activeVehicle());
78

79
    // We start with an empty mission
80 81 82
    _visualItems = new QmlObjectListModel(this);
    _addPlannedHomePosition(_visualItems, false /* addToCenter */);
    _initAllVisualItems();
83 84
}

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

90
    if (!_editMode || _missionItemsRequested || _visualItems->count() == 1) {
91 92 93 94 95
        // 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
96

97 98
        QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
        const QList<MissionItem*>& newMissionItems = _activeVehicle->missionManager()->missionItems();
99

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

114
        _missionItemsRequested = false;
115

116
        _initAllVisualItems();
117
        emit newItemsFromVehicle();
118 119 120
    }
}

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

125 126 127 128 129 130 131 132
    if (activeVehicle) {
        _missionItemsRequested = true;
        activeVehicle->missionManager()->requestMissionItems();
    }
}

void MissionController::sendMissionItems(void)
{
133 134
    if (_activeVehicle) {
        // Convert to MissionItems so we can send to vehicle
135

136 137 138 139 140 141 142 143 144 145
        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 {
146 147 148
                ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
                for (int j=0; j<complexItem->missionItems().count(); j++) {
                    MissionItem* missionItem = complexItem->missionItems()[i];
149 150 151 152 153 154 155 156
                    missionItem->setSequenceNumber(sequenceNumber++);
                    missionItems.append(missionItem);
                }
            }
        }

        _activeVehicle->missionManager()->writeMissionItems(missionItems);
        _visualItems->setDirty(false);
157 158
    }
}
159

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

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

    _recalcAll();

185
    return _visualItems->count() - 1;
186 187
}

188 189
int MissionController::insertComplexMissionItem(QGeoCoordinate coordinate, int i)
{
190 191
    ComplexMissionItem* newItem = new ComplexMissionItem(_activeVehicle, this);
    newItem->setSequenceNumber(_visualItems->count());
192
    newItem->setCoordinate(coordinate);
193
    _initVisualItem(newItem);
194

195 196
    _visualItems->insert(i, newItem);
    _complexItems->append(newItem);
197 198 199

    _recalcAll();

200
    return _visualItems->count() - 1;
201 202
}

203 204
void MissionController::removeMissionItem(int index)
{
205
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
206

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

    _recalcAll();

    // Set the new current item

222
    if (index >= _visualItems->count()) {
223 224
        index--;
    }
225 226
    for (int i=0; i<_visualItems->count(); i++) {
        MissionItem* item =  qobject_cast<MissionItem*>(_visualItems->get(i));
227 228
        item->setIsCurrentItem(i == index);
    }
229
    _visualItems->setDirty(true);
230 231
}

232 233
void MissionController::removeAllMissionItems(void)
{
234 235 236 237 238 239
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteListAndContents();
        _visualItems = new QmlObjectListModel(this);
        _addPlannedHomePosition(_visualItems, false /* addToCenter */);
        _initAllVisualItems();
240
    }
241
}
242

243
bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectListModel* missionItems, QString& errorString)
244 245 246 247 248 249 250 251 252 253 254
{
    QJsonParseError jsonParseError;
    QJsonDocument   jsonDoc(QJsonDocument::fromJson(bytes, &jsonParseError));

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

    QJsonObject json = jsonDoc.object();

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

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

    // Version check
272 273 274 275 276
    if (json[_jsonVersionKey].toString() != "1.0") {
        errorString = QStringLiteral("QGroundControl does not support this file version");
        return false;
    }

277 278 279 280 281 282 283 284 285 286 287 288 289 290 291
    // Simple items
    if (json.contains(jsonSimpleItemsKey)) {
        QJsonArray itemArray(json[jsonSimpleItemsKey].toArray());
        foreach (const QJsonValue& itemValue, itemArray) {
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

            SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
            if (item->load(itemValue.toObject(), errorString)) {
                missionItems->append(item);
            } else {
                return false;
            }
292
        }
293
    }
294

295 296 297
    // Complex items
    if (json.contains(_jsonComplexItemsKey)) {
        QJsonArray itemArray(json[_jsonComplexItemsKey].toArray());
298 299 300 301 302 303
        foreach (const QJsonValue& itemValue, itemArray) {
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

304
            ComplexMissionItem* item = new ComplexMissionItem(_activeVehicle, this);
305
            if (item->load(itemValue.toObject(), errorString)) {
306
                missionItems->append(item);
307 308 309 310 311 312 313
            } else {
                return false;
            }
        }
    }

    if (json.contains(_jsonPlannedHomePositionKey)) {
314
        SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
315 316

        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), errorString)) {
317
            missionItems->insert(0, item);
318 319 320 321
        } else {
            return false;
        }
    } else {
322
        _addPlannedHomePosition(missionItems, true /* addToCenter */);
323 324 325 326 327
    }

    return true;
}

328
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348
{
    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()) {
349
            SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
350 351

            if (item->load(stream)) {
352
                visualItems->append(item);
353 354 355 356 357 358 359 360 361 362
            } 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;
    }

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

366 367 368 369 370
        // 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
371 372
            }
        }
373 374 375
    }

    return true;
376 377
}

378
void MissionController::_loadMissionFromFile(const QString& filename)
379 380 381 382 383 384 385
{
    QString errorString;

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

386
    QmlObjectListModel* newMissionItems = new QmlObjectListModel(this);
387 388 389 390 391 392

    QFile file(filename);

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

396 397 398
        QString firstLine = stream.readLine();
        if (firstLine.contains(QRegExp("QGC.*WPL"))) {
            stream.seek(0);
399
            _loadTextMissionFile(stream, newMissionItems, errorString);
400
        } else {
401
            _loadJsonMissionFile(bytes, newMissionItems, errorString);
402 403
        }
    }
404

405
    if (!errorString.isEmpty()) {
406
        delete newMissionItems;
407
        qgcApp()->showMessage(errorString);
408
        return;
409 410
    }

411 412 413
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteListAndContents();
414
    }
415 416 417
    _visualItems = newMissionItems;
    if (_visualItems->count() == 0) {
        _addPlannedHomePosition(_visualItems, true /* addToCenter */);
418 419
    }

420
    _initAllVisualItems();
421 422
}

423
void MissionController::loadMissionFromFile(void)
424
{
425
#ifndef __mobile__
426 427 428 429 430 431 432 433 434 435 436 437
    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;
438 439 440 441

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

443
    QString missionFilename = filename;
444
    if (!QFileInfo(filename).fileName().contains(".")) {
445
        missionFilename += ".mission";
446 447
    }

448
    QFile file(missionFilename);
449

450
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
451
        qgcApp()->showMessage(file.errorString());
452
    } else {
453 454 455
        QJsonObject missionFileObject;      // top level json object
        QJsonArray  simpleItemsObject;
        QJsonArray  complexItemsObject;
456

457 458
        missionFileObject[_jsonVersionKey] =        "1.0";
        missionFileObject[_jsonGroundStationKey] =  "QGroundControl";
459

460 461 462 463 464 465 466 467 468 469
        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();
        }
470
        missionFileObject[_jsonMavAutopilotKey] = firmwareType;
471

472
        // Save planned home position
473
        QJsonObject homePositionObject;
474 475 476 477 478 479 480
        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;
        }
481
        missionFileObject[_jsonPlannedHomePositionKey] = homePositionObject;
482

483
        // Save the visual items
484
        for (int i=1; i<_visualItems->count(); i++) {
485 486
            QJsonObject itemObject;

487
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
488 489 490 491 492 493
            visualItem->save(itemObject);

            if (visualItem->isSimpleItem()) {
                simpleItemsObject.append(itemObject);
            } else {
                complexItemsObject.append(itemObject);
494
            }
495
        }
496

497 498 499 500
        missionFileObject[jsonSimpleItemsKey] = simpleItemsObject;
        missionFileObject[_jsonComplexItemsKey] = complexItemsObject;

        QJsonDocument saveDoc(missionFileObject);
501
        file.write(saveDoc.toJson());
502 503
    }

504
    _visualItems->setDirty(false);
505 506 507 508 509 510 511 512 513 514
}

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
515
    _saveMissionToFile(filename);
516
#endif
517 518
}

519 520 521 522 523 524 525 526
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
527
    _saveMissionToFile(docDirs.at(0) + QDir::separator() + filename);
528 529 530 531 532 533 534 535 536 537 538 539
}

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

540
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
541
{
Don Gagne's avatar
Don Gagne committed
542
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
543
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
544 545 546 547
    bool            distanceOk =    false;

    // Convert to fixed altitudes

548
    qCDebug(MissionControllerLog) << homeAlt
549 550
                                  << currentItem->coordinateHasRelativeAltitude() << currentItem->coordinate().altitude()
                                  << prevItem->exitCoordinateHasRelativeAltitude() << prevItem->exitCoordinate().altitude();
551

552
    distanceOk = true;
553
    if (currentItem->coordinateHasRelativeAltitude()) {
554 555
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
556
    if (prevItem->exitCoordinateHasRelativeAltitude()) {
557
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
558 559 560 561 562
    }

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

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
563 564 565
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
566
    } else {
Don Gagne's avatar
Don Gagne committed
567
        *altDifference = 0.0;
568
        *azimuth = 0.0;
Don Gagne's avatar
Don Gagne committed
569
        *distance = -1.0;   // Signals no values
570 571 572
    }
}

573 574
void MissionController::_recalcWaypointLines(void)
{
575 576 577 578 579 580 581 582 583 584 585
    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();
586 587 588 589 590 591

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

593
    // No values for first item
594
    lastCoordinateItem->setAltDifference(0.0);
595
    lastCoordinateItem->setAzimuth(0.0);
596 597
    lastCoordinateItem->setDistance(-1.0);

598 599 600 601 602
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
    double homePositionAltitude = homeItem->coordinate().altitude();
    minAltSeen = maxAltSeen = homeItem->coordinate().altitude();

603 604
    _waypointLines.clear();

Don Gagne's avatar
Don Gagne committed
605
    bool linkBackToHome = false;
606 607
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
608

609 610 611
        // Assume the worst
        item->setAzimuth(0.0);
        item->setDistance(-1.0);
612

613 614 615 616
        // 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
617 618 619
            linkBackToHome = true;
        }

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

623
            double absoluteAltitude = item->coordinate().altitude();
624
            if (item->coordinateHasRelativeAltitude()) {
625 626 627 628 629
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

630 631 632 633 634 635 636 637 638 639
            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
640
                firstCoordinateItem = false;
641
                if (lastCoordinateItem != homeItem || (showHomePosition && linkBackToHome)) {
642 643 644 645
                    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
646
                    _calcPrevWaypointValues(homeAlt, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
647 648 649 650
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
                    _waypointLines.append(new CoordinateVector(lastCoordinateItem->coordinate(), item->coordinate()));
651
                }
652 653 654 655 656 657 658
                lastCoordinateItem = item;
            }
        }
    }

    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
659 660
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
661 662 663

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
664
            if (item->coordinateHasRelativeAltitude()) {
665 666 667 668 669 670
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
671
            }
672 673
        }
    }
674 675

    emit waypointLinesChanged();
676 677
}

678 679 680
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
681 682 683 684 685 686 687 688 689
    // 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);
690

691 692 693 694 695 696
            if (complexItem) {
                sequenceNumber = complexItem->nextSequenceNumber();
            } else {
                qWarning() << "isSimpleItem == false, yet not ComplexMissionItem";
            }
        }
697 698 699
    }
}

700 701 702
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
703
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
704 705 706

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

707 708
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
709 710 711 712 713 714 715 716 717 718 719

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

720 721
void MissionController::_recalcAll(void)
{
722
    _recalcSequence();
723 724 725 726
    _recalcChildItems();
    _recalcWaypointLines();
}

727
/// Initializes a new set of mission items
728
void MissionController::_initAllVisualItems(void)
729
{
730 731 732 733 734 735 736 737 738
    SimpleMissionItem* homeItem = NULL;

    // Setup home position at index 0

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

Don Gagne's avatar
Don Gagne committed
740
    homeItem->setHomePositionSpecialCase(true);
741
    homeItem->setShowHomePosition(_editMode);
742 743
    homeItem->missionItem().setCommand(MAV_CMD_NAV_WAYPOINT);
    homeItem->missionItem().setFrame(MAV_FRAME_GLOBAL);
744 745 746 747 748
    homeItem->setIsCurrentItem(true);

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

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

753
    QmlObjectListModel* newComplexItems = new QmlObjectListModel(this);
754 755 756
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
757

758 759 760
        // Set up complex item list
        if (!item->isSimpleItem()) {
            ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);
761

762 763 764 765 766
            if (complexItem) {
                newComplexItems->append(item);
            } else {
                qWarning() << "isSimpleItem == false, but not ComplexMissionItem";
            }
767
        }
768 769
    }

770 771 772 773
    if (_complexItems) {
        _complexItems->deleteLater();
    }
    _complexItems = newComplexItems;
774

775
    _recalcAll();
776

777 778
    emit visualItemsChanged();
    emit complexVisualItemsChanged();
779

780
    _visualItems->setDirty(false);
781

782
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_dirtyChanged);
783 784
}

785
void MissionController::_deinitAllVisualItems(void)
786
{
787 788
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
789 790
    }

791
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_dirtyChanged);
792 793
}

794
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
795
{
796 797 798 799 800
    _visualItems->setDirty(false);

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

802 803 804 805 806 807 808 809 810 811
    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";
        }
    }
812 813
}

814
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
815
{
816 817
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
818 819 820 821 822 823 824 825
}

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

826
void MissionController::_itemCommandChanged(void)
827
{
828 829
    _recalcChildItems();
    _recalcWaypointLines();
830 831 832 833
}

void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
{
834 835
    qCDebug(MissionControllerLog) << "_activeVehicleChanged activeVehicle" << activeVehicle;

836 837
    if (_activeVehicle) {
        MissionManager* missionManager = _activeVehicle->missionManager();
838

839
        disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailableFromVehicle);
840
        disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
841
        disconnect(missionManager, &MissionManager::currentItemChanged,         this, &MissionController::_currentMissionItemChanged);
842 843
        disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged,      this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
844
        _activeVehicle = NULL;
Don Gagne's avatar
Don Gagne committed
845 846
    }

847
    _activeVehicle = activeVehicle;
848

849 850
    if (_activeVehicle) {
        MissionManager* missionManager = activeVehicle->missionManager();
851

852
        connect(missionManager, &MissionManager::newMissionItemsAvailable,  this, &MissionController::_newMissionItemsAvailableFromVehicle);
853
        connect(missionManager, &MissionManager::inProgressChanged,         this, &MissionController::_inProgressChanged);
854
        connect(missionManager, &MissionManager::currentItemChanged,        this, &MissionController::_currentMissionItemChanged);
855 856 857
        connect(_activeVehicle, &Vehicle::homePositionAvailableChanged,     this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);

858 859 860
        if (!_editMode) {
            removeAllMissionItems();
        }
861 862 863 864

        _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
        _activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
    }
865 866 867

    // Whenever vehicle changes we need to update syncInProgress
    emit syncInProgressChanged(syncInProgress());
868 869 870 871
}

void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
872 873 874 875 876 877 878 879 880
    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";
        }
881
    }
882 883 884 885
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
886 887
    if (!_editMode && _visualItems) {
        qobject_cast<VisualMissionItem*>(_visualItems->get(0))->setCoordinate(homePosition);
888 889
        _recalcWaypointLines();
    }
890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909
}

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) {
910
        Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
911 912 913 914 915 916 917 918 919 920 921 922 923 924 925

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

void MissionController::_autoSyncSend(void)
{
    qDebug() << "Auto-syncing with vehicle";
    _queuedSend = false;
926
    if (_visualItems) {
927
        sendMissionItems();
928
        _visualItems->setDirty(false);
929 930
    }
}
931

932
void MissionController::_inProgressChanged(bool inProgress)
933
{
934
    emit syncInProgressChanged(inProgress);
935 936 937 938
    if (!inProgress && _queuedSend) {
        _autoSyncSend();
    }
}
939

940
bool MissionController::_findLastAltitude(double* lastAltitude)
941
{
942 943
    bool found = false;
    double foundAltitude;
944

945
    // Don't use home position
946 947
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
948

949 950
        if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
            foundAltitude = item->exitCoordinate().altitude();
951
            found = true;
952 953 954
        }
    }

955 956 957 958 959 960 961 962 963 964 965 966
    if (found) {
        *lastAltitude = foundAltitude;
    }

    return found;
}

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

967 968
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
969

970 971 972 973 974 975 976 977 978 979 980
        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";
            }
981 982 983 984 985 986 987 988
        }
    }

    if (found) {
        *lastAcceptanceRadius = foundAcceptanceRadius;
    }

    return found;
989
}
990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003

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
1004
void MissionController::_addPlannedHomePosition(QmlObjectListModel* visualItems, bool addToCenter)
1005
{
1006 1007
    SimpleMissionItem* homeItem = new SimpleMissionItem(_activeVehicle, this);
    visualItems->insert(0, homeItem);
1008

1009 1010
    if (visualItems->count() > 1  && addToCenter) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(visualItems->get(1));
1011 1012 1013 1014 1015 1016

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

1017 1018
        for (int i=2; i<visualItems->count(); i++) {
            item = qobject_cast<VisualMissionItem*>(visualItems->get(i));
1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033

            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());
    }
}
1034 1035 1036 1037 1038 1039 1040 1041

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

1042 1043
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1044 1045 1046 1047
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
    }
}
1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067

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;
}
1068 1069 1070

bool MissionController::syncInProgress(void)
{
1071 1072 1073 1074 1075
    if (_activeVehicle) {
        return _activeVehicle->missionManager()->inProgress();
    } else {
        return false;
    }
1076
}