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

QGroundControl Open Source Ground Control Station

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

This file is part of the QGROUNDCONTROL project

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

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

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

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

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

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

35 36
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

37
const char* MissionController::_settingsGroup = "MissionController";
38 39 40

MissionController::MissionController(QObject *parent)
    : QObject(parent)
41
    , _editMode(false)
42 43
    , _missionItems(NULL)
    , _activeVehicle(NULL)
44 45
    , _liveHomePositionAvailable(false)
    , _autoSync(false)
46
    , _firstItemsFromVehicle(false)
47 48
    , _missionItemsRequested(false)
    , _queuedSend(false)
49
{
50 51 52 53 54

}

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

56 57 58 59
}

void MissionController::start(bool editMode)
{
60 61
    qCDebug(MissionControllerLog) << "start editMode" << editMode;

62 63
    _editMode = editMode;

64
    MultiVehicleManager* multiVehicleMgr = qgcApp()->toolbox()->multiVehicleManager();
65

66
    connect(multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &MissionController::_activeVehicleChanged);
67

Don Gagne's avatar
Don Gagne committed
68 69
    _setupMissionItems(true /* loadFromVehicle */, true /* forceLoad */);
    _setupActiveVehicle(multiVehicleMgr->activeVehicle(), true /* forceLoadFromVehicle */);
70 71
}

72
void MissionController::_newMissionItemsAvailableFromVehicle(void)
73
{
74 75
    qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle";

Don Gagne's avatar
Don Gagne committed
76
    _setupMissionItems(true /* loadFromVehicle */, false /* forceLoad */);
77 78
}

Don Gagne's avatar
Don Gagne committed
79 80 81
/// @param loadFromVehicle true: load items from vehicle
/// @param forceLoad true: disregard any flags which may prevent load
void MissionController::_setupMissionItems(bool loadFromVehicle, bool forceLoad)
82
{
Don Gagne's avatar
Don Gagne committed
83 84
    qCDebug(MissionControllerLog) << "_setupMissionItems loadFromVehicle:forceLoad:_editMode:_firstItemsFromVehicle"
                                  << loadFromVehicle << forceLoad << _editMode << _firstItemsFromVehicle;
85 86 87 88 89 90 91 92

    MissionManager* missionManager = NULL;
    if (_activeVehicle) {
        missionManager = _activeVehicle->missionManager();
    } else {
        qCDebug(MissionControllerLog) << "running offline";
    }

Don Gagne's avatar
Don Gagne committed
93 94
    if (!forceLoad) {
        if (_editMode && loadFromVehicle) {
95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110
            if (_firstItemsFromVehicle) {
                if (missionManager) {
                    if (missionManager->inProgress()) {
                        // Still in progress of retrieving items from vehicle, leave current set alone and wait for
                        // mission manager to finish
                        qCDebug(MissionControllerLog) << "disregarding due to MissionManager in progress";
                        return;
                    } else {
                        // We have the first set of items from the vehicle. If we haven't already started creating a
                        // new mission, switch to the items from the vehicle
                        _firstItemsFromVehicle = false;
                        if (_missionItems->count() != 1) {
                            qCDebug(MissionControllerLog) << "disregarding due to existing items";
                            return;
                        }
                    }
111
                }
112 113 114 115 116
            } else if (!_missionItemsRequested) {
                // We didn't specifically ask for new mission items. Disregard the new set since it is
                // the most likely the set we just sent to the vehicle.
                qCDebug(MissionControllerLog) << "disregarding due to unrequested notification";
                return;
117 118 119 120
            }
        }
    }

121 122
    qCDebug(MissionControllerLog) << "fell through to main setup";

123 124
    _missionItemsRequested = false;

125
    if (_missionItems) {
126
        _deinitAllMissionItems();
127 128
        _missionItems->deleteLater();
    }
129

Don Gagne's avatar
Don Gagne committed
130
    if (!missionManager || !loadFromVehicle || missionManager->inProgress()) {
131
        _missionItems = new QmlObjectListModel(this);
132
        qCDebug(MissionControllerLog) << "creating empty set";
133
        _initAllMissionItems();
134 135
    } else {
        _missionItems = missionManager->copyMissionItems();
136
        qCDebug(MissionControllerLog) << "loading from vehicle count"<< _missionItems->count();
137 138
        _initAllMissionItems();
        emit newItemsFromVehicle();
139 140 141
    }
}

