MissionController.cc 41.9 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
9 10 11 12 13 14


#include "MissionController.h"
#include "MultiVehicleManager.h"
#include "MissionManager.h"
#include "CoordinateVector.h"
15
#include "FirmwarePlugin.h"
16
#include "QGCApplication.h"
17 18
#include "SimpleMissionItem.h"
#include "ComplexMissionItem.h"
19
#include "JsonHelper.h"
20
#include "ParameterLoader.h"
21

22 23 24 25
#ifndef __mobile__
#include "QGCFileDialog.h"
#endif

26 27
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

28 29
const char* MissionController::jsonSimpleItemsKey = "items";

30 31 32 33
const char* MissionController::_settingsGroup =                 "MissionController";
const char* MissionController::_jsonVersionKey =                "version";
const char* MissionController::_jsonGroundStationKey =          "groundStation";
const char* MissionController::_jsonMavAutopilotKey =           "MAV_AUTOPILOT";
34
const char* MissionController::_jsonComplexItemsKey =           "complexItems";
35
const char* MissionController::_jsonPlannedHomePositionKey =    "plannedHomePosition";
36 37 38

MissionController::MissionController(QObject *parent)
    : QObject(parent)
39
    , _editMode(false)
40 41
    , _visualItems(NULL)
    , _complexItems(NULL)
42
    , _activeVehicle(NULL)
43
    , _autoSync(false)
44
    , _firstItemsFromVehicle(false)
45 46
    , _missionItemsRequested(false)
    , _queuedSend(false)
47
{
48 49 50 51 52

}

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

54 55 56 57
}

void MissionController::start(bool editMode)
{
58 59
    qCDebug(MissionControllerLog) << "start editMode" << editMode;

60 61
    _editMode = editMode;

62
    MultiVehicleManager* multiVehicleMgr = qgcApp()->toolbox()->multiVehicleManager();
63

64
    connect(multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &MissionController::_activeVehicleChanged);
65
    _activeVehicleChanged(multiVehicleMgr->activeVehicle());
66

67
    // We start with an empty mission
68 69 70
    _visualItems = new QmlObjectListModel(this);
    _addPlannedHomePosition(_visualItems, false /* addToCenter */);
    _initAllVisualItems();
71 72
}

73
// Called when new mission items have completed downloading from Vehicle
74
void MissionController::_newMissionItemsAvailableFromVehicle(void)
75
{
76 77
    qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle";

78
    if (!_editMode || _missionItemsRequested || _visualItems->count() == 1) {
79
        // Fly Mode:
Don Gagne's avatar
Don Gagne committed
80
        //      - Always accepts new items from the vehicle so Fly view is kept up to date
81 82
        // Edit Mode:
        //      - Either a load from vehicle was manually requested or
Don Gagne's avatar
Don Gagne committed
83
        //      - The initial automatic load from a vehicle completed and the current editor is empty
84

85 86
        QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
        const QList<MissionItem*>& newMissionItems = _activeVehicle->missionManager()->missionItems();
87

88 89 90 91 92 93 94 95 96 97 98 99
        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 */);
100 101
        }

102
        _missionItemsRequested = false;
103

104
        _initAllVisualItems();
105
        emit newItemsFromVehicle();
106 107 108
    }
}

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

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

void MissionController::sendMissionItems(void)
{
121 122 123 124 125 126 127
    if (_activeVehicle) {
        // Convert to MissionItems so we can send to vehicle
        QList<MissionItem*> missionItems;

        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
            if (visualItem->isSimpleItem()) {
128
                missionItems.append(new MissionItem(qobject_cast<SimpleMissionItem*>(visualItem)->missionItem()));
129
            } else {
130
                ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
131 132 133
                QmlObjectListModel* complexMissionItems = complexItem->getMissionItems();
                for (int j=0; j<complexMissionItems->count(); j++) {
                    missionItems.append(new MissionItem(*qobject_cast<MissionItem*>(complexMissionItems->get(j))));
134
                }
135
                delete complexMissionItems;
136 137 138 139 140
            }
        }

        _activeVehicle->missionManager()->writeMissionItems(missionItems);
        _visualItems->setDirty(false);
141 142 143 144

        for (int i=0; i<missionItems.count(); i++) {
            delete missionItems[i];
        }
145 146
    }
}
147

