Commit 1a71942d authored by Lorenz Meier's avatar Lorenz Meier

Merge pull request #2255 from dogmaphobic/messageScreen

New system message dialog.
parents eb13a148 921046bf
......@@ -44,6 +44,7 @@ Item {
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
property real avaiableHeight: parent.height
property bool interactive: true
readonly property bool isBackgroundDark: _mainIsMap ? (_flightMap ? _flightMap.isSatelliteMap : true) : true
......@@ -85,6 +86,11 @@ Item {
FlightDisplayViewController { id: _controller }
onInteractiveChanged: {
if(_flightMap)
_flightMap.interactive = interactive
}
function reloadContents() {
if(_flightVideo) {
_flightVideo.visible = false
......
......@@ -27,7 +27,6 @@
#include "LinkManager.h"
#include "FirmwarePlugin.h"
#include "AutoPilotPluginManager.h"
#include "UASMessageHandler.h"
#include "UAS.h"
#include "JoystickManager.h"
#include "MissionManager.h"
......@@ -111,7 +110,7 @@ Vehicle::Vehicle(LinkInterface* link,
_mavlink = qgcApp()->toolbox()->mavlinkProtocol();
connect(_mavlink, &MAVLinkProtocol::messageReceived, this, &Vehicle::_mavlinkMessageReceived);
connect(_mavlink, &MAVLinkProtocol::messageReceived, this, &Vehicle::_mavlinkMessageReceived);
connect(this, &Vehicle::_sendMessageOnThread, this, &Vehicle::_sendMessage, Qt::QueuedConnection);
_uas = new UAS(_mavlink, this, _firmwarePluginManager);
......@@ -143,7 +142,8 @@ Vehicle::Vehicle(LinkInterface* link,
_currentHeartbeatTimeout = 0;
emit heartbeatTimeoutChanged();
// Listen for system messages
connect(qgcApp()->toolbox()->uasMessageHandler(), &UASMessageHandler::textMessageCountChanged, this, &Vehicle::_handleTextMessage);
connect(qgcApp()->toolbox()->uasMessageHandler(), &UASMessageHandler::textMessageCountChanged, this, &Vehicle::_handleTextMessage);
connect(qgcApp()->toolbox()->uasMessageHandler(), &UASMessageHandler::textMessageReceived, this, &Vehicle::_handletextMessageReceived);
// Now connect the new UAS
connect(_mav, SIGNAL(attitudeChanged (UASInterface*,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*, double, double, double, quint64)));
connect(_mav, SIGNAL(attitudeChanged (UASInterface*,int,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*,int,double, double, double, quint64)));
......@@ -594,6 +594,24 @@ QString Vehicle::getMavIconColor()
return QString("black");
}
QString Vehicle::formatedMessages()
{
QString messages;
foreach(UASMessage* message, qgcApp()->toolbox()->uasMessageHandler()->messages()) {
messages += message->getFormatedText();
}
return messages;
}
void Vehicle::_handletextMessageReceived(UASMessage* message)
{
if(message)
{
_formatedMessage = message->getFormatedText();
emit formatedMessageChanged();
}
}
void Vehicle::_updateBatteryRemaining(UASInterface*, double voltage, double, double percent, int)
{
......
......@@ -35,6 +35,7 @@
#include "MissionItem.h"
#include "QmlObjectListModel.h"
#include "MAVLinkProtocol.h"
#include "UASMessageHandler.h"
class UAS;
class UASInterface;
......@@ -45,6 +46,7 @@ class AutoPilotPluginManager;
class MissionManager;
class ParameterLoader;
class JoystickManager;
class UASMessage;
Q_DECLARE_LOGGING_CATEGORY(VehicleLog)
......@@ -101,6 +103,8 @@ public:
Q_PROPERTY(bool messageTypeError READ messageTypeError NOTIFY messageTypeChanged)
Q_PROPERTY(int newMessageCount READ newMessageCount NOTIFY newMessageCountChanged)
Q_PROPERTY(int messageCount READ messageCount NOTIFY messageCountChanged)
Q_PROPERTY(QString formatedMessages READ formatedMessages NOTIFY formatedMessagesChanged)
Q_PROPERTY(QString formatedMessage READ formatedMessage NOTIFY formatedMessageChanged)
Q_PROPERTY(QString latestError READ latestError NOTIFY latestErrorChanged)
Q_PROPERTY(int joystickMode READ joystickMode WRITE setJoystickMode NOTIFY joystickModeChanged)
Q_PROPERTY(QStringList joystickModes READ joystickModes CONSTANT)
......@@ -116,6 +120,9 @@ public:
Q_INVOKABLE QString getMavIconColor();
// Called when the message drop-down is invoked to clear current count
Q_INVOKABLE void resetMessages();
// Property accessors
QGeoCoordinate coordinate(void) { return _coordinate; }
......@@ -216,15 +223,14 @@ public:
ALTITUDEAMSL_CHANGED
};
// Called when the message drop-down is invoked to clear current count
void resetMessages();
bool messageTypeNone () { return _currentMessageType == MessageNone; }
bool messageTypeNormal () { return _currentMessageType == MessageNormal; }
bool messageTypeWarning () { return _currentMessageType == MessageWarning; }
bool messageTypeError () { return _currentMessageType == MessageError; }
int newMessageCount () { return _currentMessageCount; }
int messageCount () { return _messageCount; }
QString formatedMessages ();
QString formatedMessage () { return _formatedMessage; }
QString latestError () { return _latestError; }
float roll () { return _roll; }
float pitch () { return _pitch; }
......@@ -273,6 +279,8 @@ signals:
void messageTypeChanged ();
void newMessageCountChanged ();
void messageCountChanged ();
void formatedMessagesChanged();
void formatedMessageChanged ();
void latestErrorChanged ();
void rollChanged ();
void pitchChanged ();
......@@ -304,6 +312,7 @@ private slots:
void _communicationInactivityTimedOut(void);
void _handleTextMessage (int newCount);
void _handletextMessageReceived (UASMessage* message);
/** @brief Attitude from main autopilot / system state */
void _updateAttitude (UASInterface* uas, double roll, double pitch, double yaw, quint64 timestamp);
/** @brief Attitude from one specific component / redundant autopilot */
......@@ -394,6 +403,7 @@ private:
int _satelliteCount;
int _satelliteLock;
int _updateCount;
QString _formatedMessage;
MissionManager* _missionManager;
bool _missionManagerInitialRequestComplete;
......
......@@ -37,6 +37,7 @@ This file is part of the QGROUNDCONTROL project
#include "Vehicle.h"
#include "QGCToolbox.h"
class Vehicle;
class UASInterface;
class UASMessageHandler;
class QGCApplication;
......@@ -82,7 +83,7 @@ private:
class UASMessageHandler : public QGCTool
{
Q_OBJECT
public:
explicit UASMessageHandler(QGCApplication* app);
~UASMessageHandler();
......@@ -123,10 +124,10 @@ public:
* @brief Get latest error message
*/
QString getLatestError() { return _latestError; }
/// Begin to show message which are errors in the toolbar
void showErrorsInToolbar(void) { _showErrorsInToolbar = true; }
// Override from QGCTool
virtual void setToolbox(QGCToolbox *toolbox);
......@@ -139,7 +140,7 @@ public slots:
* @param text Message Text
*/
void handleTextMessage(int uasid, int componentid, int severity, QString text);
signals:
/**
* @brief Sent out when new message arrives
......@@ -151,10 +152,10 @@ signals:
* @param count The new message count
*/
void textMessageCountChanged(int count);
private slots:
void _activeVehicleChanged(Vehicle* vehicle);
private:
UASInterface* _activeUAS;
QVector<UASMessage*> _messages;
......
......@@ -125,6 +125,10 @@ Item {
}
}
function setMapInteractive(enabled) {
flightView.interactive = enabled
}
//-- Left Settings Menu
Loader {
id: leftPanel
......
......@@ -50,6 +50,8 @@ Rectangle {
property bool isBackgroundDark: true
property bool opaqueBackground: false
property string formatedMessage: activeVehicle ? activeVehicle.formatedMessage : ""
/*
Dev System (Mac OS)
......@@ -146,6 +148,28 @@ Rectangle {
MainToolBarController { id: _controller }
onFormatedMessageChanged: {
if(messageArea.visible) {
messageText.append(formatedMessage)
//-- Hack to scroll down
messageFlick.flick(0,-500)
}
}
function showMessageArea() {
if(multiVehicleManager.activeVehicleAvailable) {
messageText.text = activeVehicle.formatedMessages
//-- Hack to scroll to last message
for (var i = 0; i < activeVehicle.messageCount; i++)
messageFlick.flick(0,-5000)
activeVehicle.resetMessages()
} else {
messageText.text = "No Messages"
}
messageArea.visible = true
mainWindow.setMapInteractive(false)
}
function showToolbarMessage(message) {
toolBarMessage.text = message
toolBarMessageArea.visible = true
......@@ -248,6 +272,7 @@ Rectangle {
}
Item {
id: vehicleIndicators
visible: showMavStatus() && !connectionStatus.visible
height: mainWindow.tbCellHeight
width: (toolBar.width - viewRow.width - connectRow.width)
......@@ -261,6 +286,55 @@ Rectangle {
}
}
//-------------------------------------------------------------------------
//-- System Message Area
Rectangle {
id: messageArea
width: mainWindow.width * 0.5
height: mainWindow.height * 0.5
anchors.top: parent.bottom
anchors.horizontalCenter: parent.horizontalCenter
color: Qt.rgba(0,0,0,0.75)
visible: false
radius: ScreenTools.defaultFontPixelHeight * 0.5
Flickable {
id: messageFlick
anchors.margins: ScreenTools.defaultFontPixelHeight
anchors.fill: parent
contentHeight: messageText.height
contentWidth: messageText.width
boundsBehavior: Flickable.StopAtBounds
pixelAligned: true
clip: true
TextEdit {
id: messageText
readOnly: true
textFormat: TextEdit.RichText
color: "white"
}
}
//-- Dismiss System Message
Image {
anchors.margins: ScreenTools.defaultFontPixelHeight
anchors.top: parent.top
anchors.right: parent.right
width: ScreenTools.defaultFontPixelHeight * 1.5
height: ScreenTools.defaultFontPixelHeight * 1.5
source: "/res/XDelete.svg"
fillMode: Image.PreserveAspectFit
mipmap: true
smooth: true
MouseArea {
anchors.fill: parent
onClicked: {
messageText.text = ""
messageArea.visible = false
mainWindow.setMapInteractive(true)
}
}
}
}
QGCLabel {
id: connectionStatus
visible: (_controller.connectionCount > 0 && multiVehicleManager.activeVehicleAvailable && activeVehicle.heartbeatTimeout != 0)
......
......@@ -49,23 +49,22 @@ MainToolBarController::MainToolBarController(QObject* parent)
, _remoteRSSIstore(100.0)
, _telemetryRRSSI(0)
, _telemetryLRSSI(0)
, _rollDownMessages(0)
, _toolbarMessageVisible(false)
{
emit configListChanged();
emit connectionCountChanged(_connectionCount);
_activeVehicleChanged(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle());
// Link signals
connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkConfigurationChanged, this, &MainToolBarController::_updateConfigurations);
connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkConnected, this, &MainToolBarController::_linkConnected);
connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkDisconnected, this, &MainToolBarController::_linkDisconnected);
// RSSI (didn't like standard connection)
connect(qgcApp()->toolbox()->mavlinkProtocol(),
SIGNAL(radioStatusChanged(LinkInterface*, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned)), this,
SLOT(_telemetryChanged(LinkInterface*, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned)));
connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &MainToolBarController::_activeVehicleChanged);
}
......@@ -137,42 +136,6 @@ void MainToolBarController::onConnect(QString conf)
}
}
void MainToolBarController::onEnterMessageArea(int x, int y)
{
Q_UNUSED(x);
Q_UNUSED(y);
// If not already there and messages are actually present
if(!_rollDownMessages && qgcApp()->toolbox()->uasMessageHandler()->messages().count()) {
if (qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()) {
qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->resetMessages();
}
// FIXME: Position of the message dropdown is hacked right now to speed up Qml conversion
// Show messages
int dialogWidth = 400;
#if 0
x = x - (dialogWidth >> 1);
if(x < 0) x = 0;
y = height() / 3;
#endif
// Put dialog on top of the message alert icon
_rollDownMessages = new UASMessageViewRollDown(qgcApp()->toolbox()->uasMessageHandler(), MainWindow::instance());
_rollDownMessages->setAttribute(Qt::WA_DeleteOnClose);
_rollDownMessages->move(QPoint(100, 100));
_rollDownMessages->setMinimumSize(dialogWidth,200);
connect(_rollDownMessages, &UASMessageViewRollDown::closeWindow, this, &MainToolBarController::_leaveMessageView);
_rollDownMessages->show();
}
}
void MainToolBarController::_leaveMessageView()
{
// Mouse has left the message window area (and it has closed itself)
_rollDownMessages = NULL;
}
void MainToolBarController::_activeVehicleChanged(Vehicle* vehicle)
{
// Disconnect the previous one (if any)
......@@ -182,7 +145,7 @@ void MainToolBarController::_activeVehicleChanged(Vehicle* vehicle)
_mav = NULL;
_vehicle = NULL;
}
// Connect new system
if (vehicle)
{
......@@ -303,30 +266,30 @@ void MainToolBarController::_setProgressBarValue(float value)
void MainToolBarController::showToolBarMessage(const QString& message)
{
_toolbarMessageQueueMutex.lock();
if (_toolbarMessageQueue.count() == 0 && !_toolbarMessageVisible) {
QTimer::singleShot(500, this, &MainToolBarController::_delayedShowToolBarMessage);
}
_toolbarMessageQueue += message;
_toolbarMessageQueueMutex.unlock();
}
void MainToolBarController::_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);
......
......@@ -55,7 +55,6 @@ public:
Q_INVOKABLE void onFlyView();
Q_INVOKABLE void onConnect(QString conf);
Q_INVOKABLE void onDisconnect(QString conf);
Q_INVOKABLE void onEnterMessageArea(int x, int y);
Q_INVOKABLE void onToolBarMessageClosed(void);
Q_INVOKABLE void showSettings(void);
......@@ -73,9 +72,9 @@ public:
int telemetryRRSSI () { return _telemetryRRSSI; }
int telemetryLRSSI () { return _telemetryLRSSI; }
int connectionCount () { return _connectionCount; }
void showToolBarMessage(const QString& message);
signals:
void connectionCountChanged (int count);
void configListChanged ();
......@@ -85,7 +84,7 @@ signals:
void telemetryRRSSIChanged (int value);
void telemetryLRSSIChanged (int value);
void heightChanged (double height);
/// Shows a non-modal message below the toolbar
void showMessage(const QString& message);
......@@ -94,7 +93,6 @@ private slots:
void _updateConfigurations ();
void _linkConnected (LinkInterface* link);
void _linkDisconnected (LinkInterface* link);
void _leaveMessageView ();
void _setProgressBarValue (float value);
void _remoteControlRSSIChanged (uint8_t rssi);
void _telemetryChanged (LinkInterface* link, unsigned rxerrors, unsigned fixed, unsigned rssi, unsigned remrssi, unsigned txbuf, unsigned noise, unsigned remnoise);
......@@ -116,8 +114,6 @@ private:
int _telemetryLRSSI;
double _toolbarHeight;
UASMessageViewRollDown* _rollDownMessages;
bool _toolbarMessageVisible;
QStringList _toolbarMessageQueue;
QMutex _toolbarMessageQueueMutex;
......
......@@ -160,8 +160,7 @@ Row {
MouseArea {
anchors.fill: parent
onClicked: {
var p = mapToItem(toolBar, mouseX, mouseY);
_controller.onEnterMessageArea(p.x, p.y);
toolBar.showMessageArea()
}
}
}
......@@ -568,3 +567,5 @@ Row {
*/
} // Row
......@@ -105,56 +105,3 @@ void UASMessageViewWidget::handleTextMessage(UASMessage *message)
msgWidget->setUpdatesEnabled(true);
}
}
/*-------------------------------------------------------------------------------------
UASMessageViewRollDown
-------------------------------------------------------------------------------------*/
UASMessageViewRollDown::UASMessageViewRollDown(UASMessageHandler* uasMessageHandler, QWidget *parent)
: UASMessageView(parent)
, _uasMessageHandler(uasMessageHandler)
{
setAttribute(Qt::WA_TranslucentBackground);
setStyleSheet("background-color: rgba(0%,0%,0%,80%); border: 2px;");
QPlainTextEdit *msgWidget = ui()->plainTextEdit;
// Init Messages
_uasMessageHandler->lockAccess();
msgWidget->setUpdatesEnabled(false);
QVector<UASMessage*> messages = _uasMessageHandler->messages();
for(int i = 0; i < messages.count(); i++) {
msgWidget->appendHtml(messages.at(i)->getFormatedText());
}
QScrollBar *scroller = msgWidget->verticalScrollBar();
scroller->setValue(scroller->maximum());
msgWidget->setUpdatesEnabled(true);
connect(_uasMessageHandler, &UASMessageHandler::textMessageReceived, this, &UASMessageViewRollDown::handleTextMessage);
_uasMessageHandler->unlockAccess();
}
UASMessageViewRollDown::~UASMessageViewRollDown()
{
}
void UASMessageViewRollDown::handleTextMessage(UASMessage *message)
{
// Reset
if(!message) {
ui()->plainTextEdit->clear();
} else {
QPlainTextEdit *msgWidget = ui()->plainTextEdit;
// Turn off updates while we're appending content to avoid breaking the autoscroll behavior
msgWidget->setUpdatesEnabled(false);
QScrollBar *scroller = msgWidget->verticalScrollBar();
msgWidget->appendHtml(message->getFormatedText());
// Ensure text area scrolls correctly
scroller->setValue(scroller->maximum());
msgWidget->setUpdatesEnabled(true);
}
}
void UASMessageViewRollDown::leaveEvent(QEvent*)
{
emit closeWindow();
close();
}
......@@ -42,7 +42,7 @@ class UASMessageView;
class UASMessageView : public QWidget
{
Q_OBJECT
public:
explicit UASMessageView(QWidget *parent = 0);
virtual ~UASMessageView();
......@@ -70,25 +70,4 @@ private:
UASMessageHandler* _uasMessageHandler;
};
// Roll down Message View
class UASMessageViewRollDown : public UASMessageView
{
Q_OBJECT
public:
explicit UASMessageViewRollDown(UASMessageHandler* uasMessageHandler, QWidget *parent);
~UASMessageViewRollDown();
signals:
void closeWindow();
public slots:
void handleTextMessage(UASMessage* message);
protected:
void leaveEvent(QEvent* event);
private:
UASMessageHandler* _uasMessageHandler;
};
#endif // QGCMESSAGEVIEW_H
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment