MissionController.cc 22.1 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
/*=====================================================================

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"
27
#include "QGCFileDialog.h"
28
#include "CoordinateVector.h"
29 30 31
#include "QGCMessageBox.h"
#include "FirmwarePlugin.h"

32 33
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

34
const char* MissionController::_settingsGroup = "MissionController";
35 36 37

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

}

MissionController::~MissionController()
{
52 53 54
    // Start with empty list
    _missionItems = new QmlObjectListModel(this);
    _initAllMissionItems();
55 56 57 58
}

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

61 62
    _editMode = editMode;

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

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

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

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

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

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

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

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

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

122 123
    _missionItemsRequested = false;

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

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

    _initAllMissionItems();
}

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

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

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

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

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

        if (_findLastAcceptanceRadius(&lastValue)) {
            newItem->setParam2(lastValue);
        }
        if (_findLastAltitude(&lastValue)) {
            newItem->setParam7(lastValue);
        }
180
    }
181 182 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 212 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
    _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)
{
    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);
241
                } else {
242 243
                    errorString = "The mission file is corrupted.";
                    break;
244 245 246
                }
            }
        }
247

248
    }
249 250 251 252 253 254

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

    _initAllMissionItems();
255 256
}

257
void MissionController::saveMissionToFile(void)
258
{
259 260 261 262 263 264
    QString errorString;
    QString filename = QGCFileDialog::getSaveFileName(NULL, "Select file to save mission to");

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

266
    QFile file(filename);
267

268 269 270 271
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
        errorString = file.errorString();
    } else {
        QTextStream out(&file);
272

273
        out << "QGC WPL 120\r\n";   // Version string
274

275 276 277 278 279 280 281 282
        for (int i=1; i<_missionItems->count(); i++) {
            qobject_cast<MissionItem*>(_missionItems->get(i))->save(out);
        }
    }

    _missionItems->setDirty(false);
}

283
void MissionController::_calcPrevWaypointValues(bool homePositionValid, double homeAlt, MissionItem* item1, MissionItem* item2, double* azimuth, double* distance)
284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311
{
    QGeoCoordinate  coord1 =        item1->coordinate();
    QGeoCoordinate  coord2 =        item2->coordinate();
    bool            distanceOk =    false;

    // Convert to fixed altitudes

    qCDebug(MissionControllerLog) << homePositionValid << homeAlt
                                  << item1->relativeAltitude() << item1->coordinate().altitude()
                                  << item2->relativeAltitude() << item2->coordinate().altitude();

    if (homePositionValid) {
        distanceOk = true;
        if (item1->relativeAltitude()) {
            coord1.setAltitude(homeAlt + coord1.altitude());
        }
        if (item2->relativeAltitude()) {
            coord2.setAltitude(homeAlt + coord2.altitude());
        }
    } else {
        if (item1->relativeAltitude() && item2->relativeAltitude()) {
            distanceOk = true;
        }
    }

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

    if (distanceOk) {
312 313
        *distance = item1->coordinate().distanceTo(item2->coordinate());
        *azimuth = item1->coordinate().azimuthTo(item2->coordinate());
314
    } else {
315 316
        *azimuth = 0.0;
        *distance = -1.0;
317 318 319
    }
}

320 321 322
void MissionController::_recalcWaypointLines(void)
{
    MissionItem*    lastCoordinateItem =    qobject_cast<MissionItem*>(_missionItems->get(0));
323
    MissionItem*    homeItem =              lastCoordinateItem;
324
    bool            firstCoordinateItem =   true;
325 326 327 328 329 330 331 332
    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.
333

334 335
    // No values for first item
    lastCoordinateItem->setAzimuth(0.0);
336 337
    lastCoordinateItem->setDistance(-1.0);

338 339 340 341 342
    _waypointLines.clear();

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

343 344 345
        // Assume the worst
        item->setAzimuth(0.0);
        item->setDistance(-1.0);
346

347 348 349 350
        if (item->specifiesCoordinate()) {
            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
351
                    if (homePositionValid) {
352 353
                        double azimuth, distance;

354
                        _waypointLines.append(new CoordinateVector(homeItem->coordinate(), item->coordinate()));
355 356 357 358
                        _calcPrevWaypointValues(homePositionValid, homeAlt, homeItem, item, &azimuth, &distance);
                        qDebug() << azimuth << distance;
                        item->setAzimuth(azimuth);
                        item->setDistance(distance);
359 360 361 362 363 364
                    }
                } else {
                    // First coordiante is not a takeoff command, it does not link backwards to anything
                }
                firstCoordinateItem = false;
            } else if (!lastCoordinateItem->homePosition() || lastCoordinateItem->homePositionValid()) {
365 366
                double azimuth, distance;

367 368
                // Subsequent coordinate items link to last coordinate item. If the last coordinate item
                // is an invalid home position we skip the line
369 370 371 372
                _calcPrevWaypointValues(homePositionValid, homeAlt, lastCoordinateItem, item, &azimuth, &distance);
                qDebug() << azimuth << distance;
                item->setAzimuth(azimuth);
                item->setDistance(distance);
373
                _waypointLines.append(new CoordinateVector(lastCoordinateItem->coordinate(), item->coordinate()));
374
            }
375
            lastCoordinateItem = item;
376 377
        }
    }
378 379

    emit waypointLinesChanged();
380 381
}

382 383 384 385 386 387 388 389 390 391 392
// 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);
    }
}

393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412
// 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);
        }
    }
}

413 414
void MissionController::_recalcAll(void)
{
415
    _recalcSequence();
416 417 418 419 420 421 422
    _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)
{
423 424 425 426 427 428 429 430 431
    MissionItem* homeItem = NULL;

    if (_activeVehicle && _activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() && _missionItems->count() != 0) {
        homeItem = qobject_cast<MissionItem*>(_missionItems->get(0));
        homeItem->setHomePositionSpecialCase(true);
    } else {
        // Add the home position item to the front
        homeItem = new MissionItem(this);
        homeItem->setHomePositionSpecialCase(true);
432 433 434
        homeItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_LAST);
        homeItem->setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
        homeItem->setSequenceNumber(0);
435 436
        _missionItems->insert(0, homeItem);
    }
437
    homeItem->setHomePositionValid(false);
438 439 440 441 442

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

443
    _recalcAll();
444

445
    emit missionItemsChanged();
446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466

    _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);
467
    connect(item, &MissionItem::frameChanged,       this, &MissionController::_itemFrameChanged);
468 469 470 471 472 473
}

void MissionController::_deinitMissionItem(MissionItem* item)
{
    disconnect(item, &MissionItem::commandChanged,     this, &MissionController::_itemCommandChanged);
    disconnect(item, &MissionItem::coordinateChanged,  this, &MissionController::_itemCoordinateChanged);
474
    disconnect(item, &MissionItem::frameChanged,       this, &MissionController::_itemFrameChanged);
475 476 477 478 479 480 481 482
}

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

483 484 485 486 487 488
void MissionController::_itemFrameChanged(int frame)
{
    Q_UNUSED(frame);
    _recalcWaypointLines();
}

489 490 491 492 493
void MissionController::_itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command)
{
    Q_UNUSED(command);;
    _recalcChildItems();
    _recalcWaypointLines();
494 495 496 497
}

void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
{
498 499
    qCDebug(MissionControllerLog) << "_activeVehicleChanged activeVehicle" << activeVehicle;

500 501
    if (_activeVehicle) {
        MissionManager* missionManager = _activeVehicle->missionManager();
502

503
        disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailableFromVehicle);
504 505 506
        disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
        disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged,      this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
507
        _activeVehicle = NULL;
508 509

        // When the active vehicle goes away we toss the editor items
Don Gagne's avatar
Don Gagne committed
510
        _setupMissionItems(false /* loadFromVehicle */, true /* forceLoad */);
511
        _activeVehicleHomePositionAvailableChanged(false);
512
    }
513

Don Gagne's avatar
Don Gagne committed
514 515 516 517 518 519 520 521 522 523 524 525
    _setupActiveVehicle(activeVehicle, false /* forceLoadFromVehicle */);
}

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

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

526
    _activeVehicle = activeVehicle;
527

528 529
    if (_activeVehicle) {
        MissionManager* missionManager = activeVehicle->missionManager();
530

531
        connect(missionManager, &MissionManager::newMissionItemsAvailable,  this, &MissionController::_newMissionItemsAvailableFromVehicle);
532 533 534 535
        connect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
        connect(_activeVehicle, &Vehicle::homePositionAvailableChanged,     this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);

536
        _firstItemsFromVehicle = true;
Don Gagne's avatar
Don Gagne committed
537
        _setupMissionItems(true /* fromVehicle */, forceLoadFromVehicle);
538 539 540 541 542 543 544 545 546

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

void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
    _liveHomePositionAvailable = homePositionAvailable;
Don Gagne's avatar
Don Gagne committed
547
    qobject_cast<MissionItem*>(_missionItems->get(0))->setHomePositionValid(homePositionAvailable);
548 549 550 551 552 553
    emit liveHomePositionAvailableChanged(_liveHomePositionAvailable);
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
    _liveHomePosition = homePosition;
Don Gagne's avatar
Don Gagne committed
554
    qobject_cast<MissionItem*>(_missionItems->get(0))->setCoordinate(_liveHomePosition);
555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586
    emit liveHomePositionChanged(_liveHomePosition);
}

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) {
587
        Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605

        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);
606 607
    }
}
608

609
void MissionController::_inProgressChanged(bool inProgress)
610
{
611 612 613 614
    if (!inProgress && _queuedSend) {
        _autoSyncSend();
    }
}
615

616 617 618
QmlObjectListModel* MissionController::missionItems(void)
{
    return _missionItems;
619
}
620

621
bool MissionController::_findLastAltitude(double* lastAltitude)
622
{
623 624
    bool found = false;
    double foundAltitude;
625 626 627 628 629

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

        if (item->specifiesCoordinate()) {
630 631
            foundAltitude = item->param7();
            found = true;
632 633 634
        }
    }

635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660
    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;
661
}