MainToolBar.cc 24.2 KB
Newer Older
dogmaphobic's avatar
dogmaphobic committed
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 28 29 30 31 32 33
/*=====================================================================

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/>.

======================================================================*/

/**
 * @file
 *   @brief QGC Main Tool Bar
 *   @author Gus Grubba <mavlink@grubba.com>
 */

#include <QQmlContext>
#include <QQmlEngine>

#include "MainToolBar.h"
34
#include "MainWindow.h"
dogmaphobic's avatar
dogmaphobic committed
35 36
#include "UASMessageHandler.h"
#include "UASMessageView.h"
dogmaphobic's avatar
dogmaphobic committed
37
#include "QGCFlightDisplay.h"
dogmaphobic's avatar
dogmaphobic committed
38

Don Gagne's avatar
Don Gagne committed
39 40 41
MainToolBar::MainToolBar(QWidget* parent)
    : QGCQmlWidgetHolder(parent)
    , _mav(NULL)
dogmaphobic's avatar
dogmaphobic committed
42 43 44 45 46 47 48 49 50 51
    , _toolBar(NULL)
    , _currentView(ViewNone)
    , _batteryVoltage(0.0)
    , _batteryPercent(0.0)
    , _connectionCount(0)
    , _systemArmed(false)
    , _currentHeartbeatTimeout(0)
    , _waypointDistance(0.0)
    , _currentWaypoint(0)
    , _currentMessageCount(0)
dogmaphobic's avatar
dogmaphobic committed
52
    , _messageCount(0)
dogmaphobic's avatar
dogmaphobic committed
53 54 55 56 57
    , _currentErrorCount(0)
    , _currentWarningCount(0)
    , _currentNormalCount(0)
    , _currentMessageType(MessageNone)
    , _satelliteCount(-1)
dogmaphobic's avatar
dogmaphobic committed
58
    , _satelliteLock(0)
59 60 61
    , _showGPS(true)
    , _showMav(true)
    , _showMessages(true)
62
    , _showRSSI(true)
63
    , _showBattery(true)
64
    , _progressBarValue(0.0f)
65 66 67
    , _remoteRSSI(0)
    , _telemetryRRSSI(0)
    , _telemetryLRSSI(0)
dogmaphobic's avatar
dogmaphobic committed
68 69 70 71
    , _rollDownMessages(0)
{
    setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding);
    setObjectName("MainToolBar");
72
    _updatePixelSize();
dogmaphobic's avatar
dogmaphobic committed
73 74 75 76 77 78
    setMinimumWidth(MainWindow::instance()->minimumWidth());
    // Get rid of layout default margins
    QLayout* pl = layout();
    if(pl) {
        pl->setContentsMargins(0,0,0,0);
    }
79 80 81 82 83 84 85 86 87
    // Tool Bar Preferences
    QSettings settings;
    settings.beginGroup(TOOL_BAR_SETTINGS_GROUP);
    _showBattery  = settings.value(TOOL_BAR_SHOW_BATTERY,  true).toBool();
    _showGPS      = settings.value(TOOL_BAR_SHOW_GPS,      true).toBool();
    _showMav      = settings.value(TOOL_BAR_SHOW_MAV,      true).toBool();
    _showMessages = settings.value(TOOL_BAR_SHOW_MESSAGES, true).toBool();
    settings.endGroup();

dogmaphobic's avatar
dogmaphobic committed
88 89 90 91 92 93 94 95 96
    setContextPropertyObject("mainToolBar", this);
    setSource(QUrl::fromUserInput("qrc:/qml/MainToolBar.qml"));
    setVisible(true);
    // Configure the toolbar for the current default UAS (which should be none as we just booted)
    _setActiveUAS(UASManager::instance()->getActiveUAS());
    emit configListChanged();
    emit heartbeatTimeoutChanged(_currentHeartbeatTimeout);
    emit connectionCountChanged(_connectionCount);
    // Link signals
97 98 99 100
    connect(UASManager::instance(),      &UASManager::activeUASSet,              this, &MainToolBar::_setActiveUAS);
    connect(LinkManager::instance(),     &LinkManager::linkConfigurationChanged, this, &MainToolBar::_updateConfigurations);
    connect(LinkManager::instance(),     &LinkManager::linkConnected,            this, &MainToolBar::_linkConnected);
    connect(LinkManager::instance(),     &LinkManager::linkDisconnected,         this, &MainToolBar::_linkDisconnected);