148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
        VisualMissionItem* lastItem = qobject_cast<VisualMissionItem*>(_visualItems->get(_visualItems->count() - 1));

        if (lastItem->isSimpleItem()) {
            return lastItem->sequenceNumber() + 1;
        } else {
            return qobject_cast<ComplexMissionItem*>(lastItem)->lastSequenceNumber() + 1;
        }
    }
}

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

        if (_findLastAcceptanceRadius(&lastValue)) {
180
            newItem->missionItem().setParam2(lastValue);
181 182
        }
        if (_findLastAltitude(&lastValue)) {
183
            newItem->missionItem().setParam7(lastValue);
184
        }
185
    }
186
    _visualItems->insert(i, newItem);
187 188 189

    _recalcAll();

190
    return newItem->sequenceNumber();
191 192
}

193 194
int MissionController::insertComplexMissionItem(QGeoCoordinate coordinate, int i)
{
195
    int sequenceNumber = _nextSequenceNumber();
196
    ComplexMissionItem* newItem = new ComplexMissionItem(_activeVehicle, this);
197
    newItem->setSequenceNumber(sequenceNumber);
198
    newItem->setCoordinate(coordinate);
199
    _initVisualItem(newItem);
200

201 202
    _visualItems->insert(i, newItem);
    _complexItems->append(newItem);
203 204 205

    _recalcAll();

206
    return newItem->sequenceNumber();
207 208
}

209 210
void MissionController::removeMissionItem(int index)
{
211
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
212

213 214 215 216 217 218 219 220 221
    _deinitVisualItem(item);
    if (!item->isSimpleItem()) {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(_complexItems->removeOne(item));
        if (complexItem) {
            complexItem->deleteLater();
        } else {
            qWarning() << "Complex item missing";
        }
    }
222
    item->deleteLater();
223 224 225 226 227

    _recalcAll();

    // Set the new current item

228
    if (index >= _visualItems->count()) {
229 230
        index--;
    }
231
    for (int i=0; i<_visualItems->count(); i++) {
Don Gagne's avatar
Don Gagne committed
232
        VisualMissionItem* item =  qobject_cast<VisualMissionItem*>(_visualItems->get(i));
233 234
        item->setIsCurrentItem(i == index);
    }
235
    _visualItems->setDirty(true);
236 237
}

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

250
bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString)
251 252 253 254 255 256 257 258 259 260 261
{
    QJsonParseError jsonParseError;
    QJsonDocument   jsonDoc(QJsonDocument::fromJson(bytes, &jsonParseError));

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

    QJsonObject json = jsonDoc.object();

262 263 264 265 266 267 268 269 270 271 272 273 274
    // 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)) {
275 276
        return false;
    }
277 278

    // Version check
279 280 281 282 283
    if (json[_jsonVersionKey].toString() != "1.0") {
        errorString = QStringLiteral("QGroundControl does not support this file version");
        return false;
    }

