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

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 32
#include "QGCMessageBox.h"
#include "FirmwarePlugin.h"

const char* MissionController::_settingsGroup = "MissionController";
33 34 35

MissionController::MissionController(QObject *parent)
    : QObject(parent)
36
    , _editMode(false)
37
    , _missionItems(NULL)
38
    , _canEdit(true)
39
    , _activeVehicle(NULL)
40 41 42 43 44
    , _liveHomePositionAvailable(false)
    , _autoSync(false)
    , _firstMissionItemSync(false)
    , _missionItemsRequested(false)
    , _queuedSend(false)
45
{
46 47 48 49 50 51 52 53 54 55 56

}

MissionController::~MissionController()
{
}

void MissionController::start(bool editMode)
{
    _editMode = editMode;

57
    MultiVehicleManager* multiVehicleMgr = MultiVehicleManager::instance();
58

59
    connect(multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &MissionController::_activeVehicleChanged);
60

61 62 63 64
    Vehicle* activeVehicle = multiVehicleMgr->activeVehicle();
    if (activeVehicle) {
        _activeVehicleChanged(activeVehicle);
    } else {
65
        _missionItemsRequested = true;
66 67 68 69 70 71
        _newMissionItemsAvailable();
    }
}

void MissionController::_newMissionItemsAvailable(void)
{
72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96
    if (_editMode) {
        if (_firstMissionItemSync) {
            // This is the first time the vehicle is seeing items. We have to be careful of transitioning from offline
            // to online.

            _firstMissionItemSync = false;
            if (_missionItems && _missionItems->count() > 1) {
                QGCMessageBox::StandardButton button = QGCMessageBox::warning("Mission Editing",
                                                                              "The vehicle has sent a new set of Mission Items. "
                                                                              "Do you want to discard your current set of unsaved items and use the ones from the vehicle instead?",
                                                                              QGCMessageBox::Yes | QGCMessageBox::No,
                                                                              QGCMessageBox::No);
                if (button == QGCMessageBox::No) {
                    return;
                }
            }
        } 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.
            return;
        }
    }

    _missionItemsRequested = false;

97
    if (_missionItems) {
98
        _deinitAllMissionItems();
99 100
        _missionItems->deleteLater();
    }
101

102
    MissionManager* missionManager = NULL;
103 104
    if (_activeVehicle) {
        missionManager = _activeVehicle->missionManager();
105 106 107
    }

    if (!missionManager || missionManager->inProgress()) {
108
        _canEdit = true;
109 110
        _missionItems = new QmlObjectListModel(this);
    } else {
111
        _canEdit = missionManager->canEdit();
112 113 114 115 116 117
        _missionItems = missionManager->copyMissionItems();
    }

    _initAllMissionItems();
}

118
void MissionController::getMissionItems(void)
119
{
120
    Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle();
121

122 123 124 125 126 127 128 129 130 131 132
    if (activeVehicle) {
        _missionItemsRequested = true;
        MissionManager* missionManager = activeVehicle->missionManager();
        connect(missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailable);
        activeVehicle->missionManager()->requestMissionItems();
    }
}

void MissionController::sendMissionItems(void)
{
    Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle();
133

134 135 136 137 138
    if (activeVehicle) {
        activeVehicle->missionManager()->writeMissionItems(*_missionItems);
        _missionItems->setDirty(false);
    }
}
139

140 141 142 143 144
int MissionController::addMissionItem(QGeoCoordinate coordinate)
{
    if (!_canEdit) {
        qWarning() << "addMissionItem called with _canEdit == false";
    }
145

146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 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
    // 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;
224
                    }
225
                } else {
226 227
                    errorString = "The mission file is corrupted.";
                    break;
228 229 230
                }
            }
        }
231

232
    }
233 234 235 236 237 238

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

    _initAllMissionItems();
239 240
}

