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
#include "QGCApplication.h"
40
#include "MultiVehicleManager.h"
dogmaphobic's avatar
dogmaphobic committed
41

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

MainToolBar::~MainToolBar()
{

}

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

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

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

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

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

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

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

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

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

void MainToolBar::onEnterMessageArea(int x, int y)
{
    // If not already there and messages are actually present
    if(!_rollDownMessages && UASMessageHandler::instance()->messages().count())
    {
222 223
        if (MultiVehicleManager::instance()->activeVehicle())
            MultiVehicleManager::instance()->activeVehicle()->resetMessages();
dogmaphobic's avatar
dogmaphobic committed
224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249
        // 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) {
250
        case MainWindow::VIEW_ANALYZE:
dogmaphobic's avatar
dogmaphobic committed
251 252
            view = ViewAnalyze;
            break;
253
        case MainWindow::VIEW_PLAN:
dogmaphobic's avatar
dogmaphobic committed
254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271
            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();
    }
}

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

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
310 311
}

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

329
void MainToolBar::_remoteControlRSSIChanged(uint8_t rssi)
330
{
dogmaphobic's avatar
dogmaphobic committed
331
    // We only care if we have one single connection
332
    if(_connectionCount == 1) {
dogmaphobic's avatar
dogmaphobic committed
333 334 335 336 337 338 339 340
        // 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;
341 342
            emit remoteRSSIChanged(_remoteRSSI);
        }
343 344 345
    }
}

dogmaphobic's avatar
dogmaphobic committed
346 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
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);
    }
378
    // Update telemetry RSSI display
379 380 381 382 383 384 385
    if(_connectionCount != 1 && _telemetryRRSSI > 0) {
        _telemetryRRSSI = 0;
        emit telemetryRRSSIChanged(_telemetryRRSSI);
    }
    if(_connectionCount != 1 && _telemetryLRSSI > 0) {
        _telemetryLRSSI = 0;
        emit telemetryLRSSIChanged(_telemetryLRSSI);
386
    }
387 388
    if(_connectionCount != 1 && _remoteRSSI > 0) {
        _remoteRSSI = 0;
dogmaphobic's avatar
dogmaphobic committed
389
        emit remoteRSSIChanged(_remoteRSSI);
390
    }
dogmaphobic's avatar
dogmaphobic committed
391 392
}

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

void MainToolBar::_heightChanged(double height)
{
    setMinimumHeight(height);
    setMaximumHeight(height);
}
404 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

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