284 285 286 287 288
    // Read complex items
    QJsonArray complexArray(json[_jsonComplexItemsKey].toArray());
    qCDebug(MissionControllerLog) << "Json load: complex item count" << complexArray.count();
    for (int i=0; i<complexArray.count(); i++) {
        const QJsonValue& itemValue = complexArray[i];
289

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

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

304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331
    // Read simple items, interspersing complex items into the full list

    int nextSimpleItemIndex= 0;
    int nextComplexItemIndex= 0;
    int nextSequenceNumber = 1; // Start with 1 since home is in 0
    QJsonArray itemArray(json[jsonSimpleItemsKey].toArray());

    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << complexItems->count();
    do {
        qCDebug(MissionControllerLog) << "Json load: simple item loop nextSimpleItemIndex:nextComplexItemIndex:nextSequenceNumber" << nextSimpleItemIndex << nextComplexItemIndex << nextSequenceNumber;

        // If there is a complex item that should be next in sequence add it in
        if (nextComplexItemIndex < complexItems->count()) {
            ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(complexItems->get(nextComplexItemIndex));

            if (complexItem->sequenceNumber() == nextSequenceNumber) {
                qCDebug(MissionControllerLog) << "Json load: injecting complex item expectedSequence:actualSequence:" << nextSequenceNumber << complexItem->sequenceNumber();
                visualItems->append(complexItem);
                nextSequenceNumber = complexItem->lastSequenceNumber() + 1;
                nextComplexItemIndex++;
                continue;
            }
        }

        // Add the next available simple item
        if (nextSimpleItemIndex < itemArray.count()) {
            const QJsonValue& itemValue = itemArray[nextSimpleItemIndex++];

332 333 334 335 336
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

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

            nextSequenceNumber++;
346
        }
Don Gagne's avatar
Don Gagne committed
347
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < complexItems->count());
348 349

    if (json.contains(_jsonPlannedHomePositionKey)) {
350
        SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
351 352

        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), errorString)) {
353
            visualItems->insert(0, item);
354 355 356 357
        } else {
            return false;
        }
    } else {
358
        _addPlannedHomePosition(visualItems, true /* addToCenter */);
359 360 361 362 363
    }

    return true;
}

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

            if (item->load(stream)) {
388
                visualItems->append(item);
389 390 391 392 393 394 395 396 397 398
            } 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;
    }

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

402 403 404 405 406
        // 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
407 408
            }
        }
409 410 411
    }

    return true;
412 413
}

Don Gagne's avatar
Don Gagne committed
414
void MissionController::loadMissionFromFile(const QString& filename)
415 416 417 418 419 420 421
{
    QString errorString;

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

422 423
    QmlObjectListModel* newVisualItems = new QmlObjectListModel(this);
    QmlObjectListModel* newComplexItems = new QmlObjectListModel(this);
424 425 426 427 428 429

    QFile file(filename);

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

433 434 435
        QString firstLine = stream.readLine();
        if (firstLine.contains(QRegExp("QGC.*WPL"))) {
            stream.seek(0);
436
            _loadTextMissionFile(stream, newVisualItems, errorString);
437
        } else {
438
            _loadJsonMissionFile(bytes, newVisualItems, newComplexItems, errorString);
439 440
        }
    }
441

442
    if (!errorString.isEmpty()) {
443 444 445 446 447 448 449 450 451
        for (int i=0; i<newVisualItems->count(); i++) {
            newVisualItems->get(i)->deleteLater();
        }
        for (int i=0; i<newComplexItems->count(); i++) {
            newComplexItems->get(i)->deleteLater();
        }
        delete newVisualItems;
        delete newComplexItems;

452
        qgcApp()->showMessage(errorString);
453
        return;
454 455
    }

456 457 458
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteListAndContents();
459
    }
460 461 462 463 464 465 466
    if (_complexItems) {
        _complexItems->deleteLater();
    }

    _visualItems = newVisualItems;
    _complexItems = newComplexItems;

467 468
    if (_visualItems->count() == 0) {
        _addPlannedHomePosition(_visualItems, true /* addToCenter */);
469 470
    }

471
    _initAllVisualItems();
472 473
}

Don Gagne's avatar
Don Gagne committed
474
void MissionController::loadMissionFromFilePicker(void)
475
{
476
#ifndef __mobile__
477 478 479 480 481
    QString filename = QGCFileDialog::getOpenFileName(NULL, "Select Mission File to load", QString(), "Mission file (*.mission);;All Files (*.*)");

    if (filename.isEmpty()) {
        return;
    }
Don Gagne's avatar
Don Gagne committed
482
    loadMissionFromFile(filename);
483 484 485
#endif
}