101
    connect(MainWindow::instance(),      &MainWindow::pixelSizeChanged,          this, &MainToolBar::_updatePixelSize);
102 103 104 105
    // RSSI (didn't like standard connection)
    connect(MAVLinkProtocol::instance(),
        SIGNAL(radioStatusChanged(LinkInterface*, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned)), this,
        SLOT(_telemetryChanged(LinkInterface*, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned)));
dogmaphobic's avatar
dogmaphobic committed
106 107 108 109 110 111 112
}

MainToolBar::~MainToolBar()
{

}

113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130
void MainToolBar::_setToolBarState(const QString& key, bool value)
{
    QSettings settings;
    settings.beginGroup(TOOL_BAR_SETTINGS_GROUP);
    settings.setValue(key, value);
    settings.endGroup();
    if(key == TOOL_BAR_SHOW_GPS) {
        _showGPS = value;
        emit showGPSChanged(value);
    } else if(key == TOOL_BAR_SHOW_MAV) {
        _showMav = value;
        emit showMavChanged(value);
    }else if(key == TOOL_BAR_SHOW_BATTERY) {
        _showBattery = value;
        emit showBatteryChanged(value);
    } else if(key == TOOL_BAR_SHOW_MESSAGES) {
        _showMessages = value;
        emit showMessagesChanged(value);
131 132 133
    } else if(key == TOOL_BAR_SHOW_RSSI) {
        _showRSSI = value;
        emit showRSSIChanged(value);
134 135 136 137 138 139 140 141
    }
}

void MainToolBar::viewStateChanged(const QString &key, bool value)
{
    _setToolBarState(key, value);
}

dogmaphobic's avatar
dogmaphobic committed
142 143
void MainToolBar::onSetupView()
{
144
    setCurrentView(MainWindow::VIEW_SETUP);
dogmaphobic's avatar
dogmaphobic committed
145 146 147 148 149
    MainWindow::instance()->loadSetupView();
}

void MainToolBar::onPlanView()
{
150 151
    setCurrentView(MainWindow::VIEW_PLAN);
    MainWindow::instance()->loadPlanView();
dogmaphobic's avatar
dogmaphobic committed
152 153 154 155
}

void MainToolBar::onFlyView()
{
156
    setCurrentView(MainWindow::VIEW_FLIGHT);
157
    MainWindow::instance()->loadFlightView();
dogmaphobic's avatar
dogmaphobic committed
158 159
}

dogmaphobic's avatar
dogmaphobic committed
160 161 162 163 164 165 166 167
void MainToolBar::onFlyViewMenu()
{
    QGCFlightDisplay* fdsp = MainWindow::instance()->getFlightDisplay();
    if(fdsp) {
        fdsp->showOptionsMenu();
    }
}

dogmaphobic's avatar
dogmaphobic committed
168 169
void MainToolBar::onAnalyzeView()
{
170 171
    setCurrentView(MainWindow::VIEW_ANALYZE);
    MainWindow::instance()->loadAnalyzeView();
dogmaphobic's avatar
dogmaphobic committed
172 173
}

dogmaphobic's avatar
dogmaphobic committed
174
void MainToolBar::onDisconnect(QString conf)
dogmaphobic's avatar
dogmaphobic committed
175
{
dogmaphobic's avatar
dogmaphobic committed
176 177 178 179 180 181 182 183 184
    if(conf.isEmpty()) {
        // Disconnect Only Connected Link
        int connectedCount = 0;
        LinkInterface* connectedLink = NULL;
        QList<LinkInterface*> links = LinkManager::instance()->getLinks();
        foreach(LinkInterface* link, links) {
            if (link->isConnected()) {
                connectedCount++;
                connectedLink = link;
dogmaphobic's avatar
dogmaphobic committed
185 186
            }
        }
dogmaphobic's avatar
dogmaphobic committed
187 188 189 190
        Q_ASSERT(connectedCount   == 1);
        Q_ASSERT(_connectionCount == 1);
        Q_ASSERT(connectedLink);
        LinkManager::instance()->disconnectLink(connectedLink);
dogmaphobic's avatar
dogmaphobic committed
191
    } else {
dogmaphobic's avatar
dogmaphobic committed
192 193 194 195 196 197
        // Disconnect Named Connected Link
        QList<LinkInterface*> links = LinkManager::instance()->getLinks();
        foreach(LinkInterface* link, links) {
            if (link->isConnected()) {
                if(link->getLinkConfiguration() && link->getLinkConfiguration()->name() == conf) {
                    LinkManager::instance()->disconnectLink(link);
dogmaphobic's avatar
dogmaphobic committed
198 199 200 201 202 203
                }
            }
        }
    }
}

