Browse Source

Merge pull request #1790 from DonLakeFlyer/ModelessMessages

Modeless messages
QGC4.4
Don Gagne 10 years ago
parent
commit
9a2774f712
  1. 5
      src/FactSystem/ParameterLoader.cc
  2. 5
      src/uas/UASMessageHandler.cc
  3. 8
      src/uas/UASMessageHandler.h
  4. 41
      src/ui/toolbar/MainToolBar.cc
  5. 8
      src/ui/toolbar/MainToolBar.h
  6. 13
      src/ui/toolbar/MainToolBar.qml

5
src/FactSystem/ParameterLoader.cc

@ -759,6 +759,7 @@ void ParameterLoader::_checkInitialLoadComplete(void)
if (msgHandler->getErrorCountTotal()) { if (msgHandler->getErrorCountTotal()) {
QString errors; QString errors;
bool firstError = true; bool firstError = true;
bool errorsFound = false;
msgHandler->lockAccess(); msgHandler->lockAccess();
foreach (UASMessage* msg, msgHandler->messages()) { foreach (UASMessage* msg, msgHandler->messages()) {
@ -769,11 +770,13 @@ void ParameterLoader::_checkInitialLoadComplete(void)
errors += " - "; errors += " - ";
errors += msg->getText(); errors += msg->getText();
firstError = false; firstError = false;
errorsFound = true;
} }
} }
msgHandler->showErrorsInToolbar();
msgHandler->unlockAccess(); msgHandler->unlockAccess();
if (!firstError) { if (errorsFound) {
QString errorMsg = QString("Errors were detected during vehicle startup. You should resolve these prior to flight.\n%1").arg(errors); QString errorMsg = QString("Errors were detected during vehicle startup. You should resolve these prior to flight.\n%1").arg(errors);
qgcApp()->showToolBarMessage(errorMsg); qgcApp()->showToolBarMessage(errorMsg);
} }

5
src/uas/UASMessageHandler.cc

@ -60,6 +60,7 @@ UASMessageHandler::UASMessageHandler(QObject *parent)
, _errorCountTotal(0) , _errorCountTotal(0)
, _warningCount(0) , _warningCount(0)
, _normalCount(0) , _normalCount(0)
, _showErrorsInToolbar(false)
{ {
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
emit textMessageReceived(NULL); emit textMessageReceived(NULL);
@ -184,6 +185,10 @@ void UASMessageHandler::handleTextMessage(int, int compId, int severity, QString
_mutex.unlock(); _mutex.unlock();
emit textMessageReceived(message); emit textMessageReceived(message);
emit textMessageCountChanged(count); emit textMessageCountChanged(count);
if (_showErrorsInToolbar && message->severityIsError()) {
qgcApp()->showToolBarMessage(message->getText());
}
} }
int UASMessageHandler::getErrorCountTotal() { int UASMessageHandler::getErrorCountTotal() {

8
src/uas/UASMessageHandler.h

@ -81,6 +81,7 @@ class UASMessageHandler : public QGCSingleton
{ {
Q_OBJECT Q_OBJECT
DECLARE_QGC_SINGLETON(UASMessageHandler, UASMessageHandler) DECLARE_QGC_SINGLETON(UASMessageHandler, UASMessageHandler)
public: public:
explicit UASMessageHandler(QObject *parent = 0); explicit UASMessageHandler(QObject *parent = 0);
~UASMessageHandler(); ~UASMessageHandler();
@ -120,6 +121,10 @@ public:
* @brief Get latest error message * @brief Get latest error message
*/ */
QString getLatestError() { return _latestError; } QString getLatestError() { return _latestError; }
/// Begin to show message which are errors in the toolbar
void showErrorsInToolbar(void) { _showErrorsInToolbar = true; }
public slots: public slots:
/** /**
* @brief Set currently active UAS * @brief Set currently active UAS
@ -134,6 +139,7 @@ public slots:
* @param text Message Text * @param text Message Text
*/ */
void handleTextMessage(int uasid, int componentid, int severity, QString text); void handleTextMessage(int uasid, int componentid, int severity, QString text);
signals: signals:
/** /**
* @brief Sent out when new message arrives * @brief Sent out when new message arrives
@ -145,6 +151,7 @@ signals:
* @param count The new message count * @param count The new message count
*/ */
void textMessageCountChanged(int count); void textMessageCountChanged(int count);
private: private:
// Stores the UAS that we're currently receiving messages from. // Stores the UAS that we're currently receiving messages from.
UASInterface* _activeUAS; UASInterface* _activeUAS;
@ -155,6 +162,7 @@ private:
int _warningCount; int _warningCount;
int _normalCount; int _normalCount;
QString _latestError; QString _latestError;
bool _showErrorsInToolbar;
}; };
#endif // QGCMESSAGEHANDLER_H #endif // QGCMESSAGEHANDLER_H

41
src/ui/toolbar/MainToolBar.cc

@ -56,6 +56,7 @@ MainToolBar::MainToolBar(QWidget* parent)
, _telemetryRRSSI(0) , _telemetryRRSSI(0)
, _telemetryLRSSI(0) , _telemetryLRSSI(0)
, _rollDownMessages(0) , _rollDownMessages(0)
, _toolbarMessageVisible(false)
{ {
setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding);
setObjectName("MainToolBar"); setObjectName("MainToolBar");
@ -404,3 +405,43 @@ void MainToolBar::_heightChanged(double height)
setMinimumHeight(height); setMinimumHeight(height);
setMaximumHeight(height); setMaximumHeight(height);
} }
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();
}

8
src/ui/toolbar/MainToolBar.h

@ -68,6 +68,7 @@ public:
Q_INVOKABLE void onConnect(QString conf); Q_INVOKABLE void onConnect(QString conf);
Q_INVOKABLE void onDisconnect(QString conf); Q_INVOKABLE void onDisconnect(QString conf);
Q_INVOKABLE void onEnterMessageArea(int x, int y); Q_INVOKABLE void onEnterMessageArea(int x, int y);
Q_INVOKABLE void onToolBarMessageClosed(void);
Q_PROPERTY(double height MEMBER _toolbarHeight NOTIFY heightChanged) Q_PROPERTY(double height MEMBER _toolbarHeight NOTIFY heightChanged)
Q_PROPERTY(ViewType_t currentView MEMBER _currentView NOTIFY currentViewChanged) Q_PROPERTY(ViewType_t currentView MEMBER _currentView NOTIFY currentViewChanged)
@ -91,7 +92,7 @@ public:
int telemetryLRSSI () { return _telemetryLRSSI; } int telemetryLRSSI () { return _telemetryLRSSI; }
int connectionCount () { return _connectionCount; } int connectionCount () { return _connectionCount; }
void showToolBarMessage(const QString& message) { emit showMessage(message); } void showToolBarMessage(const QString& message);
signals: signals:
void connectionCountChanged (int count); void connectionCountChanged (int count);
@ -123,6 +124,7 @@ private slots:
void _remoteControlRSSIChanged (uint8_t rssi); void _remoteControlRSSIChanged (uint8_t rssi);
void _telemetryChanged (LinkInterface* link, unsigned rxerrors, unsigned fixed, unsigned rssi, unsigned remrssi, unsigned txbuf, unsigned noise, unsigned remnoise); void _telemetryChanged (LinkInterface* link, unsigned rxerrors, unsigned fixed, unsigned rssi, unsigned remrssi, unsigned txbuf, unsigned noise, unsigned remnoise);
void _heightChanged (double height); void _heightChanged (double height);
void _delayedShowToolBarMessage (void);
private: private:
void _updateConnection (LinkInterface *disconnectedLink = NULL); void _updateConnection (LinkInterface *disconnectedLink = NULL);
@ -148,6 +150,10 @@ private:
double _toolbarHeight; double _toolbarHeight;
UASMessageViewRollDown* _rollDownMessages; UASMessageViewRollDown* _rollDownMessages;
bool _toolbarMessageVisible;
QStringList _toolbarMessageQueue;
QMutex _toolbarMessageQueueMutex;
}; };
#endif // MAINTOOLBAR_H #endif // MAINTOOLBAR_H