Don Gagne's avatar
Don Gagne committed
486
void MissionController::saveMissionToFile(const QString& filename)
487 488
{
    qDebug() << filename;
489 490 491 492

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

494
    QString missionFilename = filename;
495
    if (!QFileInfo(filename).fileName().contains(".")) {
Don Gagne's avatar
Don Gagne committed
496
        missionFilename += QString(".%1").arg(QGCApplication::missionFileExtension);
497 498
    }

499
    QFile file(missionFilename);
500

501
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
502
        qgcApp()->showMessage(file.errorString());
503
    } else {
504 505 506
        QJsonObject missionFileObject;      // top level json object
        QJsonArray  simpleItemsObject;
        QJsonArray  complexItemsObject;
507

508 509
        missionFileObject[_jsonVersionKey] =        "1.0";
        missionFileObject[_jsonGroundStationKey] =  "QGroundControl";
510

511 512 513 514 515 516 517 518 519 520
        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();
        }
521
        missionFileObject[_jsonMavAutopilotKey] = firmwareType;
522

523
        // Save planned home position
524
        QJsonObject homePositionObject;
525 526 527 528 529 530 531
        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;
        }
532
        missionFileObject[_jsonPlannedHomePositionKey] = homePositionObject;
533

534
        // Save the visual items
535
        for (int i=1; i<_visualItems->count(); i++) {
536 537
            QJsonObject itemObject;

538
            VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
539 540 541 542 543 544
            visualItem->save(itemObject);

            if (visualItem->isSimpleItem()) {
                simpleItemsObject.append(itemObject);
            } else {
                complexItemsObject.append(itemObject);
545
            }
546
        }
547

548 549 550 551
        missionFileObject[jsonSimpleItemsKey] = simpleItemsObject;
        missionFileObject[_jsonComplexItemsKey] = complexItemsObject;

        QJsonDocument saveDoc(missionFileObject);
552
        file.write(saveDoc.toJson());
553 554
    }

555
    _visualItems->setDirty(false);
556 557
}

Don Gagne's avatar
Don Gagne committed
558
void MissionController::saveMissionToFilePicker(void)
559 560 561 562 563 564 565
{
#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
566
    saveMissionToFile(filename);
567
#endif
568 569
}

570
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
571
{
Don Gagne's avatar
Don Gagne committed
572
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
573
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
574 575 576 577
    bool            distanceOk =    false;

    // Convert to fixed altitudes

578
    qCDebug(MissionControllerLog) << homeAlt
579 580
                                  << currentItem->coordinateHasRelativeAltitude() << currentItem->coordinate().altitude()
                                  << prevItem->exitCoordinateHasRelativeAltitude() << prevItem->exitCoordinate().altitude();
581

582
    distanceOk = true;
583
    if (currentItem->coordinateHasRelativeAltitude()) {
584 585
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
586
    if (prevItem->exitCoordinateHasRelativeAltitude()) {
587
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
588 589 590 591 592
    }

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

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
593 594 595
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
596
    } else {
Don Gagne's avatar
Don Gagne committed
597
        *altDifference = 0.0;
598
        *azimuth = 0.0;
Don Gagne's avatar
Don Gagne committed
599
        *distance = -1.0;   // Signals no values
600 601 602
    }
}

603 604
void MissionController::_recalcWaypointLines(void)
{
605 606 607 608 609 610 611
    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";
612 613
    } else {
        connect(homeItem, &VisualMissionItem::coordinateChanged, this, &MissionController::_recalcAltitudeRangeBearing);
614 615 616
    }

    bool    showHomePosition =  homeItem->showHomePosition();
617 618 619

    qCDebug(MissionControllerLog) << "_recalcWaypointLines";