dogmaphobic's avatar
dogmaphobic committed
204
void MainToolBar::onConnect(QString conf)
dogmaphobic's avatar
dogmaphobic committed
205
{
dogmaphobic's avatar
dogmaphobic committed
206 207 208 209 210 211 212 213 214 215 216 217 218
    // Connect Link
    if(conf.isEmpty()) {
        MainWindow::instance()->manageLinks();
    } else {
        // We don't want the list updating under our feet
        LinkManager::instance()->suspendConfigurationUpdates(true);
        // Create a link
        LinkInterface* link = LinkManager::instance()->createConnectedLink(conf);
        if(link) {
            // Save last used connection
            MainWindow::instance()->saveLastUsedConnection(conf);
        }
        LinkManager::instance()->suspendConfigurationUpdates(false);
dogmaphobic's avatar
dogmaphobic committed
219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235
    }
}

void MainToolBar::onEnterMessageArea(int x, int y)
{
    // If not already there and messages are actually present
    if(!_rollDownMessages && UASMessageHandler::instance()->messages().count())
    {
        // Reset Counts
        int count = _currentMessageCount;
        MessageType_t type = _currentMessageType;
        _currentErrorCount   = 0;
        _currentWarningCount = 0;
        _currentNormalCount  = 0;
        _currentMessageCount = 0;
        _currentMessageType = MessageNone;
        if(count != _currentMessageCount) {
dogmaphobic's avatar
dogmaphobic committed
236
            emit newMessageCountChanged(0);
dogmaphobic's avatar
dogmaphobic committed
237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275
        }
        if(type != _currentMessageType) {
            emit messageTypeChanged(MessageNone);
        }
        // Show messages
        int dialogWidth = 400;
        x = x - (dialogWidth >> 1);
        if(x < 0) x = 0;
        y = height() / 3;
        // Put dialog on top of the message alert icon
        QPoint p = mapToGlobal(QPoint(x,y));
        _rollDownMessages = new UASMessageViewRollDown(MainWindow::instance());
        _rollDownMessages->setAttribute(Qt::WA_DeleteOnClose);
        _rollDownMessages->move(mapFromGlobal(p));
        _rollDownMessages->setMinimumSize(dialogWidth,200);
        connect(_rollDownMessages, &UASMessageViewRollDown::closeWindow, this, &MainToolBar::_leaveMessageView);
        _rollDownMessages->show();
    }
}

QString MainToolBar::getMavIconColor()
{
    // TODO: Not using because not only the colors are ghastly, it doesn't respect dark/light palette
    if(_mav)
        return _mav->getColor().name();
    else
        return QString("black");
}

void MainToolBar::_leaveMessageView()
{
    // Mouse has left the message window area (and it has closed itself)
    _rollDownMessages = NULL;
}

void MainToolBar::setCurrentView(int currentView)
{
    ViewType_t view = ViewNone;
    switch((MainWindow::VIEW_SECTIONS)currentView) {
276
        case MainWindow::VIEW_ANALYZE:
dogmaphobic's avatar
dogmaphobic committed
277 278
            view = ViewAnalyze;
            break;
279
        case MainWindow::VIEW_PLAN:
dogmaphobic's avatar
dogmaphobic committed
280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306
            view = ViewPlan;
            break;
           case MainWindow::VIEW_FLIGHT:
            view = ViewFly;
            break;
        case MainWindow::VIEW_SETUP:
            view = ViewSetup;
            break;
        default:
            view = ViewNone;
            break;
    }
    if(view != _currentView) {
        _currentView = view;
        emit currentViewChanged();
    }
}