142
void MissionController::getMissionItems(void)
143
{
144
    Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
145

146 147 148 149 150 151 152 153
    if (activeVehicle) {
        _missionItemsRequested = true;
        activeVehicle->missionManager()->requestMissionItems();
    }
}

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

156 157 158 159 160
    if (activeVehicle) {
        activeVehicle->missionManager()->writeMissionItems(*_missionItems);
        _missionItems->setDirty(false);
    }
}
161

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

        if (_findLastAcceptanceRadius(&lastValue)) {
            newItem->setParam2(lastValue);
        }
        if (_findLastAltitude(&lastValue)) {
            newItem->setParam7(lastValue);
        }
182
    }
183
    _missionItems->insert(i, newItem);
184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208

    _recalcAll();

    return _missionItems->count() - 1;
}

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

    _deinitMissionItem(item);

    _recalcAll();

    // Set the new current item

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

209 210 211 212 213 214 215 216 217
void MissionController::removeAllMissionItems(void)
{
    if (_missionItems) {
        _deinitAllMissionItems();
        _missionItems->deleteLater();
    }
    _missionItems = new QmlObjectListModel(this);

    _initAllMissionItems();
218
    _missionItems->setDirty(true);
219 220
}

221 222
void MissionController::loadMissionFromFile(void)
{
223
#ifndef __mobile__
224 225
    QString errorString;
    QString filename = QGCFileDialog::getOpenFileName(NULL, "Select Mission File to load");
226
    bool versionAPM = false;
227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248

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

    if (_missionItems) {
        _deinitAllMissionItems();
        _missionItems->deleteLater();
    }
    _missionItems = new QmlObjectListModel(this);

    // FIXME: This needs to handle APM files which have WP 0 in them

    QFile file(filename);

    if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
        errorString = file.errorString();
    } else {
        QTextStream in(&file);

        const QStringList& version = in.readLine().split(" ");

249 250 251 252 253 254 255 256 257 258 259
        bool versionOk = false;
        if (version.size() == 3 && version[0] == "QGC" && version[1] == "WPL") {
            if (version[2] == "120") {
                versionOk = true;
            } else if (version[2] == "110") {
                versionOk = true;
                versionAPM = true;
            }
        }

        if (versionOk) {
260
            while (!in.atEnd()) {
261
                MissionItem* item = new MissionItem(_activeVehicle, this);
262 263 264

                if (item->load(in)) {
                    _missionItems->append(item);
265
                } else {
266 267
                    errorString = "The mission file is corrupted.";
                    break;
268 269
                }
            }
270 271
        } else {
            errorString = "The mission file is not compatible with this version of QGroundControl.";
272 273
        }
    }
274

275 276 277 278 279 280
    if (errorString.isEmpty()) {
        if (versionAPM) {
            // Remove fake home position from APM files
            _missionItems->removeAt(0);
        }
    } else {
281
        _missionItems->clear();
282
        qgcApp()->showMessage(errorString);
283 284 285
    }

    _initAllMissionItems();
286
#endif
287 288
}

289
void MissionController::saveMissionToFile(void)
290
{
291
#ifndef __mobile__
292 293 294 295 296
    QString filename = QGCFileDialog::getSaveFileName(NULL, "Select file to save mission to");

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

298
    QFile file(filename);
299

300
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
301
        qgcApp()->showMessage(file.errorString());
302 303
    } else {
        QTextStream out(&file);
304

305
        out << "QGC WPL 120\r\n";   // Version string
306

307 308 309 310 311 312
        for (int i=1; i<_missionItems->count(); i++) {
            qobject_cast<MissionItem*>(_missionItems->get(i))->save(out);
        }
    }

    _missionItems->setDirty(false);