241
void MissionController::saveMissionToFile(void)
242
{
243 244 245 246 247 248
    QString errorString;
    QString filename = QGCFileDialog::getSaveFileName(NULL, "Select file to save mission to");

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

250
    QFile file(filename);
251

252 253 254 255
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
        errorString = file.errorString();
    } else {
        QTextStream out(&file);
256

257
        out << "QGC WPL 120\r\n";   // Version string
258

259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293
        for (int i=1; i<_missionItems->count(); i++) {
            qobject_cast<MissionItem*>(_missionItems->get(i))->save(out);
        }
    }

    _missionItems->setDirty(false);
}

void MissionController::_recalcWaypointLines(void)
{
    MissionItem*    lastCoordinateItem =    qobject_cast<MissionItem*>(_missionItems->get(0));
    bool            firstCoordinateItem =   true;

    _waypointLines.clear();

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

        if (item->specifiesCoordinate()) {
            if (firstCoordinateItem) {
                if (item->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) {
                    MissionItem* homeItem = qobject_cast<MissionItem*>(_missionItems->get(0));

                    // The first coordinate we hit is a takeoff command so link back to home position if valid
                    if (homeItem->homePositionValid()) {
                        _waypointLines.append(new CoordinateVector(qobject_cast<MissionItem*>(_missionItems->get(0))->coordinate(), item->coordinate()));
                    }
                } 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
                _waypointLines.append(new CoordinateVector(lastCoordinateItem->coordinate(), item->coordinate()));
294
            }
295
            lastCoordinateItem = item;
296 297
        }
    }
298 299

    emit waypointLinesChanged();
300 301
}

302 303 304 305 306 307 308 309 310 311 312
// 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);
    }
}

313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332
// 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);
        }
    }
}

333 334
void MissionController::_recalcAll(void)
{
335
    _recalcSequence();
336 337 338 339 340 341 342
    _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)
{
343 344 345 346 347 348 349 350 351 352 353 354
    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);
    }
355
    homeItem->setHomePositionValid(false);
356 357 358 359 360

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

361
    _recalcAll();
362

363
    emit missionItemsChanged();
364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404
    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);
}

void MissionController::_deinitMissionItem(MissionItem* item)
{
    disconnect(item, &MissionItem::commandChanged,     this, &MissionController::_itemCommandChanged);
    disconnect(item, &MissionItem::coordinateChanged,  this, &MissionController::_itemCoordinateChanged);
}

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

void MissionController::_itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command)
{
    Q_UNUSED(command);;
    _recalcChildItems();
    _recalcWaypointLines();
405 406 407 408 409 410
}

void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
{
    if (_activeVehicle) {
        MissionManager* missionManager = _activeVehicle->missionManager();
411

412
        disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailable);
413 414 415
        disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
        disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged,      this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
416
        _activeVehicle = NULL;
417 418
        _newMissionItemsAvailable();
        _activeVehicleHomePositionAvailableChanged(false);
419
    }
420

421
    _activeVehicle = activeVehicle;
422

423 424
    if (_activeVehicle) {
        MissionManager* missionManager = activeVehicle->missionManager();
425

426
        connect(missionManager, &MissionManager::newMissionItemsAvailable,  this, &MissionController::_newMissionItemsAvailable);
427 428 429 430 431 432 433 434 435 436 437 438 439
        connect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
        connect(_activeVehicle, &Vehicle::homePositionAvailableChanged,     this, &MissionController::_activeVehicleHomePositionAvailableChanged);
        connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);

        if (missionManager->inProgress()) {
            // Vehicle is still in process of requesting mission items
            _firstMissionItemSync = true;
        } else {
            // Vehicle already has mission items
            _firstMissionItemSync = false;
        }

        _missionItemsRequested = true;
440
        _newMissionItemsAvailable();
441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506

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

void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
    _liveHomePositionAvailable = homePositionAvailable;
    emit liveHomePositionAvailableChanged(_liveHomePositionAvailable);
}

void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
    _liveHomePosition = homePosition;
    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) {
        Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle();

        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);
507 508
    }
}
509

510
void MissionController::_inProgressChanged(bool inProgress)
511
{
512 513 514 515
    if (!inProgress && _queuedSend) {
        _autoSyncSend();
    }
}
516

517 518 519
QmlObjectListModel* MissionController::missionItems(void)
{
    return _missionItems;
520
}