void MainToolBar::_setActiveUAS(UASInterface* active)
{
    // Do nothing if system is the same
    if (_mav == active) {
        return;
    }
    // If switching the UAS, disconnect the existing one.
    if (_mav)
    {
dogmaphobic's avatar
dogmaphobic committed
307 308 309 310 311 312 313
        disconnect(UASMessageHandler::instance(), &UASMessageHandler::textMessageCountChanged,  this, &MainToolBar::_handleTextMessage);
        disconnect(_mav, &UASInterface::heartbeatTimeout,                                       this, &MainToolBar::_heartbeatTimeout);
        disconnect(_mav, &UASInterface::batteryChanged,                                         this, &MainToolBar::_updateBatteryRemaining);
        disconnect(_mav, &UASInterface::modeChanged,                                            this, &MainToolBar::_updateMode);
        disconnect(_mav, &UASInterface::nameChanged,                                            this, &MainToolBar::_updateName);
        disconnect(_mav, &UASInterface::systemTypeSet,                                          this, &MainToolBar::_setSystemType);
        disconnect(_mav, &UASInterface::localizationChanged,                                    this, &MainToolBar::_setSatLoc);
314
        disconnect(_mav, &UASInterface::remoteControlRSSIChanged,                               this, &MainToolBar::_remoteControlRSSIChanged);
dogmaphobic's avatar
dogmaphobic committed
315 316
        disconnect(_mav, SIGNAL(statusChanged(UASInterface*,QString,QString)),                  this, SLOT(_updateState(UASInterface*,QString,QString)));
        disconnect(_mav, SIGNAL(armingChanged(bool)),                                           this, SLOT(_updateArmingState(bool)));
317 318

        if (_mav->getWaypointManager()) {
dogmaphobic's avatar
dogmaphobic committed
319 320 321
            disconnect(_mav->getWaypointManager(), &UASWaypointManager::currentWaypointChanged,  this, &MainToolBar::_updateCurrentWaypoint);
            disconnect(_mav->getWaypointManager(), &UASWaypointManager::waypointDistanceChanged, this, &MainToolBar::_updateWaypointDistance);
        }
322
        
dogmaphobic's avatar
dogmaphobic committed
323 324 325 326
        UAS* pUas = dynamic_cast<UAS*>(_mav);
        if(pUas) {
            disconnect(pUas, &UAS::satelliteCountChanged, this, &MainToolBar::_setSatelliteCount);
        }
327 328
        
        disconnect(AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_mav), &AutoPilotPlugin::parameterListProgress, this, &MainToolBar::_setProgressBarValue);
dogmaphobic's avatar
dogmaphobic committed
329 330 331 332 333 334 335
    }
    // Connect new system
    _mav = active;
    if (_mav)
    {
        _setSystemType(_mav, _mav->getSystemType());
        _updateArmingState(_mav->isArmed());
dogmaphobic's avatar
dogmaphobic committed
336
        connect(UASMessageHandler::instance(), &UASMessageHandler::textMessageCountChanged, this, &MainToolBar::_handleTextMessage);
dogmaphobic's avatar
dogmaphobic committed
337 338 339 340 341
        connect(_mav, &UASInterface::heartbeatTimeout,                                      this, &MainToolBar::_heartbeatTimeout);
        connect(_mav, &UASInterface::batteryChanged,                                        this, &MainToolBar::_updateBatteryRemaining);
        connect(_mav, &UASInterface::modeChanged,                                           this, &MainToolBar::_updateMode);
        connect(_mav, &UASInterface::nameChanged,                                           this, &MainToolBar::_updateName);
        connect(_mav, &UASInterface::systemTypeSet,                                         this, &MainToolBar::_setSystemType);
dogmaphobic's avatar
dogmaphobic committed
342
        connect(_mav, &UASInterface::localizationChanged,                                   this, &MainToolBar::_setSatLoc);
343
        connect(_mav, &UASInterface::remoteControlRSSIChanged,                              this, &MainToolBar::_remoteControlRSSIChanged);
dogmaphobic's avatar
dogmaphobic committed
344 345
        connect(_mav, SIGNAL(statusChanged(UASInterface*,QString,QString)),                 this, SLOT(_updateState(UASInterface*, QString,QString)));
        connect(_mav, SIGNAL(armingChanged(bool)),                                          this, SLOT(_updateArmingState(bool)));
346 347
        
        if (_mav->getWaypointManager()) {
dogmaphobic's avatar
dogmaphobic committed
348 349 350
            connect(_mav->getWaypointManager(), &UASWaypointManager::currentWaypointChanged,  this, &MainToolBar::_updateCurrentWaypoint);
            connect(_mav->getWaypointManager(), &UASWaypointManager::waypointDistanceChanged, this, &MainToolBar::_updateWaypointDistance);
        }
351
        
dogmaphobic's avatar
dogmaphobic committed
352 353 354 355 356
        UAS* pUas = dynamic_cast<UAS*>(_mav);
        if(pUas) {
            _setSatelliteCount(pUas->getSatelliteCount(), QString(""));
            connect(pUas, &UAS::satelliteCountChanged, this, &MainToolBar::_setSatelliteCount);
        }
357 358 359
        
        connect(AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_mav), &AutoPilotPlugin::parameterListProgress, this, &MainToolBar::_setProgressBarValue);
        