313
#endif
314 315
}

Don Gagne's avatar
Don Gagne committed
316
void MissionController::_calcPrevWaypointValues(bool homePositionValid, double homeAlt, MissionItem* currentItem, MissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
317
{
Don Gagne's avatar
Don Gagne committed
318 319
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  prevCoord =     prevItem->coordinate();
320 321 322 323 324
    bool            distanceOk =    false;

    // Convert to fixed altitudes

    qCDebug(MissionControllerLog) << homePositionValid << homeAlt
Don Gagne's avatar
Don Gagne committed
325 326
                                  << currentItem->relativeAltitude() << currentItem->coordinate().altitude()
                                  << prevItem->relativeAltitude() << prevItem->coordinate().altitude();
327 328 329

    if (homePositionValid) {
        distanceOk = true;
Don Gagne's avatar
Don Gagne committed
330 331
        if (currentItem->relativeAltitude()) {
            currentCoord.setAltitude(homeAlt + currentCoord.altitude());
332
        }
Don Gagne's avatar
Don Gagne committed
333 334
        if (prevItem->relativeAltitude()) {
            prevCoord.setAltitude(homeAlt + prevCoord.altitude());
335 336
        }
    } else {
Don Gagne's avatar
Don Gagne committed
337
        if (prevItem->relativeAltitude() && currentItem->relativeAltitude()) {
338 339 340 341 342 343 344
            distanceOk = true;
        }
    }

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

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
345 346 347
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
348
    } else {
Don Gagne's avatar
Don Gagne committed
349
        *altDifference = 0.0;
350
        *azimuth = 0.0;
Don Gagne's avatar
Don Gagne committed
351
        *distance = -1.0;   // Signals no values
352 353 354
    }
}

355 356 357
void MissionController::_recalcWaypointLines(void)
{
    MissionItem*    lastCoordinateItem =    qobject_cast<MissionItem*>(_missionItems->get(0));
358
    MissionItem*    homeItem =              lastCoordinateItem;
359
    bool            firstCoordinateItem =   true;
360 361 362 363 364 365 366 367
    bool            homePositionValid =     homeItem->homePositionValid();
    double          homeAlt =               homeItem->coordinate().altitude();

    qCDebug(MissionControllerLog) << "_recalcWaypointLines";

    // If home position is valid we can calculate distances between all waypoints.
    // If home position is not valid we can only calculate distances between waypoints which are
    // both relative altitude.
368

369
    // No values for first item
370
    lastCoordinateItem->setAltDifference(0.0);
371
    lastCoordinateItem->setAzimuth(0.0);
372 373
    lastCoordinateItem->setDistance(-1.0);

374 375 376 377 378
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
    double homePositionAltitude = homeItem->coordinate().altitude();
    minAltSeen = maxAltSeen = homeItem->coordinate().altitude();

379 380 381 382 383
    _waypointLines.clear();

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

384 385 386
        // Assume the worst
        item->setAzimuth(0.0);
        item->setDistance(-1.0);
387

388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410
        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
            if (item->relativeAltitude() && homePositionValid) {
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

            if (!item->standaloneCoordinate()) {
                if (firstCoordinateItem) {
                    if (item->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) {
                        // The first coordinate we hit is a takeoff command so link back to home position if valid
                        if (homePositionValid) {
                            double azimuth, distance, altDifference;

                            _waypointLines.append(new CoordinateVector(homeItem->coordinate(), item->coordinate()));
                            _calcPrevWaypointValues(homePositionValid, homeAlt, item, homeItem, &azimuth, &distance, &altDifference);
                            item->setAltDifference(altDifference);
                            item->setAzimuth(azimuth);
                            item->setDistance(distance);
                        }
                    } else {
                        // First coordiante is not a takeoff command, it does not link backwards to anything
411
                    }
412 413 414 415 416 417 418 419 420 421 422
                    firstCoordinateItem = false;
                } else if (!lastCoordinateItem->homePosition() || lastCoordinateItem->homePositionValid()) {
                    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
                    _calcPrevWaypointValues(homePositionValid, homeAlt, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
                    _waypointLines.append(new CoordinateVector(lastCoordinateItem->coordinate(), item->coordinate()));
423
                }
424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442
                lastCoordinateItem = item;
            }
        }
    }

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

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
            if (item->relativeAltitude() && homePositionValid) {
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
443
            }
444 445
        }
    }
