MainToolBar.cc 13.9 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"
Don Gagne's avatar
Don Gagne committed
34
#include "ScreenToolsController.h"
35
#include "MainWindow.h"
dogmaphobic's avatar
dogmaphobic committed
36
#include "UASMessageView.h"
37
#include "UASMessageHandler.h"
38
#include "FlightDisplay.h"
39 40
#include "QGCApplication.h"
#include "MavManager.h"
41
#include "MultiVehicleManager.h"
dogmaphobic's avatar
dogmaphobic committed
42

Don Gagne's avatar
Don Gagne committed
43 44
MainToolBar::MainToolBar(QWidget* parent)
    : QGCQmlWidgetHolder(parent)
45
    , _vehicle(NULL)
Don Gagne's avatar
Don Gagne committed
46
    , _mav(NULL)
dogmaphobic's avatar
dogmaphobic committed
47 48 49
    , _toolBar(NULL)
    , _currentView(ViewNone)
    , _connectionCount(0)
50 51 52
    , _showGPS(true)
    , _showMav(true)
    , _showMessages(true)
53
    , _showRSSI(true)
54
    , _showBattery(true)
55
    , _progressBarValue(0.0f)
56
    , _remoteRSSI(0)
dogmaphobic's avatar
dogmaphobic committed
57
    , _remoteRSSIstore(100.0)
58 59
    , _telemetryRRSSI(0)
    , _telemetryLRSSI(0)
dogmaphobic's avatar
dogmaphobic committed
60
    , _rollDownMessages(0)
61
    , _toolbarMessageVisible(false)
dogmaphobic's avatar
dogmaphobic committed
62 63 64 65 66 67 68 69 70
{
    setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding);
    setObjectName("MainToolBar");
    setMinimumWidth(MainWindow::instance()->minimumWidth());
    // Get rid of layout default margins
    QLayout* pl = layout();
    if(pl) {
        pl->setContentsMargins(0,0,0,0);
    }
Don Gagne's avatar
Don Gagne committed
71 72
    setMinimumHeight(ScreenToolsController::defaultFontPixelSize_s() * 3);
    setMaximumHeight(ScreenToolsController::defaultFontPixelSize_s() * 3);
73 74 75 76 77 78 79 80 81
    // 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
82 83 84 85 86
    setContextPropertyObject("mainToolBar", this);
    setSource(QUrl::fromUserInput("qrc:/qml/MainToolBar.qml"));
    setVisible(true);
    emit configListChanged();
    emit connectionCountChanged(_connectionCount);
87 88
    _activeVehicleChanged(MultiVehicleManager::instance()->activeVehicle());
    
dogmaphobic's avatar
dogmaphobic committed
89
    // Link signals
90 91 92
    connect(LinkManager::instance(),     &LinkManager::linkConfigurationChanged, this, &MainToolBar::_updateConfigurations);
    connect(LinkManager::instance(),     &LinkManager::linkConnected,            this, &MainToolBar::_linkConnected);
    connect(LinkManager::instance(),     &LinkManager::linkDisconnected,         this, &MainToolBar::_linkDisconnected);
93
    
94 95 96 97
    // 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)));
98 99
    
    connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &MainToolBar::_activeVehicleChanged);
Don Gagne's avatar
Don Gagne committed
100 101
    
    connect(this, &MainToolBar::heightChanged, this, &MainToolBar::_heightChanged);
dogmaphobic's avatar
dogmaphobic committed
102 103 104 105 106 107 108
}

MainToolBar::~MainToolBar()
{

}

109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126
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);
127 128 129
    } else if(key == TOOL_BAR_SHOW_RSSI) {
        _showRSSI = value;
        emit showRSSIChanged(value);
130 131 132 133 134 135 136 137
    }
}

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

dogmaphobic's avatar
dogmaphobic committed
138 139
void MainToolBar::onSetupView()
{
140
    setCurrentView(MainWindow::VIEW_SETUP);
dogmaphobic's avatar
dogmaphobic committed
141 142 143 144 145
    MainWindow::instance()->loadSetupView();
}