360 361 362
        // Reset connection lost (if any)
        _currentHeartbeatTimeout = 0;
        emit heartbeatTimeoutChanged(_currentHeartbeatTimeout);
dogmaphobic's avatar
dogmaphobic committed
363 364 365 366 367
    }
    // Let toolbar know about it
    emit mavPresentChanged(_mav != NULL);
}

368
void MainToolBar::_telemetryChanged(LinkInterface*, unsigned, unsigned, unsigned rssi, unsigned remrssi, unsigned, unsigned, unsigned)
369
{
370
    // We only care if we haveone single connection
371
    if(_connectionCount == 1) {
372 373 374 375 376 377 378 379 380
        if((unsigned)_telemetryLRSSI != rssi) {
            // According to the Silabs data sheet, the RSSI value is 0.5db per bit
            _telemetryLRSSI = rssi >> 1;
            emit telemetryLRSSIChanged(_telemetryLRSSI);
        }
        if((unsigned)_telemetryRRSSI != remrssi) {
            // According to the Silabs data sheet, the RSSI value is 0.5db per bit
            _telemetryRRSSI = remrssi >> 1;
            emit telemetryRRSSIChanged(_telemetryRRSSI);
381 382 383 384
        }
    }
}

385
void MainToolBar::_remoteControlRSSIChanged(uint8_t rssi)
386
{
387 388 389 390 391 392
    // We only care if we haveone single connection
    if(_connectionCount == 1) {
        if(_remoteRSSI != rssi) {
            _remoteRSSI = rssi;
            emit remoteRSSIChanged(_remoteRSSI);
        }
393 394 395
    }
}

dogmaphobic's avatar
dogmaphobic committed
396 397 398 399 400 401 402 403 404 405
void MainToolBar::_updateArmingState(bool armed)
{
    if(_systemArmed != armed) {
        _systemArmed = armed;
        emit systemArmedChanged(armed);
    }
}

void MainToolBar::_updateBatteryRemaining(UASInterface*, double voltage, double, double percent, int)
{
dogmaphobic's avatar
dogmaphobic committed
406

dogmaphobic's avatar
dogmaphobic committed
407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428
    if(percent < 0.0) {
        percent = 0.0;
    }
    if(voltage < 0.0) {
        voltage = 0.0;
    }
    if (_batteryVoltage != voltage) {
        _batteryVoltage = voltage;
        emit batteryVoltageChanged(voltage);
    }
    if (_batteryPercent != percent) {
        _batteryPercent = percent;
        emit batteryPercentChanged(voltage);
    }
}