446 447

    emit waypointLinesChanged();
448 449
}

450 451 452 453 454 455 456 457 458 459 460
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
    for (int i=0; i<_missionItems->count(); i++) {
        MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));

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

461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
    MissionItem* currentParentItem = qobject_cast<MissionItem*>(_missionItems->get(0));

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

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

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

481 482
void MissionController::_recalcAll(void)
{
483
    _recalcSequence();
484 485 486 487 488 489 490
    _recalcChildItems();
    _recalcWaypointLines();
}

/// Initializes a new set of mission items which may have come from the vehicle or have been loaded from a file
void MissionController::_initAllMissionItems(void)
{
491 492 493 494 495 496
    MissionItem* homeItem = NULL;

    if (_activeVehicle && _activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() && _missionItems->count() != 0) {
        homeItem = qobject_cast<MissionItem*>(_missionItems->get(0));
    } else {
        // Add the home position item to the front
497
        homeItem = new MissionItem(_activeVehicle, this);
498
        homeItem->setSequenceNumber(0);
499 500
        _missionItems->insert(0, homeItem);
    }
Don Gagne's avatar
Don Gagne committed
501 502 503
    homeItem->setHomePositionSpecialCase(true);
    if (_activeVehicle) {
        homeItem->setHomePositionValid(_activeVehicle->homePositionAvailable());
DonLakeFlyer's avatar
DonLakeFlyer committed
504 505 506
        if (homeItem->homePositionValid()) {
            homeItem->setCoordinate(_activeVehicle->homePosition());
        }
Don Gagne's avatar
Don Gagne committed
507 508 509 510 511
    } else {
        homeItem->setHomePositionValid(false);
    }
    homeItem->setCommand(MAV_CMD_NAV_WAYPOINT);
    homeItem->setFrame(MAV_FRAME_GLOBAL);
512
    if (!homeItem->homePositionValid()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
513 514
        // Set a bogus home position, the important value is 0.0 Altitude
        homeItem->setCoordinate(QGeoCoordinate(37.803784, -122.462276, 0.0));
515
    }
516

dogmaphobic's avatar
dogmaphobic committed
517
    //qDebug() << "home item" << homeItem->homePositionValid() << homeItem->coordinate();
DonLakeFlyer's avatar
DonLakeFlyer committed
518

519 520 521 522
    for (int i=0; i<_missionItems->count(); i++) {
        _initMissionItem(qobject_cast<MissionItem*>(_missionItems->get(i)));
    }

523
    _recalcAll();
524

525
    emit missionItemsChanged();
526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546

    _missionItems->setDirty(false);

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

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

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

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

    connect(item, &MissionItem::commandChanged,     this, &MissionController::_itemCommandChanged);
    connect(item, &MissionItem::coordinateChanged,  this, &MissionController::_itemCoordinateChanged);
547
    connect(item, &MissionItem::frameChanged,       this, &MissionController::_itemFrameChanged);
548 549 550 551 552 553
}

void MissionController::_deinitMissionItem(MissionItem* item)
{
    disconnect(item, &MissionItem::commandChanged,     this, &MissionController::_itemCommandChanged);
    disconnect(item, &MissionItem::coordinateChanged,  this, &MissionController::_itemCoordinateChanged);
554
    disconnect(item, &MissionItem::frameChanged,       this, &MissionController::_itemFrameChanged);
555 556 557 558 559 560 561 562
}

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

