MissionController.cc 24.2 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()
{
55 56 57
    // Start with empty list
    _missionItems = new QmlObjectListModel(this);
    _initAllMissionItems();
58 59 60 61
}

void MissionController::start(bool editMode)
{
62 63
    qCDebug(MissionControllerLog) << "start editMode" << editMode;

64 65
    _editMode = editMode;

66
    MultiVehicleManager* multiVehicleMgr = qgcApp()->toolbox()->multiVehicleManager();
67

68
    connect(multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &MissionController::_activeVehicleChanged);
69

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

74
void MissionController::_newMissionItemsAvailableFromVehicle(void)
75
{
76 77
    qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle";

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

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

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

Don Gagne's avatar
Don Gagne committed
95 96
    if (!forceLoad) {
        if (_editMode && loadFromVehicle) {
97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112
            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;
                        }
                    }
113
                }
114 115 116 117 118
            } 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;
119 120 121 122
            }
        }
    }

123 124
    qCDebug(MissionControllerLog) << "fell through to main setup";

125 126
    _missionItemsRequested = false;

127
    if (_missionItems) {
128
        _deinitAllMissionItems();
129 130
        _missionItems->deleteLater();
    }
131

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

    _initAllMissionItems();
}

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

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

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

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

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

        if (_findLastAcceptanceRadius(&lastValue)) {
            newItem->setParam2(lastValue);
        }
        if (_findLastAltitude(&lastValue)) {
            newItem->setParam7(lastValue);
        }
183
    }
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 209 210 211
    _missionItems->append(newItem);

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

void MissionController::loadMissionFromFile(void)
{
212
#ifndef __mobile__
213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244
    QString errorString;
    QString filename = QGCFileDialog::getOpenFileName(NULL, "Select Mission File to load");

    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(" ");

        if (!(version.size() == 3 && version[0] == "QGC" && version[1] == "WPL" && version[2] == "120")) {
            errorString = "The mission file is not compatible with the current version of QGroundControl.";
        } else {
            while (!in.atEnd()) {
                MissionItem* item = new MissionItem();

                if (item->load(in)) {
                    _missionItems->append(item);
245
                } else {
246 247
                    errorString = "The mission file is corrupted.";
                    break;
248 249 250
                }
            }
        }
251

252
    }
253 254 255 256 257 258

    if (!errorString.isEmpty()) {
        _missionItems->clear();
    }

    _initAllMissionItems();
259
#endif
260 261
}

262
void MissionController::saveMissionToFile(void)
263
{
264
#ifndef __mobile__
265 266 267 268 269 270
    QString errorString;
    QString filename = QGCFileDialog::getSaveFileName(NULL, "Select file to save mission to");

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

272
    QFile file(filename);
273

274 275 276 277
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
        errorString = file.errorString();
    } else {
        QTextStream out(&file);
278

279
        out << "QGC WPL 120\r\n";   // Version string
280

281 282 283 284 285 286
        for (int i=1; i<_missionItems->count(); i++) {
            qobject_cast<MissionItem*>(_missionItems->get(i))->save(out);
        }
    }

    _missionItems->setDirty(false);
287
#endif
288 289
}

Don Gagne's avatar
Don Gagne committed
290
void MissionController::_calcPrevWaypointValues(bool homePositionValid, double homeAlt, MissionItem* currentItem, MissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
291
{
Don Gagne's avatar
Don Gagne committed
292 293
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  prevCoord =     prevItem->coordinate();
294 295 296 297 298
    bool            distanceOk =    false;

    // Convert to fixed altitudes

    qCDebug(MissionControllerLog) << homePositionValid << homeAlt
Don Gagne's avatar
Don Gagne committed
299 300
                                  << currentItem->relativeAltitude() << currentItem->coordinate().altitude()
                                  << prevItem->relativeAltitude() << prevItem->coordinate().altitude();
301 302 303

    if (homePositionValid) {
        distanceOk = true;
Don Gagne's avatar
Don Gagne committed
304 305
        if (currentItem->relativeAltitude()) {
            currentCoord.setAltitude(homeAlt + currentCoord.altitude());
306
        }
Don Gagne's avatar
Don Gagne committed
307 308
        if (prevItem->relativeAltitude()) {
            prevCoord.setAltitude(homeAlt + prevCoord.altitude());
309 310
        }
    } else {
Don Gagne's avatar
Don Gagne committed
311
        if (prevItem->relativeAltitude() && currentItem->relativeAltitude()) {
312 313 314 315 316 317 318
            distanceOk = true;
        }
    }

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

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
319 320 321
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
322
    } else {
Don Gagne's avatar
Don Gagne committed
323
        *altDifference = 0.0;
324
        *azimuth = 0.0;
Don Gagne's avatar
Don Gagne committed
325
        *distance = -1.0;   // Signals no values
326 327 328
    }
}

329 330 331
void MissionController::_recalcWaypointLines(void)
{
    MissionItem*    lastCoordinateItem =    qobject_cast<MissionItem*>(_missionItems->get(0));
332
    MissionItem*    homeItem =              lastCoordinateItem;
333
    bool            firstCoordinateItem =   true;
334 335 336 337 338 339 340 341
    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.
342

343
    // No values for first item
344
    lastCoordinateItem->setAltDifference(0.0);
345
    lastCoordinateItem->setAzimuth(0.0);
346 347
    lastCoordinateItem->setDistance(-1.0);

348 349 350 351 352
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
    double homePositionAltitude = homeItem->coordinate().altitude();
    minAltSeen = maxAltSeen = homeItem->coordinate().altitude();

353 354 355 356 357
    _waypointLines.clear();

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

358 359 360
        // Assume the worst
        item->setAzimuth(0.0);
        item->setDistance(-1.0);
361

362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384
        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
385
                    }
386 387 388 389 390 391 392 393 394 395 396
                    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()));
397
                }
398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416
                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);
417
            }
418 419
        }
    }
420 421

    emit waypointLinesChanged();
422 423
}

424 425 426 427 428 429 430 431 432 433 434
// 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);
    }
}

435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454
// 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);
        }
    }
}

455 456
void MissionController::_recalcAll(void)
{
457
    _recalcSequence();
458 459 460 461 462 463 464
    _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)
{
465 466 467 468 469 470 471
    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
        homeItem = new MissionItem(this);
472
        homeItem->setSequenceNumber(0);
473 474
        _missionItems->insert(0, homeItem);
    }
Don Gagne's avatar
Don Gagne committed
475 476 477 478 479 480 481 482 483
    homeItem->setHomePositionSpecialCase(true);
    if (_activeVehicle) {
        homeItem->setCoordinate(_activeVehicle->homePosition());
        homeItem->setHomePositionValid(_activeVehicle->homePositionAvailable());
    } else {
        homeItem->setHomePositionValid(false);
    }
    homeItem->setCommand(MAV_CMD_NAV_WAYPOINT);
    homeItem->setFrame(MAV_FRAME_GLOBAL);
484 485 486 487 488
    if (!homeItem->homePositionValid()) {
        QGeoCoordinate homeCoord = homeItem->coordinate();
        homeCoord.setAltitude(0.0);
        homeItem->setCoordinate(homeCoord);
    }
489 490 491 492 493

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

494
    _recalcAll();
495

496
    emit missionItemsChanged();
497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517

    _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);
518
    connect(item, &MissionItem::frameChanged,       this, &MissionController::_itemFrameChanged);
519 520 521 522 523 524
}

void MissionController::_deinitMissionItem(MissionItem* item)
{
    disconnect(item, &MissionItem::commandChanged,     this, &MissionController::_itemCommandChanged);
    disconnect(item, &MissionItem::coordinateChanged,  this, &MissionController::_itemCoordinateChanged);
525
    disconnect(item, &MissionItem::frameChanged,       this, &MissionController::_itemFrameChanged);
526 527 528 529 530 531 532 533
}

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

534 535 536 537 538 539
void MissionController::_itemFrameChanged(int frame)
{
    Q_UNUSED(frame);
    _recalcWaypointLines();
}

540 541 542 543 544
void MissionController::_itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command)
{
    Q_UNUSED(command);;
    _recalcChildItems();
    _recalcWaypointLines();
545 546 547 548
}

void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
{
549 550
    qCDebug(MissionControllerLog) << "_activeVehicleChanged activeVehicle" << activeVehicle;

551 552
    if (_activeVehicle) {
        MissionManager* missionManager = _activeVehicle->missionManager();
553

554
        disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailableFromVehicle);
555 556 557
        disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
        disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged,      this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
558
        _activeVehicle = NULL;
559 560

        // When the active vehicle goes away we toss the editor items
Don Gagne's avatar
Don Gagne committed
561
        _setupMissionItems(false /* loadFromVehicle */, true /* forceLoad */);
562
        _activeVehicleHomePositionAvailableChanged(false);
563
    }
564

Don Gagne's avatar
Don Gagne committed
565 566 567 568 569 570 571 572 573 574 575 576
    _setupActiveVehicle(activeVehicle, false /* forceLoadFromVehicle */);
}

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

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

577
    _activeVehicle = activeVehicle;
578

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

582
        connect(missionManager, &MissionManager::newMissionItemsAvailable,  this, &MissionController::_newMissionItemsAvailableFromVehicle);
583
        connect(missionManager, &MissionManager::inProgressChanged,         this, &MissionController::_inProgressChanged);
584 585 586
        connect(_activeVehicle, &Vehicle::homePositionAvailableChanged,     this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);

587
        _firstItemsFromVehicle = true;
Don Gagne's avatar
Don Gagne committed
588
        _setupMissionItems(true /* fromVehicle */, forceLoadFromVehicle);
589 590 591 592 593 594 595 596 597

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

void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
    _liveHomePositionAvailable = homePositionAvailable;
Don Gagne's avatar
Don Gagne committed
598
    qobject_cast<MissionItem*>(_missionItems->get(0))->setHomePositionValid(homePositionAvailable);
599
    emit liveHomePositionAvailableChanged(_liveHomePositionAvailable);
600
    _recalcWaypointLines();
601 602 603 604 605
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
    _liveHomePosition = homePosition;
Don Gagne's avatar
Don Gagne committed
606
    qobject_cast<MissionItem*>(_missionItems->get(0))->setCoordinate(_liveHomePosition);
607
    emit liveHomePositionChanged(_liveHomePosition);
608
    _recalcWaypointLines();
609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639
}

void MissionController::deleteCurrentMissionItem(void)
{
    for (int i=0; i<_missionItems->count(); i++) {
        MissionItem* item =  qobject_cast<MissionItem*>(_missionItems->get(i));
        if (item->isCurrentItem() && i != 0) {
            removeMissionItem(i);
            return;
        }
    }
}

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) {
640
        Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658

        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);
659 660
    }
}
661

662
void MissionController::_inProgressChanged(bool inProgress)
663
{
664 665 666 667
    if (!inProgress && _queuedSend) {
        _autoSyncSend();
    }
}
668

669 670 671
QmlObjectListModel* MissionController::missionItems(void)
{
    return _missionItems;
672
}
673

674
bool MissionController::_findLastAltitude(double* lastAltitude)
675
{
676 677
    bool found = false;
    double foundAltitude;
678 679 680 681

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

682
        if (item->specifiesCoordinate() && !item->standaloneCoordinate()) {
683 684
            foundAltitude = item->param7();
            found = true;
685 686 687
        }
    }

688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713
    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;
714
}