MissionController.cc 20.6 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
    , _missionItems(NULL)
40
    , _canEdit(true)
41
    , _activeVehicle(NULL)
42 43
    , _liveHomePositionAvailable(false)
    , _autoSync(false)
44
    , _firstItemsFromVehicle(false)
45 46
    , _missionItemsRequested(false)
    , _queuedSend(false)
47
{
48 49 50 51 52

}

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

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

63 64
    _editMode = editMode;

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

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

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

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

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

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

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

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

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

124 125
    _missionItemsRequested = false;

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

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

    _initAllMissionItems();
}

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

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

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

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

164 165 166 167 168
int MissionController::addMissionItem(QGeoCoordinate coordinate)
{
    if (!_canEdit) {
        qWarning() << "addMissionItem called with _canEdit == false";
    }
169

170 171 172 173 174 175 176 177 178 179 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 241 242 243 244 245 246 247
    // Coordinate will come through without altitude
    coordinate.setAltitude(MissionItem::defaultAltitude);

    MissionItem * newItem = new MissionItem(this, _missionItems->count(), coordinate, MAV_CMD_NAV_WAYPOINT);
    _initMissionItem(newItem);
    if (_missionItems->count() == 1) {
        newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
    }
    _missionItems->append(newItem);

    _recalcAll();

    return _missionItems->count() - 1;
}

void MissionController::removeMissionItem(int index)
{
    if (!_canEdit) {
        qWarning() << "addMissionItem called with _canEdit == false";
        return;
    }

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

    _canEdit = true;

    // 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);

                    if (!item->canEdit()) {
                        _canEdit = false;
248
                    }
249
                } else {
250 251
                    errorString = "The mission file is corrupted.";
                    break;
252 253 254
                }
            }
        }
255

256
    }
257 258 259 260 261 262

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

    _initAllMissionItems();
263 264
}

265
void MissionController::saveMissionToFile(void)
266
{
267 268 269 270 271 272
    QString errorString;
    QString filename = QGCFileDialog::getSaveFileName(NULL, "Select file to save mission to");

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

274
    QFile file(filename);
275

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

281
        out << "QGC WPL 120\r\n";   // Version string
282

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

    _missionItems->setDirty(false);
}

291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325
double MissionController::_calcDistance(bool homePositionValid, double homeAlt, MissionItem* item1, MissionItem* item2)
{
    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) {
        return item1->coordinate().distanceTo(item2->coordinate());
    } else {
        return -1.0;
    }
}

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

340 341 342
    // No distance for first item
    lastCoordinateItem->setDistance(-1.0);

343 344 345 346 347
    _waypointLines.clear();

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

348 349
        item->setDistance(-1.0);    // Assume the worst

350 351 352 353
        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
354
                    if (homePositionValid) {
355
                        _waypointLines.append(new CoordinateVector(homeItem->coordinate(), item->coordinate()));
356
                        item->setDistance(_calcDistance(homePositionValid, homeAlt, homeItem, item));
357 358 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()) {
                // Subsequent coordinate items link to last coordinate item. If the last coordinate item
                // is an invalid home position we skip the line
365
                item->setDistance(_calcDistance(homePositionValid, homeAlt, lastCoordinateItem, item));
366
                _waypointLines.append(new CoordinateVector(lastCoordinateItem->coordinate(), item->coordinate()));
367
            }
368
            lastCoordinateItem = item;
369 370
        }
    }
371 372

    emit waypointLinesChanged();
373 374
}

375 376 377 378 379 380 381 382 383 384 385
// 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);
    }
}

386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405
// 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);
        }
    }
}

406 407
void MissionController::_recalcAll(void)
{
408
    _recalcSequence();
409 410 411 412 413 414 415
    _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)
{
416 417 418 419 420 421 422 423 424 425 426 427
    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);
        homeItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
        _missionItems->insert(0, homeItem);
    }
428
    homeItem->setHomePositionValid(false);
429 430 431 432 433

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

434
    _recalcAll();
435

436
    emit missionItemsChanged();
437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458
    emit canEditChanged(_canEdit);

    _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);
459
    connect(item, &MissionItem::frameChanged,       this, &MissionController::_itemFrameChanged);
460 461 462 463 464 465
}

void MissionController::_deinitMissionItem(MissionItem* item)
{
    disconnect(item, &MissionItem::commandChanged,     this, &MissionController::_itemCommandChanged);
    disconnect(item, &MissionItem::coordinateChanged,  this, &MissionController::_itemCoordinateChanged);
466
    disconnect(item, &MissionItem::frameChanged,       this, &MissionController::_itemFrameChanged);
467 468 469 470 471 472 473 474
}

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

475 476 477 478 479 480
void MissionController::_itemFrameChanged(int frame)
{
    Q_UNUSED(frame);
    _recalcWaypointLines();
}

481 482 483 484 485
void MissionController::_itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command)
{
    Q_UNUSED(command);;
    _recalcChildItems();
    _recalcWaypointLines();
486 487 488 489
}

void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
{
490 491
    qCDebug(MissionControllerLog) << "_activeVehicleChanged activeVehicle" << activeVehicle;

492 493
    if (_activeVehicle) {
        MissionManager* missionManager = _activeVehicle->missionManager();
494

495
        disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailableFromVehicle);
496 497 498
        disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
        disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged,      this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
499
        _activeVehicle = NULL;
500 501

        // When the active vehicle goes away we toss the editor items
Don Gagne's avatar
Don Gagne committed
502
        _setupMissionItems(false /* loadFromVehicle */, true /* forceLoad */);
503
        _activeVehicleHomePositionAvailableChanged(false);
504
    }
505

Don Gagne's avatar
Don Gagne committed
506 507 508 509 510 511 512 513 514 515 516 517
    _setupActiveVehicle(activeVehicle, false /* forceLoadFromVehicle */);
}

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

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

518
    _activeVehicle = activeVehicle;
519

520 521
    if (_activeVehicle) {
        MissionManager* missionManager = activeVehicle->missionManager();
522

523
        connect(missionManager, &MissionManager::newMissionItemsAvailable,  this, &MissionController::_newMissionItemsAvailableFromVehicle);
524 525 526 527
        connect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
        connect(_activeVehicle, &Vehicle::homePositionAvailableChanged,     this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);

528
        _firstItemsFromVehicle = true;
Don Gagne's avatar
Don Gagne committed
529
        _setupMissionItems(true /* fromVehicle */, forceLoadFromVehicle);
530 531 532 533 534 535 536 537 538

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

void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
    _liveHomePositionAvailable = homePositionAvailable;
Don Gagne's avatar
Don Gagne committed
539
    qobject_cast<MissionItem*>(_missionItems->get(0))->setHomePositionValid(homePositionAvailable);
540 541 542 543 544 545
    emit liveHomePositionAvailableChanged(_liveHomePositionAvailable);
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
    _liveHomePosition = homePosition;
Don Gagne's avatar
Don Gagne committed
546
    qobject_cast<MissionItem*>(_missionItems->get(0))->setCoordinate(_liveHomePosition);
547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578
    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) {
579
        Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597

        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);
598 599
    }
}
600

601
void MissionController::_inProgressChanged(bool inProgress)
602
{
603 604 605 606
    if (!inProgress && _queuedSend) {
        _autoSyncSend();
    }
}
607

608 609 610
QmlObjectListModel* MissionController::missionItems(void)
{
    return _missionItems;
611
}