void MainToolBar::_updateConfigurations()
{
    QStringList tmpList;
    QList<LinkConfiguration*> configs = LinkManager::instance()->getLinkConfigurationList();
    foreach(LinkConfiguration* conf, configs) {
        if(conf) {
dogmaphobic's avatar
dogmaphobic committed
429 430 431 432
            if(conf->isPreferred()) {
                tmpList.insert(0,conf->name());
            } else {
                tmpList << conf->name();
dogmaphobic's avatar
dogmaphobic committed
433 434 435 436 437 438 439 440 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
            }
        }
    }
    // Any changes?
    if(tmpList != _linkConfigurations) {
        _linkConfigurations = tmpList;
        emit configListChanged();
    }
}

void MainToolBar::_linkConnected(LinkInterface*)
{
    _updateConnection();
}

void MainToolBar::_linkDisconnected(LinkInterface* link)
{
    _updateConnection(link);
}

void MainToolBar::_updateConnection(LinkInterface *disconnectedLink)
{
    QStringList connList;
    int oldCount = _connectionCount;
    // If there are multiple connected links add/update the connect button menu
    _connectionCount = 0;
    QList<LinkInterface*> links = LinkManager::instance()->getLinks();
    foreach(LinkInterface* link, links) {
        if (disconnectedLink != link && link->isConnected()) {
            _connectionCount++;
            if(link->getLinkConfiguration()) {
                connList << link->getLinkConfiguration()->name();
            }
        }
    }
    if(oldCount != _connectionCount) {
        emit connectionCountChanged(_connectionCount);
    }
    if(connList != _connectedList) {
        _connectedList = connList;
        emit connectedListChanged(_connectedList);
    }
475
    // Update telemetry RSSI display
476 477 478 479 480 481 482
    if(_connectionCount != 1 && _telemetryRRSSI > 0) {
        _telemetryRRSSI = 0;
        emit telemetryRRSSIChanged(_telemetryRRSSI);
    }
    if(_connectionCount != 1 && _telemetryLRSSI > 0) {
        _telemetryLRSSI = 0;
        emit telemetryLRSSIChanged(_telemetryLRSSI);
483
    }
484 485
    if(_connectionCount != 1 && _remoteRSSI > 0) {
        _remoteRSSI = 0;
dogmaphobic's avatar
dogmaphobic committed
486
        emit remoteRSSIChanged(_remoteRSSI);
487
    }
dogmaphobic's avatar
dogmaphobic committed
488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527
}

void MainToolBar::_updateState(UASInterface*, QString name, QString)
{
    if (_currentState != name) {
        _currentState = name;
        emit currentStateChanged(_currentState);
    }
}

void MainToolBar::_updateMode(int, QString name, QString)
{
    if (name.size()) {
        QString shortMode = name;
        shortMode = shortMode.replace("D|", "");
        shortMode = shortMode.replace("A|", "");
        if (_currentMode != shortMode) {
            _currentMode = shortMode;
            emit currentModeChanged();
        }
    }
}

void MainToolBar::_updateName(const QString& name)
{
    if (_systemName != name) {
        _systemName = name;
        // TODO: emit signal and use it
    }
}

/**
 * The current system type is represented through the system icon.
 *
 * @param uas Source system, has to be the same as this->uas
 * @param systemType type ID, following the MAVLink system type conventions
 * @see http://pixhawk.ethz.ch/software/mavlink
 */