void MainToolBar::onPlanView()
{
146 147
    setCurrentView(MainWindow::VIEW_PLAN);
    MainWindow::instance()->loadPlanView();
dogmaphobic's avatar
dogmaphobic committed
148 149 150 151
}

void MainToolBar::onFlyView()
{
152
    setCurrentView(MainWindow::VIEW_FLIGHT);
153
    MainWindow::instance()->loadFlightView();
dogmaphobic's avatar
dogmaphobic committed
154 155
}

dogmaphobic's avatar
dogmaphobic committed
156 157
void MainToolBar::onFlyViewMenu()
{
158
    FlightDisplay* fdsp = MainWindow::instance()->getFlightDisplay();
dogmaphobic's avatar
dogmaphobic committed
159 160 161 162 163
    if(fdsp) {
        fdsp->showOptionsMenu();
    }
}

dogmaphobic's avatar
dogmaphobic committed
164 165
void MainToolBar::onAnalyzeView()
{
166 167
    setCurrentView(MainWindow::VIEW_ANALYZE);
    MainWindow::instance()->loadAnalyzeView();
dogmaphobic's avatar
dogmaphobic committed
168 169
}

dogmaphobic's avatar
dogmaphobic committed
170
void MainToolBar::onDisconnect(QString conf)
dogmaphobic's avatar
dogmaphobic committed
171
{
dogmaphobic's avatar
dogmaphobic committed
172 173 174 175 176 177 178 179 180
    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
181 182
            }
        }
dogmaphobic's avatar
dogmaphobic committed
183 184 185 186
        Q_ASSERT(connectedCount   == 1);
        Q_ASSERT(_connectionCount == 1);
        Q_ASSERT(connectedLink);
        LinkManager::instance()->disconnectLink(connectedLink);
dogmaphobic's avatar
dogmaphobic committed
187
    } else {
dogmaphobic's avatar
dogmaphobic committed
188 189 190 191 192 193
        // 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
194 195 196 197 198 199
                }
            }
        }
    }
}

dogmaphobic's avatar
dogmaphobic committed
200
void MainToolBar::onConnect(QString conf)
dogmaphobic's avatar
dogmaphobic committed
201
{
dogmaphobic's avatar
dogmaphobic committed
202 203 204 205 206 207 208 209 210 211 212 213 214
    // 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
215 216 217 218 219 220 221 222
    }
}

void MainToolBar::onEnterMessageArea(int x, int y)
{
    // If not already there and messages are actually present
    if(!_rollDownMessages && UASMessageHandler::instance()->messages().count())
    {
223 224
        if(qgcApp()->getMavManager())
            qgcApp()->getMavManager()->resetMessages();
dogmaphobic's avatar
dogmaphobic committed
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
        // 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();
    }
}

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) {
251
        case MainWindow::VIEW_ANALYZE:
dogmaphobic's avatar
dogmaphobic committed
252 253
            view = ViewAnalyze;
            break;
254
        case MainWindow::VIEW_PLAN:
dogmaphobic's avatar
dogmaphobic committed
255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272
            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();
    }
}

273
void MainToolBar::_activeVehicleChanged(Vehicle* vehicle)
274
{
275 276
    // Disconnect the previous one (if any)
    if (_vehicle) {
277
        disconnect(_mav, &UASInterface::remoteControlRSSIChanged, this, &MainToolBar::_remoteControlRSSIChanged);
278
        disconnect(_vehicle->autopilotPlugin(), &AutoPilotPlugin::parameterListProgress, this, &MainToolBar::_setProgressBarValue);
279
        _mav = NULL;
280
        _vehicle = NULL;
281
    }
282
    
dogmaphobic's avatar
dogmaphobic committed
283
    // Connect new system
284
    if (vehicle)
dogmaphobic's avatar
dogmaphobic committed
285
    {
286 287
        _vehicle = vehicle;
        _mav = vehicle->uas();
288
        connect(_mav, &UASInterface::remoteControlRSSIChanged, this, &MainToolBar::_remoteControlRSSIChanged);
289
        connect(_vehicle->autopilotPlugin(), &AutoPilotPlugin::parameterListProgress, this, &MainToolBar::_setProgressBarValue);
dogmaphobic's avatar
dogmaphobic committed
290
    }
291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310
}