13
src/ui/toolbar/MainToolBar.qml

@ -68,7 +68,11 @@ Rectangle {
onShowMessage: { onShowMessage: {
toolBarMessage.text = message toolBarMessage.text = message
mainToolBar.height = toolBarHeight + toolBarMessage.contentHeight + verticalMargins if (toolBarMessage.contentHeight > toolBarMessageCloseButton.height) {
mainToolBar.height = toolBarHeight + toolBarMessage.contentHeight + (verticalMargins * 2)
} else {
mainToolBar.height = toolBarHeight + toolBarMessageCloseButton.height + (verticalMargins * 2)
}
toolBarMessageArea.visible = true toolBarMessageArea.visible = true
} }
} }
@ -772,7 +776,10 @@ Rectangle {
// Toolbar message area // Toolbar message area
Rectangle { Rectangle {
id: toolBarMessageArea id: toolBarMessageArea
anchors.margins: horizontalMargins anchors.leftMargin: horizontalMargins
anchors.rightMargin: horizontalMargins
anchors.topMargin: verticalMargins
anchors.bottomMargin: verticalMargins
anchors.top: progressBar.bottom anchors.top: progressBar.bottom
anchors.bottom: parent.bottom anchors.bottom: parent.bottom
anchors.left: parent.left anchors.left: parent.left
@ -790,7 +797,6 @@ Rectangle {
QGCButton { QGCButton {
id: toolBarMessageCloseButton id: toolBarMessageCloseButton
anchors.rightMargin: horizontalMargins anchors.rightMargin: horizontalMargins
anchors.topMargin: verticalMargins
anchors.top: parent.top anchors.top: parent.top
anchors.right: parent.right anchors.right: parent.right
primary: true primary: true
@ -799,6 +805,7 @@ Rectangle {
onClicked: { onClicked: {
parent.visible = false parent.visible = false
mainToolBar.height = toolBarHeight mainToolBar.height = toolBarHeight
mainToolBar.onToolBarMessageClosed()
} }
} }
} }

Loading…
Cancel
Save