Nate Weibley's avatar
Nate Weibley committed
620 621
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642
    _waypointLines.clear();

    bool linkBackToHome = false;
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));


        // If we still haven't found the first coordinate item and we hit a a takeoff command link back to home
        if (firstCoordinateItem &&
                item->isSimpleItem() &&
                qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) {
            linkBackToHome = true;
        }

        if (item->specifiesCoordinate()) {
            if (!item->isStandaloneCoordinate()) {
                firstCoordinateItem = false;
                VisualItemPair pair(lastCoordinateItem, item);
                if (lastCoordinateItem != homeItem || (showHomePosition && linkBackToHome)) {
                    if (old_table.contains(pair)) {
                        // Do nothing, this segment already exists and is wired up
Nate Weibley's avatar
Nate Weibley committed
643
                        _linesTable[pair] = old_table.take(pair);
644 645 646 647 648 649 650 651 652 653 654 655
                    } else {
                        // Create a new segment and wire update notifiers
                        auto linevect       = new CoordinateVector(lastCoordinateItem->isSimpleItem() ? lastCoordinateItem->coordinate() : lastCoordinateItem->exitCoordinate(), item->coordinate(), this);
                        auto originNotifier = lastCoordinateItem->isSimpleItem() ? &VisualMissionItem::coordinateChanged : &VisualMissionItem::exitCoordinateChanged,
                             endNotifier    = &VisualMissionItem::coordinateChanged;
                        // Use signals/slots to update the coordinate endpoints
                        connect(lastCoordinateItem, originNotifier, linevect, &CoordinateVector::setCoordinate1);
                        connect(item,               endNotifier,    linevect, &CoordinateVector::setCoordinate2);

                        // FIXME: We should ideally have signals for 2D position change, alt change, and 3D position change
                        // Not optimal, but still pretty fast, do a full update of range/bearing/altitudes
                        connect(item, &VisualMissionItem::coordinateChanged, this, &MissionController::_recalcAltitudeRangeBearing);
Nate Weibley's avatar
Nate Weibley committed
656
                        _linesTable[pair] = linevect;
657 658 659 660 661 662 663 664 665 666 667
                    }
                }
                lastCoordinateItem = item;
            }
        }
    }


    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
668 669
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703
            objs.append(vect);
        }

        // We don't delete here because many links may still be valid
        _waypointLines.swapObjectList(objs);
    }


    // Anything left in the old table is an obsolete line object that can go
    qDeleteAll(old_table);

    _recalcAltitudeRangeBearing();

    emit waypointLinesChanged();
}

void MissionController::_recalcAltitudeRangeBearing()
{
    if (!_visualItems->count())
        return;

    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

    SimpleMissionItem*  homeItem = qobject_cast<SimpleMissionItem*>(lastCoordinateItem);

    if (!homeItem) {
        qWarning() << "Home item is not SimpleMissionItem";
    }

    bool    showHomePosition =  homeItem->showHomePosition();

    qCDebug(MissionControllerLog) << "_recalcAltitudeRangeBearing";

704 705 706
    // 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.
707

708
    // No values for first item
709
    lastCoordinateItem->setAltDifference(0.0);
710
    lastCoordinateItem->setAzimuth(0.0);
711 712
    lastCoordinateItem->setDistance(-1.0);

713 714
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
715
    const double homePositionAltitude = homeItem->coordinate().altitude();
716 717
    minAltSeen = maxAltSeen = homeItem->coordinate().altitude();

Don Gagne's avatar
Don Gagne committed
718
    bool linkBackToHome = false;
719 720
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
721

722 723 724
        // Assume the worst
        item->setAzimuth(0.0);
        item->setDistance(-1.0);
725

726 727 728 729
        // 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
730 731 732
            linkBackToHome = true;
        }

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

736
            double absoluteAltitude = item->coordinate().altitude();
737
            if (item->coordinateHasRelativeAltitude()) {
738 739 740 741 742
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

743 744 745 746 747 748 749 750 751 752
            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
753
                firstCoordinateItem = false;
754
                if (lastCoordinateItem != homeItem || (showHomePosition && linkBackToHome)) {
755 756 757 758
                    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
759
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
760 761 762
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
763
                }
764 765 766 767 768 769 770
                lastCoordinateItem = item;
            }
        }
    }

    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