void MainToolBar::_updateConfigurations()
{
    QStringList tmpList;
    QList<LinkConfiguration*> configs = LinkManager::instance()->getLinkConfigurationList();
    foreach(LinkConfiguration* conf, configs) {
        if(conf) {
            if(conf->isPreferred()) {
                tmpList.insert(0,conf->name());
            } else {
                tmpList << conf->name();
            }
        }
    }
    // Any changes?
    if(tmpList != _linkConfigurations) {
        _linkConfigurations = tmpList;
        emit configListChanged();
    }
dogmaphobic's avatar
dogmaphobic committed
311 312
}

313
void MainToolBar::_telemetryChanged(LinkInterface*, unsigned, unsigned, unsigned rssi, unsigned remrssi, unsigned, unsigned, unsigned)
314
{
315
    // We only care if we haveone single connection
316
    if(_connectionCount == 1) {
317 318 319 320 321 322 323 324 325
        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);
326 327 328 329
        }
    }
}

330
void MainToolBar::_remoteControlRSSIChanged(uint8_t rssi)
331
{
dogmaphobic's avatar
dogmaphobic committed
332
    // We only care if we have one single connection
333
    if(_connectionCount == 1) {
dogmaphobic's avatar
dogmaphobic committed
334 335 336 337 338 339 340 341
        // Low pass to git rid of jitter
        _remoteRSSIstore = (_remoteRSSIstore * 0.9f) + ((float)rssi * 0.1);
        uint8_t filteredRSSI = (uint8_t)ceil(_remoteRSSIstore);
        if(_remoteRSSIstore < 0.1) {
            filteredRSSI = 0;
        }
        if(_remoteRSSI != filteredRSSI) {
            _remoteRSSI = filteredRSSI;
342 343
            emit remoteRSSIChanged(_remoteRSSI);
        }
344 345 346
    }
}

dogmaphobic's avatar
dogmaphobic committed
347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378
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);
    }
379
    // Update telemetry RSSI display
380 381 382 383 384 385 386
    if(_connectionCount != 1 && _telemetryRRSSI > 0) {
        _telemetryRRSSI = 0;
        emit telemetryRRSSIChanged(_telemetryRRSSI);
    }
    if(_connectionCount != 1 && _telemetryLRSSI > 0) {
        _telemetryLRSSI = 0;
        emit telemetryLRSSIChanged(_telemetryLRSSI);
387
    }
388 389
    if(_connectionCount != 1 && _remoteRSSI > 0) {
        _remoteRSSI = 0;
dogmaphobic's avatar
dogmaphobic committed
390
        emit remoteRSSIChanged(_remoteRSSI);
391
    }
dogmaphobic's avatar
dogmaphobic committed
392 393
}

394 395 396 397 398
void MainToolBar::_setProgressBarValue(float value)
{
    _progressBarValue = value;
    emit progressBarValueChanged(value);
}
Don Gagne's avatar
Don Gagne committed
399 400 401 402 403 404

void MainToolBar::_heightChanged(double height)
{
    setMinimumHeight(height);
    setMaximumHeight(height);
}
405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444

void MainToolBar::showToolBarMessage(const QString& message)
{
    _toolbarMessageQueueMutex.lock();
    
    if (_toolbarMessageQueue.count() == 0 && !_toolbarMessageVisible) {
        QTimer::singleShot(500, this, &MainToolBar::_delayedShowToolBarMessage);
    }
    
    _toolbarMessageQueue += message;
    
    _toolbarMessageQueueMutex.unlock();
}

void MainToolBar::_delayedShowToolBarMessage(void)
{
    QString messages;
    
    if (!_toolbarMessageVisible) {
        _toolbarMessageQueueMutex.lock();
        
        foreach (QString message, _toolbarMessageQueue) {
            messages += message + "\n";
        }
        _toolbarMessageQueue.clear();
        
        _toolbarMessageQueueMutex.unlock();
        
        if (!messages.isEmpty()) {
            _toolbarMessageVisible = true;
            emit showMessage(messages);
        }
    }
}

void MainToolBar::onToolBarMessageClosed(void)
{
    _toolbarMessageVisible = false;
    _delayedShowToolBarMessage();
}