563 564 565 566 567 568
void MissionController::_itemFrameChanged(int frame)
{
    Q_UNUSED(frame);
    _recalcWaypointLines();
}

569 570 571 572 573
void MissionController::_itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command)
{
    Q_UNUSED(command);;
    _recalcChildItems();
    _recalcWaypointLines();
574 575 576 577
}

void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
{
578 579
    qCDebug(MissionControllerLog) << "_activeVehicleChanged activeVehicle" << activeVehicle;

580 581
    if (_activeVehicle) {
        MissionManager* missionManager = _activeVehicle->missionManager();
582

583
        disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailableFromVehicle);
584 585 586
        disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
        disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged,      this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
587
        _activeVehicle = NULL;
588 589

        // When the active vehicle goes away we toss the editor items
Don Gagne's avatar
Don Gagne committed
590
        _setupMissionItems(false /* loadFromVehicle */, true /* forceLoad */);
591
        _activeVehicleHomePositionAvailableChanged(false);
592
    }
593

Don Gagne's avatar
Don Gagne committed
594 595 596 597 598 599 600 601 602 603 604 605
    _setupActiveVehicle(activeVehicle, false /* forceLoadFromVehicle */);
}

void MissionController::_setupActiveVehicle(Vehicle* activeVehicle, bool forceLoadFromVehicle)
{
    qCDebug(MissionControllerLog) << "_setupActiveVehicle activeVehicle:forceLoadFromVehicle"
                                  << activeVehicle << forceLoadFromVehicle;

    if (_activeVehicle) {
        qCWarning(MissionControllerLog) << "_activeVehicle != NULL";
    }

606
    _activeVehicle = activeVehicle;
607

608 609
    if (_activeVehicle) {
        MissionManager* missionManager = activeVehicle->missionManager();
610

611
        connect(missionManager, &MissionManager::newMissionItemsAvailable,  this, &MissionController::_newMissionItemsAvailableFromVehicle);
612
        connect(missionManager, &MissionManager::inProgressChanged,         this, &MissionController::_inProgressChanged);
613 614 615
        connect(_activeVehicle, &Vehicle::homePositionAvailableChanged,     this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);

616
        _firstItemsFromVehicle = true;
Don Gagne's avatar
Don Gagne committed
617
        _setupMissionItems(true /* fromVehicle */, forceLoadFromVehicle);
618 619 620 621 622 623 624 625 626

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

void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
    _liveHomePositionAvailable = homePositionAvailable;
Don Gagne's avatar
Don Gagne committed
627
    qobject_cast<MissionItem*>(_missionItems->get(0))->setHomePositionValid(homePositionAvailable);
628
    emit liveHomePositionAvailableChanged(_liveHomePositionAvailable);
629
    _recalcWaypointLines();
630 631 632 633 634
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
    _liveHomePosition = homePosition;
Don Gagne's avatar
Don Gagne committed
635
    qobject_cast<MissionItem*>(_missionItems->get(0))->setCoordinate(_liveHomePosition);
636
    emit liveHomePositionChanged(_liveHomePosition);
637
    _recalcWaypointLines();
638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657
}

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) {
658
        Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676

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

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

680
void MissionController::_inProgressChanged(bool inProgress)
681
{
682 683 684 685
    if (!inProgress && _queuedSend) {
        _autoSyncSend();
    }
}
686

687 688 689
QmlObjectListModel* MissionController::missionItems(void)
{
    return _missionItems;
690
}
691

692
bool MissionController::_findLastAltitude(double* lastAltitude)
693
{
694 695
    bool found = false;
    double foundAltitude;
696 697 698 699

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

700
        if (item->specifiesCoordinate() && !item->standaloneCoordinate()) {
701 702
            foundAltitude = item->param7();
            found = true;
703 704 705
        }
    }

706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731
    if (found) {
        *lastAltitude = foundAltitude;
    }

    return found;
}

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

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

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

    if (found) {
        *lastAcceptanceRadius = foundAcceptanceRadius;
    }

    return found;
732
}