771 772
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
773 774 775

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
776
            if (item->coordinateHasRelativeAltitude()) {
777 778 779 780 781 782
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
783
            }
784 785 786 787
        }
    }
}

788 789 790
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
791 792 793 794 795 796 797 798 799
    // 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);
800

801
            if (complexItem) {
802
                 sequenceNumber = complexItem->lastSequenceNumber() + 1;
803 804 805 806
            } else {
                qWarning() << "isSimpleItem == false, yet not ComplexMissionItem";
            }
        }
807 808 809
    }
}

810 811 812
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
813
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
814 815 816

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

817 818
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
819 820 821 822 823

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
824
        } else if (item->isSimpleItem()) {
825 826 827 828 829
            currentParentItem->childItems()->append(item);
        }
    }
}

830 831
void MissionController::_recalcAll(void)
{
832
    _recalcSequence();
833 834 835 836
    _recalcChildItems();
    _recalcWaypointLines();
}

837
/// Initializes a new set of mission items
838
void MissionController::_initAllVisualItems(void)
839
{
840 841 842 843 844 845 846 847 848
    SimpleMissionItem* homeItem = NULL;

    // Setup home position at index 0

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

Don Gagne's avatar
Don Gagne committed
850
    homeItem->setHomePositionSpecialCase(true);
851
    homeItem->setShowHomePosition(_editMode);
852 853
    homeItem->missionItem().setCommand(MAV_CMD_NAV_WAYPOINT);
    homeItem->missionItem().setFrame(MAV_FRAME_GLOBAL);
854 855 856 857 858
    homeItem->setIsCurrentItem(true);

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

861
    QmlObjectListModel* newComplexItems = new QmlObjectListModel(this);
862 863 864
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
865

866 867 868
        // Set up complex item list
        if (!item->isSimpleItem()) {
            ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);
869

870 871 872 873 874
            if (complexItem) {
                newComplexItems->append(item);
            } else {
                qWarning() << "isSimpleItem == false, but not ComplexMissionItem";
            }
875
        }
876 877
    }

878 879 880 881
    if (_complexItems) {
        _complexItems->deleteLater();
    }
    _complexItems = newComplexItems;
882

883
    _recalcAll();
884

885 886
    emit visualItemsChanged();
    emit complexVisualItemsChanged();
887

888
    _visualItems->setDirty(false);
889

890
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_dirtyChanged);
891 892
}

893
void MissionController::_deinitAllVisualItems(void)
894
{
895 896
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
897 898
    }

899
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_dirtyChanged);
900 901
}

902
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
903
{
904 905
    _visualItems->setDirty(false);

906
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
907 908
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
909

910 911 912 913 914 915 916 917
    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";
        }
918 919 920 921
    } else {
        // We need to track changes of lastSequenceNumber so we can recalc sequence numbers for subsequence items
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
        connect(complexItem, &ComplexMissionItem::lastSequenceNumberChanged, this, &MissionController::_recalcSequence);
922
    }
923 924
}

925
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
926
{
927 928
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
929 930
}

931
void MissionController::_itemCommandChanged(void)
932
{
933 934
    _recalcChildItems();
    _recalcWaypointLines();
935 936 937 938
}

void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
{
939 940
    qCDebug(MissionControllerLog) << "_activeVehicleChanged activeVehicle" << activeVehicle;

941 942
    if (_activeVehicle) {
        MissionManager* missionManager = _activeVehicle->missionManager();
943

944
        disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailableFromVehicle);
945
        disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
946
        disconnect(missionManager, &MissionManager::currentItemChanged,         this, &MissionController::_currentMissionItemChanged);
947 948
        disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged,      this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
949
        _activeVehicle = NULL;
Don Gagne's avatar
Don Gagne committed
950 951
    }

Don Gagne's avatar
Don Gagne committed
952 953 954 955
    // We always remove all items on vehicle change. This leaves a user model hole:
    //      If the user has unsaved changes in the Plan view they will lose them
    removeAllMissionItems();

956
    _activeVehicle = activeVehicle;
957

958 959
    if (_activeVehicle) {
        MissionManager* missionManager = activeVehicle->missionManager();
960

961
        connect(missionManager, &MissionManager::newMissionItemsAvailable,  this, &MissionController::_newMissionItemsAvailableFromVehicle);
962
        connect(missionManager, &MissionManager::inProgressChanged,         this, &MissionController::_inProgressChanged);
963
        connect(missionManager, &MissionManager::currentItemChanged,        this, &MissionController::_currentMissionItemChanged);
964 965 966
        connect(_activeVehicle, &Vehicle::homePositionAvailableChanged,     this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);

967 968 969
        if (_activeVehicle->getParameterLoader()->parametersAreReady() && !syncInProgress()) {
            // We are switching between two previously existing vehicles. We have to manually ask for the items from the Vehicle.
            // We don't request mission items for new vehicles since that will happen autamatically.
Don Gagne's avatar
Don Gagne committed
970
            getMissionItems();
971
        }
972 973 974 975

        _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
        _activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
    }
976 977 978

    // Whenever vehicle changes we need to update syncInProgress
    emit syncInProgressChanged(syncInProgress());
979 980 981 982
}

void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
983 984 985 986 987 988 989 990 991
    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";
        }
992
    }
993 994 995 996
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
997 998
    if (!_editMode && _visualItems) {
        qobject_cast<VisualMissionItem*>(_visualItems->get(0))->setCoordinate(homePosition);
999 1000
        _recalcWaypointLines();
    }
1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020
}

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) {
1021
        Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035

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

void MissionController::_autoSyncSend(void)
{
    _queuedSend = false;
1036
    if (_visualItems) {
1037
        sendMissionItems();
1038
        _visualItems->setDirty(false);
1039 1040
    }
}
1041

1042
void MissionController::_inProgressChanged(bool inProgress)
1043
{
1044
    emit syncInProgressChanged(inProgress);
1045 1046 1047 1048
    if (!inProgress && _queuedSend) {
        _autoSyncSend();
    }
}
1049

1050
bool MissionController::_findLastAltitude(double* lastAltitude)
1051
{
1052 1053
    bool found = false;
    double foundAltitude;
1054

1055
    // Don't use home position
1056
    for (int i=1; i<_visualItems->count(); i++) {
1057
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1058

1059 1060
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            foundAltitude = visualItem->exitCoordinate().altitude();
1061
            found = true;
1062 1063 1064 1065 1066 1067 1068

            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_TAKEOFF) {
                    found = false;
                }
            }
1069 1070 1071
        }
    }

1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083
    if (found) {
        *lastAltitude = foundAltitude;
    }

    return found;
}

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

1084 1085
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1086

1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097
        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";
            }
1098 1099 1100 1101 1102 1103 1104 1105
        }
    }

    if (found) {
        *lastAcceptanceRadius = foundAcceptanceRadius;
    }

    return found;
1106
}
1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120

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
1121
void MissionController::_addPlannedHomePosition(QmlObjectListModel* visualItems, bool addToCenter)
1122
{
1123 1124
    SimpleMissionItem* homeItem = new SimpleMissionItem(_activeVehicle, this);
    visualItems->insert(0, homeItem);
1125

1126 1127
    if (visualItems->count() > 1  && addToCenter) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(visualItems->get(1));
1128 1129 1130 1131 1132 1133

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

1134 1135
        for (int i=2; i<visualItems->count(); i++) {
            item = qobject_cast<VisualMissionItem*>(visualItems->get(i));
1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150

            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());
    }
}
1151 1152 1153 1154 1155 1156 1157 1158

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

1159 1160
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1161 1162 1163 1164
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
    }
}
1165

1166 1167
bool MissionController::syncInProgress(void)
{
1168 1169 1170 1171 1172
    if (_activeVehicle) {
        return _activeVehicle->missionManager()->inProgress();
    } else {
        return false;
    }
1173
}