void MainToolBar::_setSystemType(UASInterface*, unsigned int systemType)
{
Don Gagne's avatar
Don Gagne committed
528
    _systemPixmap = "qrc:/res/mavs/";
dogmaphobic's avatar
dogmaphobic committed
529 530
    switch (systemType) {
        case MAV_TYPE_GENERIC:
Don Gagne's avatar
Don Gagne committed
531
            _systemPixmap += "Generic";
dogmaphobic's avatar
dogmaphobic committed
532 533
            break;
        case MAV_TYPE_FIXED_WING:
Don Gagne's avatar
Don Gagne committed
534
            _systemPixmap += "FixedWing";
dogmaphobic's avatar
dogmaphobic committed
535 536
            break;
        case MAV_TYPE_QUADROTOR:
Don Gagne's avatar
Don Gagne committed
537
            _systemPixmap += "QuadRotor";
dogmaphobic's avatar
dogmaphobic committed
538 539
            break;
        case MAV_TYPE_COAXIAL:
Don Gagne's avatar
Don Gagne committed
540
            _systemPixmap += "Coaxial";
dogmaphobic's avatar
dogmaphobic committed
541 542
            break;
        case MAV_TYPE_HELICOPTER:
Don Gagne's avatar
Don Gagne committed
543
            _systemPixmap += "Helicopter";
dogmaphobic's avatar
dogmaphobic committed
544 545
            break;
        case MAV_TYPE_ANTENNA_TRACKER:
Don Gagne's avatar
Don Gagne committed
546
            _systemPixmap += "AntennaTracker";
dogmaphobic's avatar
dogmaphobic committed
547 548
            break;
        case MAV_TYPE_GCS:
Don Gagne's avatar
Don Gagne committed
549
            _systemPixmap += "Groundstation";
dogmaphobic's avatar
dogmaphobic committed
550 551
            break;
        case MAV_TYPE_AIRSHIP:
Don Gagne's avatar
Don Gagne committed
552
            _systemPixmap += "Airship";
dogmaphobic's avatar
dogmaphobic committed
553 554
            break;
        case MAV_TYPE_FREE_BALLOON:
Don Gagne's avatar
Don Gagne committed
555
            _systemPixmap += "FreeBalloon";
dogmaphobic's avatar
dogmaphobic committed
556 557
            break;
        case MAV_TYPE_ROCKET:
Don Gagne's avatar
Don Gagne committed
558
            _systemPixmap += "Rocket";
dogmaphobic's avatar
dogmaphobic committed
559 560
            break;
        case MAV_TYPE_GROUND_ROVER:
Don Gagne's avatar
Don Gagne committed
561
            _systemPixmap += "GroundRover";
dogmaphobic's avatar
dogmaphobic committed
562 563
            break;
        case MAV_TYPE_SURFACE_BOAT:
Don Gagne's avatar
Don Gagne committed
564
            _systemPixmap += "SurfaceBoat";
dogmaphobic's avatar
dogmaphobic committed
565 566
            break;
        case MAV_TYPE_SUBMARINE:
Don Gagne's avatar
Don Gagne committed
567
            _systemPixmap += "Submarine";
dogmaphobic's avatar
dogmaphobic committed
568 569
            break;
        case MAV_TYPE_HEXAROTOR:
Don Gagne's avatar
Don Gagne committed
570
            _systemPixmap += "HexaRotor";
dogmaphobic's avatar
dogmaphobic committed
571 572
            break;
        case MAV_TYPE_OCTOROTOR:
Don Gagne's avatar
Don Gagne committed
573
            _systemPixmap += "OctoRotor";
dogmaphobic's avatar
dogmaphobic committed
574 575
            break;
        case MAV_TYPE_TRICOPTER:
Don Gagne's avatar
Don Gagne committed
576
            _systemPixmap += "TriCopter";
dogmaphobic's avatar
dogmaphobic committed
577 578
            break;
        case MAV_TYPE_FLAPPING_WING:
Don Gagne's avatar
Don Gagne committed
579
            _systemPixmap += "FlappingWing";
dogmaphobic's avatar
dogmaphobic committed
580 581
            break;
        case MAV_TYPE_KITE:
Don Gagne's avatar
Don Gagne committed
582
            _systemPixmap += "Kite";
dogmaphobic's avatar
dogmaphobic committed
583 584
            break;
        default:
Don Gagne's avatar
Don Gagne committed
585
            _systemPixmap += "Unknown";
dogmaphobic's avatar
dogmaphobic committed
586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603
            break;
    }
    emit systemPixmapChanged(_systemPixmap);
}

void MainToolBar::_heartbeatTimeout(bool timeout, unsigned int ms)
{
    unsigned int elapsed = ms;
    if (!timeout)
    {
        elapsed = 0;
    }
    if(elapsed != _currentHeartbeatTimeout) {
        _currentHeartbeatTimeout = elapsed;
        emit heartbeatTimeoutChanged(_currentHeartbeatTimeout);
    }
}

