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()
{
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 134
    } else {
        _missionItems = missionManager->copyMissionItems();
135
        qCDebug(MissionControllerLog) << "loading from vehicle count"<< _missionItems->count();
136 137 138 139 140
    }

    _initAllMissionItems();
}

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

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

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

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

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

        if (_findLastAcceptanceRadius(&lastValue)) {
            newItem->setParam2(lastValue);
        }
        if (_findLastAltitude(&lastValue)) {
            newItem->setParam7(lastValue);
        }
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
    _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);
    }
}

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

    _initAllMissionItems();
}

219 220
void MissionController::loadMissionFromFile(void)
{
221
#ifndef __mobile__
222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253
    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);
254
                } else {
255 256
                    errorString = "The mission file is corrupted.";
                    break;
257 258 259
                }
            }
        }
260

261
    }
262 263 264 265 266 267

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

    _initAllMissionItems();
268
#endif
269 270
}

271
void MissionController::saveMissionToFile(void)
272
{
273
#ifndef __mobile__
274 275 276 277 278 279
    QString errorString;
    QString filename = QGCFileDialog::getSaveFileName(NULL, "Select file to save mission to");

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

281
    QFile file(filename);
282

283 284 285 286
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
        errorString = file.errorString();
    } else {
        QTextStream out(&file);
287

288
        out << "QGC WPL 120\r\n";   // Version string
289

290 291 292 293 294 295
        for (int i=1; i<_missionItems->count(); i++) {
            qobject_cast<MissionItem*>(_missionItems->get(i))->save(out);
        }
    }

    _missionItems->setDirty(false);
296
#endif
297 298
}

Don Gagne's avatar
Don Gagne committed
299
void MissionController::_calcPrevWaypointValues(bool homePositionValid, double homeAlt, MissionItem* currentItem, MissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
300
{
Don Gagne's avatar
Don Gagne committed
301 302
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  prevCoord =     prevItem->coordinate();
303 304 305 306 307
    bool            distanceOk =    false;

    // Convert to fixed altitudes

    qCDebug(MissionControllerLog) << homePositionValid << homeAlt
Don Gagne's avatar
Don Gagne committed
308 309
                                  << currentItem->relativeAltitude() << currentItem->coordinate().altitude()
                                  << prevItem->relativeAltitude() << prevItem->coordinate().altitude();
310 311 312

    if (homePositionValid) {
        distanceOk = true;
Don Gagne's avatar
Don Gagne committed
313 314
        if (currentItem->relativeAltitude()) {
            currentCoord.setAltitude(homeAlt + currentCoord.altitude());
315
        }
Don Gagne's avatar
Don Gagne committed
316 317
        if (prevItem->relativeAltitude()) {
            prevCoord.setAltitude(homeAlt + prevCoord.altitude());
318 319
        }
    } else {
Don Gagne's avatar
Don Gagne committed
320
        if (prevItem->relativeAltitude() && currentItem->relativeAltitude()) {
321 322 323 324 325 326 327
            distanceOk = true;
        }
    }

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

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
328 329 330
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
331
    } else {
Don Gagne's avatar
Don Gagne committed
332
        *altDifference = 0.0;
333
        *azimuth = 0.0;
Don Gagne's avatar
Don Gagne committed
334
        *distance = -1.0;   // Signals no values
335 336 337
    }
}

338 339 340
void MissionController::_recalcWaypointLines(void)
{
    MissionItem*    lastCoordinateItem =    qobject_cast<MissionItem*>(_missionItems->get(0));
341
    MissionItem*    homeItem =              lastCoordinateItem;
342
    bool            firstCoordinateItem =   true;
343 344 345 346 347 348 349 350
    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.
351

352
    // No values for first item
353
    lastCoordinateItem->setAltDifference(0.0);
354
    lastCoordinateItem->setAzimuth(0.0);
355 356
    lastCoordinateItem->setDistance(-1.0);

357 358 359 360 361
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
    double homePositionAltitude = homeItem->coordinate().altitude();
    minAltSeen = maxAltSeen = homeItem->coordinate().altitude();

362 363 364 365 366
    _waypointLines.clear();

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

367 368 369
        // Assume the worst
        item->setAzimuth(0.0);
        item->setDistance(-1.0);
370

371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393
        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
394
                    }
395 396 397 398 399 400 401 402 403 404 405
                    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()));
406
                }
407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425
                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);
426
            }
427 428
        }
    }
429 430

    emit waypointLinesChanged();
431 432
}

433 434 435 436 437 438 439 440 441 442 443
// 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);
    }
}

444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463
// 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);
        }
    }
}

464 465
void MissionController::_recalcAll(void)
{
466
    _recalcSequence();
467 468 469 470 471 472 473
    _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)
{
474 475 476 477 478 479 480
    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);
481
        homeItem->setSequenceNumber(0);
482 483
        _missionItems->insert(0, homeItem);
    }
Don Gagne's avatar
Don Gagne committed
484 485 486
    homeItem->setHomePositionSpecialCase(true);
    if (_activeVehicle) {
        homeItem->setHomePositionValid(_activeVehicle->homePositionAvailable());
DonLakeFlyer's avatar
DonLakeFlyer committed
487 488 489
        if (homeItem->homePositionValid()) {
            homeItem->setCoordinate(_activeVehicle->homePosition());
        }
Don Gagne's avatar
Don Gagne committed
490 491 492 493 494
    } else {
        homeItem->setHomePositionValid(false);
    }
    homeItem->setCommand(MAV_CMD_NAV_WAYPOINT);
    homeItem->setFrame(MAV_FRAME_GLOBAL);
495
    if (!homeItem->homePositionValid()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
496 497
        // Set a bogus home position, the important value is 0.0 Altitude
        homeItem->setCoordinate(QGeoCoordinate(37.803784, -122.462276, 0.0));
498
    }
499

DonLakeFlyer's avatar
DonLakeFlyer committed
500 501
    qDebug() << "home item" << homeItem->homePositionValid() << homeItem->coordinate();

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

506
    _recalcAll();
507

508
    emit missionItemsChanged();
509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529

    _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);
530
    connect(item, &MissionItem::frameChanged,       this, &MissionController::_itemFrameChanged);
531 532 533 534 535 536
}

void MissionController::_deinitMissionItem(MissionItem* item)
{
    disconnect(item, &MissionItem::commandChanged,     this, &MissionController::_itemCommandChanged);
    disconnect(item, &MissionItem::coordinateChanged,  this, &MissionController::_itemCoordinateChanged);
537
    disconnect(item, &MissionItem::frameChanged,       this, &MissionController::_itemFrameChanged);
538 539 540 541 542 543 544 545
}

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

546 547 548 549 550 551
void MissionController::_itemFrameChanged(int frame)
{
    Q_UNUSED(frame);
    _recalcWaypointLines();
}

552 553 554 555 556
void MissionController::_itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command)
{
    Q_UNUSED(command);;
    _recalcChildItems();
    _recalcWaypointLines();
557 558 559 560
}

void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
{
561 562
    qCDebug(MissionControllerLog) << "_activeVehicleChanged activeVehicle" << activeVehicle;

563 564
    if (_activeVehicle) {
        MissionManager* missionManager = _activeVehicle->missionManager();
565

566
        disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailableFromVehicle);
567 568 569
        disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
        disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged,      this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
570
        _activeVehicle = NULL;
571 572

        // When the active vehicle goes away we toss the editor items
Don Gagne's avatar
Don Gagne committed
573
        _setupMissionItems(false /* loadFromVehicle */, true /* forceLoad */);
574
        _activeVehicleHomePositionAvailableChanged(false);
575
    }
576

Don Gagne's avatar
Don Gagne committed
577 578 579 580 581 582 583 584 585 586 587 588
    _setupActiveVehicle(activeVehicle, false /* forceLoadFromVehicle */);
}

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

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

589
    _activeVehicle = activeVehicle;
590

591 592
    if (_activeVehicle) {
        MissionManager* missionManager = activeVehicle->missionManager();
593

594
        connect(missionManager, &MissionManager::newMissionItemsAvailable,  this, &MissionController::_newMissionItemsAvailableFromVehicle);
595
        connect(missionManager, &MissionManager::inProgressChanged,         this, &MissionController::_inProgressChanged);
596 597 598
        connect(_activeVehicle, &Vehicle::homePositionAvailableChanged,     this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);

599
        _firstItemsFromVehicle = true;
Don Gagne's avatar
Don Gagne committed
600
        _setupMissionItems(true /* fromVehicle */, forceLoadFromVehicle);
601 602 603 604 605 606 607 608 609

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

void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
    _liveHomePositionAvailable = homePositionAvailable;
Don Gagne's avatar
Don Gagne committed
610
    qobject_cast<MissionItem*>(_missionItems->get(0))->setHomePositionValid(homePositionAvailable);
611
    emit liveHomePositionAvailableChanged(_liveHomePositionAvailable);
612
    _recalcWaypointLines();
613 614 615 616 617
}

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

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

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

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

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

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

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

683
        if (item->specifiesCoordinate() && !item->standaloneCoordinate()) {
684 685
            foundAltitude = item->param7();
            found = true;
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 714
    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;
715
}