dogmaphobic's avatar
dogmaphobic committed
604
void MainToolBar::_handleTextMessage(int newCount)
dogmaphobic's avatar
dogmaphobic committed
605
{
dogmaphobic's avatar
dogmaphobic committed
606 607 608 609 610 611 612 613 614 615 616 617 618 619
    // Reset?
    if(!newCount) {
        _currentMessageCount = 0;
        _currentNormalCount  = 0;
        _currentWarningCount = 0;
        _currentErrorCount   = 0;
        _messageCount        = 0;
        _currentMessageType  = MessageNone;
        emit newMessageCountChanged(0);
        emit messageTypeChanged(MessageNone);
        emit messageCountChanged(0);
        return;
    }

dogmaphobic's avatar
dogmaphobic committed
620 621
    UASMessageHandler* pMh = UASMessageHandler::instance();
    Q_ASSERT(pMh);
dogmaphobic's avatar
dogmaphobic committed
622
    MessageType_t type = newCount ? _currentMessageType : MessageNone;
dogmaphobic's avatar
dogmaphobic committed
623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649
    int errorCount     = _currentErrorCount;
    int warnCount      = _currentWarningCount;
    int normalCount    = _currentNormalCount;
    //-- Add current message counts
    errorCount  += pMh->getErrorCount();
    warnCount   += pMh->getWarningCount();
    normalCount += pMh->getNormalCount();
    //-- See if we have a higher level
    if(errorCount != _currentErrorCount) {
        _currentErrorCount = errorCount;
        type = MessageError;
    }
    if(warnCount != _currentWarningCount) {
        _currentWarningCount = warnCount;
        if(_currentMessageType != MessageError) {
            type = MessageWarning;
        }
    }
    if(normalCount != _currentNormalCount) {
        _currentNormalCount = normalCount;
        if(_currentMessageType != MessageError && _currentMessageType != MessageWarning) {
            type = MessageNormal;
        }
    }
    int count = _currentErrorCount + _currentWarningCount + _currentNormalCount;
    if(count != _currentMessageCount) {
        _currentMessageCount = count;
dogmaphobic's avatar
dogmaphobic committed
650 651
        // Display current total new messages count
        emit newMessageCountChanged(count);
dogmaphobic's avatar
dogmaphobic committed
652 653 654 655 656 657
    }
    if(type != _currentMessageType) {
        _currentMessageType = type;
        // Update message level
        emit messageTypeChanged(type);
    }
dogmaphobic's avatar
dogmaphobic committed
658 659 660 661 662
    // Update message count (all messages)
    if(newCount != _messageCount) {
        _messageCount = newCount;
        emit messageCountChanged(_messageCount);
    }
dogmaphobic's avatar
dogmaphobic committed
663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682
}

void MainToolBar::_updateWaypointDistance(double distance)
{
    if (_waypointDistance != distance) {
        _waypointDistance = distance;
        // TODO: emit signal and use it
    }
}

void MainToolBar::_updateCurrentWaypoint(quint16 id)
{
    if (_currentWaypoint != id) {
        _currentWaypoint = id;
        // TODO: emit signal and use it
    }
}

void MainToolBar::_setSatelliteCount(double val, QString)
{
dogmaphobic's avatar
dogmaphobic committed
683 684 685
    // I'm assuming that a negative value or over 99 means there is no GPS
    if(val < 0.0)  val = -1.0;
    if(val > 99.0) val = -1.0;
dogmaphobic's avatar
dogmaphobic committed
686 687 688 689 690
    if(_satelliteCount != (int)val) {
        _satelliteCount = (int)val;
        emit satelliteCountChanged(_satelliteCount);
    }
}
dogmaphobic's avatar
dogmaphobic committed
691 692 693 694 695 696 697 698 699

void MainToolBar::_setSatLoc(UASInterface*, int fix)
{
    // fix 0: lost, 1: at least one satellite, but no GPS fix, 2: 2D lock, 3: 3D lock
    if(_satelliteLock != fix) {
        _satelliteLock = fix;
        emit satelliteLockChanged(_satelliteLock);
    }
}
700 701 702 703 704 705

void MainToolBar::_setProgressBarValue(float value)
{
    _progressBarValue = value;
    emit progressBarValueChanged(value);
}
706 707 708 709 710 711

void MainToolBar::_updatePixelSize()
{
    setMinimumHeight(40 * MainWindow::pixelSizeFactor());
    setMaximumHeight(40 * MainWindow::pixelSizeFactor());
}