diff --git a/rqt_console/resource/console_subscriber_dialog.ui b/rqt_console/resource/console_settings_dialog.ui similarity index 90% rename from rqt_console/resource/console_subscriber_dialog.ui rename to rqt_console/resource/console_settings_dialog.ui index 3f014b9c..684e9ca3 100644 --- a/rqt_console/resource/console_subscriber_dialog.ui +++ b/rqt_console/resource/console_settings_dialog.ui @@ -1,7 +1,7 @@ - ConsoleSubscriberDialog - + ConsoleSettingsDialog + Qt::ApplicationModal @@ -10,7 +10,7 @@ 0 0 368 - 119 + 123 @@ -71,8 +71,7 @@ - - + @@ -88,7 +87,7 @@ buttonBox accepted() - ConsoleSubscriberDialog + ConsoleSettingsDialog accept() @@ -104,7 +103,7 @@ buttonBox rejected() - ConsoleSubscriberDialog + ConsoleSettingsDialog reject() diff --git a/rqt_console/resource/console_widget.ui b/rqt_console/resource/console_widget.ui index acb9ab76..32e14b63 100644 --- a/rqt_console/resource/console_widget.ui +++ b/rqt_console/resource/console_widget.ui @@ -131,21 +131,30 @@ - + + + true + QAbstractItemView::SelectRows + + + 16 + 16 + + QAbstractItemView::ScrollPerPixel true - - 18 + + false - - 18 + + false @@ -218,7 +227,7 @@ - Message matching ANY of these rules will be highlighted + Messages matching ANY of these rules will be highlighted Highlight Messages... @@ -313,13 +322,6 @@ - - - ConsoleTableView - QTableView -
rqt_console.console_widget
-
-
diff --git a/rqt_console/resource/filters/custom_filter_widget.ui b/rqt_console/resource/filters/custom_filter_widget.ui index ec305eac..0aa39b27 100644 --- a/rqt_console/resource/filters/custom_filter_widget.ui +++ b/rqt_console/resource/filters/custom_filter_widget.ui @@ -54,7 +54,7 @@ - + 0 @@ -79,14 +79,27 @@ QAbstractItemView::NoEditTriggers + + true + QAbstractItemView::MultiSelection QListView::LeftToRight + + 1 + + + + + 20 + + + @@ -108,12 +121,18 @@ QAbstractItemView::NoEditTriggers + + true + QAbstractItemView::MultiSelection QListView::LeftToRight + + 1 + @@ -144,12 +163,18 @@ QAbstractItemView::NoEditTriggers + + true + QAbstractItemView::MultiSelection QListView::LeftToRight + + 1 + diff --git a/rqt_console/resource/filters/list_filter_widget.ui b/rqt_console/resource/filters/list_filter_widget.ui index 2437fe7e..79db7845 100644 --- a/rqt_console/resource/filters/list_filter_widget.ui +++ b/rqt_console/resource/filters/list_filter_widget.ui @@ -33,12 +33,18 @@ QAbstractItemView::NoEditTriggers + + true + QAbstractItemView::MultiSelection QListView::LeftToRight + + 1 + diff --git a/rqt_console/src/rqt_console/console.py b/rqt_console/src/rqt_console/console.py index ff4e4b38..c238d8ad 100644 --- a/rqt_console/src/rqt_console/console.py +++ b/rqt_console/src/rqt_console/console.py @@ -30,12 +30,16 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. +from rosgraph_msgs.msg import Log +import rospy + from python_qt_binding.QtCore import QMutex, QMutexLocker, QTimer from qt_gui.plugin import Plugin -from .console_subscriber import ConsoleSubscriber +from .console_settings_dialog import ConsoleSettingsDialog from .console_widget import ConsoleWidget +from .message import Message from .message_data_model import MessageDataModel from .message_proxy_model import MessageProxyModel @@ -52,54 +56,81 @@ def __init__(self, context): super(Console, self).__init__(context) self.setObjectName('Console') - self._datamodel = MessageDataModel() - self._proxymodel = MessageProxyModel() - self._proxymodel.setSourceModel(self._datamodel) + self._model = MessageDataModel() + self._proxy_model = MessageProxyModel() + self._proxy_model.setSourceModel(self._model) - self._mainwindow = ConsoleWidget(self._proxymodel) + self._widget = ConsoleWidget(self._proxy_model) if context.serial_number() > 1: - self._mainwindow.setWindowTitle(self._mainwindow.windowTitle() + (' (%d)' % context.serial_number())) - context.add_widget(self._mainwindow) - - self._consolesubscriber = ConsoleSubscriber(self.message_callback) + self._widget.setWindowTitle(self._widget.windowTitle() + (' (%d)' % context.serial_number())) + context.add_widget(self._widget) - # Timer and Mutex for flushing recieved messages to datamodel. - # Required since QSortProxyModel can not handle a high insert rate + # queue to store incoming data which get flushed periodically to the model + # required since QSortProxyModel can not handle a high insert rate + self._message_queue = [] self._mutex = QMutex() self._timer = QTimer() self._timer.timeout.connect(self.insert_messages) self._timer.start(100) - def insert_messages(self): + self._subscriber = None + self._topic = '/rosout_agg' + self._subscribe(self._topic) + + def queue_message(self, log_msg): """ - Callback for flushing incoming Log messages from the queue to the datamodel + Callback for adding an incomming message to the queue. """ - with QMutexLocker(self._mutex): - msgs = self._datamodel._insert_message_queue - self._datamodel._insert_message_queue = [] - self._datamodel.insert_rows(msgs) - self._mainwindow.update_status() + if not self._widget._paused: + msg = Console.convert_rosgraph_log_message(log_msg) + with QMutexLocker(self._mutex): + self._message_queue.append(msg) - def message_callback(self, msg): + @staticmethod + def convert_rosgraph_log_message(log_msg): + msg = Message() + msg.set_stamp_format('hh:mm:ss.ZZZ (yyyy-MM-dd)') + msg.message = log_msg.msg + msg.severity = log_msg.level + msg.node = log_msg.name + msg.stamp = (log_msg.header.stamp.secs, log_msg.header.stamp.nsecs) + msg.topics = sorted(log_msg.topics) + msg.location = log_msg.file + ':' + log_msg.function + ':' + str(log_msg.line) + return msg + + def insert_messages(self): """ - Callback for adding an incomming message to the queue + Callback for flushing incoming Log messages from the queue to the model. """ - if not self._datamodel._paused: - with QMutexLocker(self._mutex): - self._datamodel._insert_message_queue.append(msg) + with QMutexLocker(self._mutex): + msgs = self._message_queue + self._message_queue = [] + if msgs: + self._model.insert_rows(msgs) def shutdown_plugin(self): - self._consolesubscriber.unsubscribe_topic() + self._subscriber.unregister() self._timer.stop() - self._mainwindow.cleanup_browsers_on_close() + self._widget.cleanup_browsers_on_close() def save_settings(self, plugin_settings, instance_settings): - self._mainwindow.save_settings(plugin_settings, instance_settings) + self._widget.save_settings(plugin_settings, instance_settings) def restore_settings(self, plugin_settings, instance_settings): - self._mainwindow.restore_settings(plugin_settings, instance_settings) + self._widget.restore_settings(plugin_settings, instance_settings) def trigger_configuration(self): - self._consolesubscriber.set_message_limit(self._datamodel._message_limit) - if self._consolesubscriber.show_dialog(): - self._datamodel.set_message_limit(self._consolesubscriber.get_message_limit()) + topics = [t for t in rospy.get_published_topics() if t[1] == 'rosgraph_msgs/Log'] + topics.sort(key=lambda tup: tup[0]) + dialog = ConsoleSettingsDialog(topics) + (topic, message_limit) = dialog.query(self._topic, self._model.get_message_limit()) + if topic != self._topic: + self._subscribe(topic) + if message_limit != self._model.get_message_limit(): + self._model.set_message_limit(message_limit) + + def _subscribe(self, topic): + if self._subscriber: + self._subscriber.unregister() + self._subscriber = rospy.Subscriber(topic, Log, self.queue_message) + self._currenttopic = topic diff --git a/rqt_console/src/rqt_console/console_subscriber_dialog.py b/rqt_console/src/rqt_console/console_settings_dialog.py similarity index 63% rename from rqt_console/src/rqt_console/console_subscriber_dialog.py rename to rqt_console/src/rqt_console/console_settings_dialog.py index bb9e87d5..4db99821 100644 --- a/rqt_console/src/rqt_console/console_subscriber_dialog.py +++ b/rqt_console/src/rqt_console/console_settings_dialog.py @@ -36,23 +36,40 @@ from python_qt_binding import loadUi from python_qt_binding.QtGui import QDialog +from rqt_logger_level.logger_level_widget import LoggerLevelWidget +from rqt_logger_level.logger_level_service_caller import LoggerLevelServiceCaller -class ConsoleSubscriberDialog(QDialog): + +class ConsoleSettingsDialog(QDialog): """ - Dialog for use with ConsoleSubscriber class to change the subscribed topic - and alter the message buffer size + Dialog to change the subscribed topic and alter the message buffer size. """ - def __init__(self, topics, limit): + def __init__(self, topics): """ :param topics: list of topics to allow switching, ''list of string'' :param limit: displayed in the message buffer size spin box, ''int'' """ - super(ConsoleSubscriberDialog, self).__init__() + super(ConsoleSettingsDialog, self).__init__() rp = rospkg.RosPack() - ui_file = os.path.join(rp.get_path('rqt_console'), 'resource', 'console_subscriber_dialog.ui') + ui_file = os.path.join(rp.get_path('rqt_console'), 'resource', 'console_settings_dialog.ui') loadUi(ui_file, self) - topics.sort(reverse=True) for topic in topics: - if topic[1].find('Log') != -1: - self.topic_combo.addItem(topic[0] + ' (' + topic[1] + ')') - self.buffer_size_spin.setValue(limit) + self.topic_combo.addItem(topic[0] + ' (' + topic[1] + ')', topic[0]) + + self._service_caller = LoggerLevelServiceCaller() + self._logger_widget = LoggerLevelWidget(self._service_caller) + self.levelsLayout.addWidget(self._logger_widget) + self.adjustSize() + + def query(self, topic, buffer_size): + index = self.topic_combo.findData(topic) + if index != -1: + self.topic_combo.setCurrentIndex(index) + self.buffer_size_spin.setValue(buffer_size) + ok = self.exec_() + if ok == 1: + index = self.topic_combo.currentIndex() + if index != -1: + topic = self.topic_combo.itemData(index) + buffer_size = self.buffer_size_spin.value() + return topic, buffer_size diff --git a/rqt_console/src/rqt_console/console_subscriber.py b/rqt_console/src/rqt_console/console_subscriber.py deleted file mode 100644 index d791fdf9..00000000 --- a/rqt_console/src/rqt_console/console_subscriber.py +++ /dev/null @@ -1,92 +0,0 @@ -# Software License Agreement (BSD License) -# -# Copyright (c) 2012, Willow Garage, Inc. -# All rights reserved. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions -# are met: -# -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# * Redistributions in binary form must reproduce the above -# copyright notice, this list of conditions and the following -# disclaimer in the documentation and/or other materials provided -# with the distribution. -# * Neither the name of Willow Garage, Inc. nor the names of its -# contributors may be used to endorse or promote products derived -# from this software without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. - -from rosgraph_msgs.msg import Log -import rospy - -from python_qt_binding.QtCore import QObject - -from .console_subscriber_dialog import ConsoleSubscriberDialog -from rqt_logger_level.logger_level_widget import LoggerLevelWidget -from rqt_logger_level.logger_level_service_caller import LoggerLevelServiceCaller - - -class ConsoleSubscriber(QObject): - """ - Subscribes to the /rosout_agg topic if a callback is provided and allows - the user to change the currently subscribed topic. - Also holds the message limit from ConsolesubscriberDialog - """ - def __init__(self, callback=None): - """ - :param callback: callback function to invoke when receiving a message ''function'' - """ - super(ConsoleSubscriber, self).__init__() - self._msgcallback = callback - self._currenttopic = "/rosout_agg" - self._messagelimit = 20000 - if callback is not None: - self._sub = rospy.Subscriber(self._currenttopic, Log, self._msgcallback) - - def show_dialog(self): - self._service_caller = LoggerLevelServiceCaller() - self._logger_widget = LoggerLevelWidget(self._service_caller) - dialog = ConsoleSubscriberDialog(rospy.get_published_topics(), self._messagelimit) - for index in range(dialog.topic_combo.count()): - if str(dialog.topic_combo.itemText(index)).find(self._currenttopic) != -1: - dialog.topic_combo.setCurrentIndex(index) - dialog.buffer_size_spin.setValue = self._messagelimit - dialog.levelsLayout.addWidget(self._logger_widget) - dialog.adjustSize() - ok = dialog.exec_() - ok = ok == 1 - if ok: - temp = dialog.topic_combo.currentText() - self.subscribe_topic(temp[:temp.find(' (')].strip()) - self._messagelimit = dialog.buffer_size_spin.value() - return ok - - def unsubscribe_topic(self): - if self._msgcallback is not None: - self._sub.unregister() - - def subscribe_topic(self, topic): - if self._msgcallback is not None: - self.unsubscribe_topic() - self._sub = rospy.Subscriber(topic, Log, self._msgcallback) - self._currenttopic = topic - - def get_message_limit(self): - return self._messagelimit - - def set_message_limit(self, limit): - self._messagelimit = limit diff --git a/rqt_console/src/rqt_console/console_widget.py b/rqt_console/src/rqt_console/console_widget.py index 81e5d16b..4aa96803 100644 --- a/rqt_console/src/rqt_console/console_widget.py +++ b/rqt_console/src/rqt_console/console_widget.py @@ -34,8 +34,8 @@ import rospkg from python_qt_binding import loadUi -from python_qt_binding.QtGui import QApplication, QCursor, QFileDialog, QIcon, QItemSelectionModel, QMenu, QMessageBox, QTableView, QWidget -from python_qt_binding.QtCore import QRect, QRegExp, Qt, qWarning +from python_qt_binding.QtGui import QApplication, QCursor, QFileDialog, QHeaderView,QIcon, QMenu, QMessageBox, QTableView, QWidget +from python_qt_binding.QtCore import QRegExp, Qt, qWarning import time import datetime @@ -56,42 +56,50 @@ from .filters.text_filter_widget import TextFilterWidget from .filters.time_filter_widget import TimeFilterWidget -from .text_browse_dialog import TextBrowseDialog - +from .message import Message +from .message_data_model import MessageDataModel -class ConsoleTableView(QTableView): - def __init__(self, parent=None): - super(ConsoleTableView, self).__init__() +from .text_browse_dialog import TextBrowseDialog class ConsoleWidget(QWidget): """ Primary widget for the rqt_console plugin. """ - def __init__(self, proxymodel, minimal=False): + def __init__(self, proxy_model, minimal=False): """ :param proxymodel: the proxy model to display in the widget,''QSortFilterProxyModel'' :param minimal: if true the load, save and column buttons will be hidden as well as the filter splitter, ''bool'' """ super(ConsoleWidget, self).__init__() + self._proxy_model = proxy_model + self._model = self._proxy_model.sourceModel() + self._paused = False + + # These are lists of Tuples = (,) + self._exclude_filters = [] + self._highlight_filters = [] rp = rospkg.RosPack() ui_file = os.path.join(rp.get_path('rqt_console'), 'resource', 'console_widget.ui') - loadUi(ui_file, self, {'ConsoleTableView': ConsoleTableView}) + loadUi(ui_file, self) if minimal: self.load_button.hide() self.save_button.hide() self.column_resize_button.hide() self.setObjectName('ConsoleWidget') - self.table_view.setModel(proxymodel) - self._proxymodel = proxymodel - self._datamodel = proxymodel.sourceModel() + self.table_view.setModel(proxy_model) - self._columnwidth = (600, 140, 200, 200, 200, 600) + self._columnwidth = (60, 100, 70, 100, 100, 100, 100) for idx, width in enumerate(self._columnwidth): self.table_view.horizontalHeader().resizeSection(idx, width) - self.table_view.sortByColumn(3, Qt.DescendingOrder) + + def update_sort_indicator(logical_index, order): + if logical_index == 0: + self._proxy_model.sort(-1) + self.table_view.horizontalHeader().setSortIndicatorShown(logical_index != 0) + self.table_view.horizontalHeader().sortIndicatorChanged.connect(update_sort_indicator) self.add_exclude_button.setIcon(QIcon.fromTheme('list-add')) self.add_highlight_button.setIcon(QIcon.fromTheme('list-add')) @@ -111,13 +119,8 @@ def __init__(self, proxymodel, minimal=False): self.table_view.mouseDoubleClickEvent = self._handle_mouse_double_click self.table_view.mousePressEvent = self._handle_mouse_press self.table_view.keyPressEvent = self._handle_custom_keypress - self.severitylist = self._datamodel.get_severity_list() - # These are lists of Tuples = (,) - self._exclude_filters = [] - self._highlight_filters = [] - - self.highlight_exclude_button.clicked[bool].connect(self._proxymodel.set_show_highlighted_only) + self.highlight_exclude_button.clicked[bool].connect(self._proxy_model.set_show_highlighted_only) self.add_highlight_button.clicked.connect(self._add_highlight_filter) self.add_exclude_button.clicked.connect(self._add_exclude_filter) @@ -125,19 +128,25 @@ def __init__(self, proxymodel, minimal=False): # Filter factory dictionary: # index 0 is a label describing the widget, index 1 is the class that provides filtering logic # index 2 is the widget that sets the data in the filter class, index 3 are the arguments for the widget class constructor - self.filter_factory = {'message': (self.tr('...containing'), MessageFilter, TextFilterWidget, []), - 'severity': (self.tr('...with severities'), SeverityFilter, ListFilterWidget, [self._datamodel.get_severity_list]), - 'node': (self.tr('...from node'), NodeFilter, ListFilterWidget, [self._datamodel.get_unique_col_data, 2]), - 'time': (self.tr('...from time range'), TimeFilter, TimeFilterWidget, [self.get_time_range_from_selection]), - 'topic': (self.tr('...from topic'), TopicFilter, ListFilterWidget, [self._datamodel.get_unique_col_data, 4]), - 'location': (self.tr('...from location'), LocationFilter, TextFilterWidget, []), - 'custom': (self.tr('Custom'), CustomFilter, CustomFilterWidget, [self._datamodel.get_severity_list, self._datamodel.get_unique_col_data, 2, self._datamodel.get_unique_col_data, 4])} + self._filter_factory_order = ['message', 'severity', 'node', 'time', 'topic', 'location', 'custom'] + self.filter_factory = {'message': (self.tr('...containing'), MessageFilter, TextFilterWidget), + 'severity': (self.tr('...with severities'), SeverityFilter, ListFilterWidget, self._model.get_severity_dict), + 'node': (self.tr('...from node'), NodeFilter, ListFilterWidget, self._model.get_unique_nodes), + 'time': (self.tr('...from time range'), TimeFilter, TimeFilterWidget, self.get_time_range_from_selection), + 'topic': (self.tr('...from topic'), TopicFilter, ListFilterWidget, self._model.get_unique_topics), + 'location': (self.tr('...from location'), LocationFilter, TextFilterWidget), + 'custom': (self.tr('Custom'), CustomFilter, CustomFilterWidget, [self._model.get_severity_dict, self._model.get_unique_nodes, self._model.get_unique_topics])} + + self._model.rowsInserted.connect(self.update_status) + self._model.rowsRemoved.connect(self.update_status) + self._proxy_model.rowsInserted.connect(self.update_status) + self._proxy_model.rowsRemoved.connect(self.update_status) # list of TextBrowserDialogs to close when cleaning up self._browsers = [] # This defaults the filters panel to start by taking 50% of the available space - if(minimal): + if minimal: self.table_splitter.setSizes([1, 0]) else: self.table_splitter.setSizes([1, 1]) @@ -160,7 +169,7 @@ def get_message_summary(self, start_time_offset=None, end_time_offset=None): else: end_time = None - message_subset = self._datamodel.get_message_list(start_time, end_time) + message_subset = self._model.get_message_between(start_time, end_time) class Message_Summary(object): __slots__ = 'fatal', 'error', 'warn', 'info', 'debug' @@ -172,17 +181,18 @@ def __init__(self, messages): self.info = 0 self.debug = 0 for message in messages: - severity = message.get_data(1) - if severity == 'Debug': + if message.severity == Message.DEBUG: self.debug += 1 - elif severity == 'Info': + elif message.severity == Message.INFO: self.info += 1 - elif severity == 'Warn': + elif message.severity == Message.WARN: self.warn += 1 - elif severity == 'Error': + elif message.severity == Message.ERROR: self.error += 1 - elif severity == 'Fatal': + elif message.severity == Message.FATAL: self.fatal += 1 + else: + assert False, "Unknown severity type '%s'" % str(message.severity) return Message_Summary(message_subset) @@ -194,10 +204,10 @@ def get_time_range_from_selection(self): indexes = self.table_view.selectionModel().selectedIndexes() if indexes: - rowlist = [self._proxymodel.mapToSource(current).row() for current in indexes] + rowlist = [self._proxy_model.mapToSource(current).row() for current in indexes] rowlist = sorted(list(set(rowlist))) - mintime, maxtime = self._datamodel.get_time_range(rowlist) + mintime, maxtime = self._model.get_time_range(rowlist) return (mintime, maxtime) return (-1, -1) @@ -207,12 +217,12 @@ def _delete_highlight_filter(self): """ for index, item in enumerate(self._highlight_filters): if item[1].delete_button.isChecked(): - if self._proxymodel.delete_highlight_filter(index): - self.highlight_table.removeCellWidget(index, 0) - self.highlight_table.removeRow(index) - item[0].filter_changed_signal.disconnect(self._proxymodel.handle_filters_changed) - item[1].delete_button.clicked.disconnect(self._delete_highlight_filter) - del self._highlight_filters[index] + self._proxy_model.delete_highlight_filter(index) + self.highlight_table.removeCellWidget(index, 0) + self.highlight_table.removeRow(index) + item[0].filter_changed_signal.disconnect(self._proxy_model.handle_highlight_filters_changed) + item[1].delete_button.clicked.disconnect(self._delete_highlight_filter) + del self._highlight_filters[index] def _delete_exclude_filter(self): """ @@ -220,12 +230,12 @@ def _delete_exclude_filter(self): """ for index, item in enumerate(self._exclude_filters): if item[1].delete_button.isChecked(): - if self._proxymodel.delete_exclude_filter(index): - self.exclude_table.removeCellWidget(index, 0) - self.exclude_table.removeRow(index) - item[0].filter_changed_signal.disconnect(self._proxymodel.handle_filters_changed) - item[1].delete_button.clicked.disconnect(self._delete_exclude_filter) - del self._exclude_filters[index] + self._proxy_model.delete_exclude_filter(index) + self.exclude_table.removeCellWidget(index, 0) + self.exclude_table.removeRow(index) + item[0].filter_changed_signal.disconnect(self._proxy_model.handle_exclude_filters_changed) + item[1].delete_button.clicked.disconnect(self._delete_exclude_filter) + del self._exclude_filters[index] def _add_highlight_filter(self, filter_index=False): """ @@ -239,14 +249,14 @@ def _add_highlight_filter(self, filter_index=False): if filter_index is False: filter_index = -1 filter_select_menu = QMenu() - for index, item in self.filter_factory.items(): + for index in self._filter_factory_order: # flattens the _highlight filters list and only adds the item if it doesn't already exist - if index == 'message' or not self.filter_factory[index][1] in [type(item) for sublist in self._highlight_filters for item in sublist]: + if index in ['message', 'location'] or not self.filter_factory[index][1] in [type(item) for sublist in self._highlight_filters for item in sublist]: filter_select_menu.addAction(self.filter_factory[index][0]) action = filter_select_menu.exec_(QCursor.pos()) if action is None: return - for index, item in self.filter_factory.items(): + for index in self._filter_factory_order: if self.filter_factory[index][0] == action.text(): filter_index = index if filter_index == -1: @@ -254,14 +264,17 @@ def _add_highlight_filter(self, filter_index=False): index = len(self._highlight_filters) newfilter = self.filter_factory[filter_index][1]() - newwidget = self.filter_factory[filter_index][2](newfilter, self.filter_factory[filter_index][3]) + if len(self.filter_factory[filter_index]) >= 4: + newwidget = self.filter_factory[filter_index][2](newfilter, self.filter_factory[filter_index][3]) + else: + newwidget = self.filter_factory[filter_index][2](newfilter) # pack the new filter tuple onto the filter list self._highlight_filters.append((newfilter, FilterWrapperWidget(newwidget, self.filter_factory[filter_index][0]), filter_index)) - self._proxymodel.add_highlight_filter(newfilter) - newfilter.filter_changed_signal.connect(self._proxymodel.handle_filters_changed) + self._proxy_model.add_highlight_filter(newfilter) + newfilter.filter_changed_signal.connect(self._proxy_model.handle_highlight_filters_changed) self._highlight_filters[index][1].delete_button.clicked.connect(self._delete_highlight_filter) - self._datamodel.rowsInserted.connect(self._highlight_filters[index][1].repopulate) + self._model.rowsInserted.connect(self._highlight_filters[index][1].repopulate) # place the widget in the proper location self.highlight_table.insertRow(index) @@ -283,14 +296,14 @@ def _add_exclude_filter(self, filter_index=False): if filter_index is False: filter_index = -1 filter_select_menu = QMenu() - for index, item in self.filter_factory.items(): + for index in self._filter_factory_order: # flattens the _exclude filters list and only adds the item if it doesn't already exist - if index == 'message' or not self.filter_factory[index][1] in [type(item) for sublist in self._exclude_filters for item in sublist]: + if index in ['message', 'location'] or not self.filter_factory[index][1] in [type(item) for sublist in self._exclude_filters for item in sublist]: filter_select_menu.addAction(self.filter_factory[index][0]) action = filter_select_menu.exec_(QCursor.pos()) if action is None: return None - for index, item in self.filter_factory.items(): + for index in self._filter_factory_order: if self.filter_factory[index][0] == action.text(): filter_index = index if filter_index == -1: @@ -298,14 +311,17 @@ def _add_exclude_filter(self, filter_index=False): index = len(self._exclude_filters) newfilter = self.filter_factory[filter_index][1]() - newwidget = self.filter_factory[filter_index][2](newfilter, self.filter_factory[filter_index][3]) + if len(self.filter_factory[filter_index]) >= 4: + newwidget = self.filter_factory[filter_index][2](newfilter, self.filter_factory[filter_index][3]) + else: + newwidget = self.filter_factory[filter_index][2](newfilter) # pack the new filter tuple onto the filter list self._exclude_filters.append((newfilter, FilterWrapperWidget(newwidget, self.filter_factory[filter_index][0]), filter_index)) - self._proxymodel.add_exclude_filter(newfilter) - newfilter.filter_changed_signal.connect(self._proxymodel.handle_filters_changed) + self._proxy_model.add_exclude_filter(newfilter) + newfilter.filter_changed_signal.connect(self._proxy_model.handle_exclude_filters_changed) self._exclude_filters[index][1].delete_button.clicked.connect(self._delete_exclude_filter) - self._datamodel.rowsInserted.connect(self._exclude_filters[index][1].repopulate) + self._model.rowsInserted.connect(self._exclude_filters[index][1].repopulate) # place the widget in the proper location self.exclude_table.insertRow(index) @@ -342,13 +358,11 @@ def _process_highlight_exclude_filter(self, selection, selectiontype, exclude=Fa if exclude: filter_index = self._add_exclude_filter(selectiontype.lower()) filter_widget = self._exclude_filters[filter_index][1].findChildren(QWidget, QRegExp('.*FilterWidget.*'))[0] - filter_widget.set_regex(True) - filter_widget.set_text('^' + message + '$') else: filter_index = self._add_highlight_filter(col) filter_widget = self._highlight_filters[filter_index][1].findChildren(QWidget, QRegExp('.*FilterWidget.*'))[0] - filter_widget.set_regex(True) - filter_widget.set_text('^' + message + '$') + filter_widget.set_regex(True) + filter_widget.set_text('^' + message + '$') else: if exclude: @@ -381,20 +395,12 @@ def _rightclick_menu(self, event): from the passed in datamodel and then launches it modally :param event: the mouse event object, ''QMouseEvent'' """ - severities = self._datamodel.get_unique_col_data(1) - nodes = self._datamodel.get_unique_col_data(2) - topics = self._datamodel.get_unique_col_data(4) - temp = [] - for topic in topics: - if topic.find(', ') == -1: - temp.append(topic) - else: - temp = temp + topic.split(', ') - topics = list(set(temp)) - - columns = list(self._datamodel.message_members()) - for index in range(len(columns)): - columns[index] = [columns[index][1:].capitalize()] + severities = {} + for severity, label in Message.SEVERITY_LABELS.items(): + if severity in self._model.get_unique_severities(): + severities[severity] = label + nodes = sorted(self._model.get_unique_nodes()) + topics = sorted(self._model.get_unique_topics()) # menutext entries turned into menutext = [] @@ -412,8 +418,13 @@ def _rightclick_menu(self, event): for subitem in item[1]: if len(subitem) > 1: subsubmenus.append(QMenu(subitem[0], submenus[-1])) - for subsubitem in subitem[1]: - subsubmenus[-1].addAction(subsubitem) + if isinstance(subitem[1], dict): + for key in sorted(subitem[1].keys()): + action = subsubmenus[-1].addAction(subitem[1][key]) + action.setData(key) + else: + for subsubitem in subitem[1]: + subsubmenus[-1].addAction(subsubitem) submenus[-1].addMenu(subsubmenus[-1]) else: submenus[-1].addAction(subitem[0]) @@ -429,8 +440,8 @@ def _rightclick_menu(self, event): elif action.text() == self.tr('Copy Selected'): rowlist = [] for current in self.table_view.selectionModel().selectedIndexes(): - rowlist.append(self._proxymodel.mapToSource(current).row()) - copytext = self._datamodel.get_selected_text(rowlist) + rowlist.append(self._proxy_model.mapToSource(current).row()) + copytext = self._model.get_selected_text(rowlist) if copytext is not None: clipboard = QApplication.clipboard() clipboard.setText(copytext) @@ -454,16 +465,15 @@ def _rightclick_menu(self, event): self._process_highlight_exclude_filter(action.text(), action.parentWidget().title(), True) else: raise RuntimeError("Unknown Root Action %s selected in ConsoleWidget._rightclick_menu()" % roottitle) - self.update_status() def update_status(self): """ Sets the message display label to the current value """ - if self._datamodel.rowCount() == self._proxymodel.rowCount(): - tip = self.tr('Displaying %d messages') % (self._datamodel.rowCount()) + if self._model.rowCount() == self._proxy_model.rowCount(): + tip = self.tr('Displaying %d messages') % (self._model.rowCount()) else: - tip = self.tr('Displaying %d of %d messages') % (self._proxymodel.rowCount(), self._datamodel.rowCount()) + tip = self.tr('Displaying %d of %d messages') % (self._proxy_model.rowCount(), self._model.rowCount()) self.messages_label.setText(tip) def cleanup_browsers_on_close(self): @@ -473,28 +483,117 @@ def cleanup_browsers_on_close(self): def _show_browsers(self): rowlist = [] for current in self.table_view.selectionModel().selectedIndexes(): - rowlist.append(self._proxymodel.mapToSource(current).row()) - browsetext = self._datamodel.get_selected_text(rowlist) + rowlist.append(self._proxy_model.mapToSource(current).row()) + browsetext = self._model.get_selected_text(rowlist) if browsetext is not None: self._browsers.append(TextBrowseDialog(browsetext)) self._browsers[-1].show() def _handle_clear_button_clicked(self, checked): - self._datamodel.remove_rows([]) + self._model.remove_rows([]) + Message._next_id = 1 def _handle_load_clicked(self, checked): filename = QFileDialog.getOpenFileName(self, self.tr('Load from File'), '.', self.tr('rqt_console message file {.csv} (*.csv)')) if filename[0] != '': try: - handle = open(filename[0]) + with open(filename[0], 'r') as h: + lines = h.read().splitlines() except IOError as e: qWarning(str(e)) - return - self.pause_button.setChecked(True) - self._handle_pause_clicked(True) - self._datamodel.load_from_file(handle) - handle.close() - self.update_status() + return False + + # extract column header + columns = lines[0].split(';') + if len(lines) < 2: + return True + + # join wrapped lines + rows = [] + last_wrapped = False + for line in lines[1:]: + # ignore empty lines + if not line: + continue + # check for quotes and remove them + if line == '"': + has_prefix = not last_wrapped + has_suffix = last_wrapped + line = '' + else: + has_prefix = line[0] == '"' + if has_prefix: + line = line[1:] + has_suffix = line[-1] == '"' + if has_suffix: + line = line[:-1] + + # ignore line without prefix if previous line was not wrapped + if not has_prefix and not last_wrapped: + continue + # remove wrapped line which is not continued on the next line + if last_wrapped and has_prefix: + rows.pop() + + # add/append lines + if last_wrapped: + rows[-1] += line + else: + # add line without quote prefix + rows.append(line) + + last_wrapped = not has_suffix + + # generate message for each row + messages = [] + skipped = [] + for row in rows: + data = row.split('";"') + msg = Message() + msg.set_stamp_format('hh:mm:ss.ZZZ (yyyy-MM-dd)') + for i, column in enumerate(columns): + value = data[i] + if column == 'message': + msg.message = value.replace('\\"', '"') + elif column == 'severity': + msg.severity = int(value) + if msg.severity not in Message.SEVERITY_LABELS: + skipped.append('Unknown severity value: %s' % value) + msg = None + break + elif column == 'stamp': + parts = value.split('.') + if len(parts) != 2: + skipped.append('Unknown timestamp format: %s' % value) + msg = None + break + msg.stamp = (int(parts[0]), int(parts[1])) + elif column == 'topics': + msg.topics = value.split(',') + elif column == 'node': + msg.node = value + elif column == 'location': + msg.location = value + else: + skipped.append('Unknown column: %s' % column) + msg = None + break + if msg: + messages.append(msg) + if skipped: + qWarning('Skipped %d rows since they do not appear to be in rqt_console message file format:\n- %s' % (len(skipped), '\n- '.join(skipped))) + + if messages: + self._model.insert_rows(messages) + + self.pause_button.setChecked(True) + self._handle_pause_clicked(True) + + return True + + else: + qWarning('File does not appear to be a rqt_console message file: missing file header.') + return False def _handle_save_clicked(self, checked): filename = QFileDialog.getSaveFileName(self, 'Save to File', '.', self.tr('rqt_console msg file {.csv} (*.csv)')) @@ -507,13 +606,32 @@ def _handle_save_clicked(self, checked): except IOError as e: qWarning(str(e)) return - self._proxymodel.save_to_file(handle) - handle.close() - self.update_status() + try: + handle.write(';'.join(MessageDataModel.columns) + '\n') + for index in range(self._proxy_model.rowCount()): + row = self._proxy_model.mapToSource(self._proxy_model.index(index, 0)).row() + msg = self._model._messages[row] + data = {} + data['message'] = msg.message.replace('"', '\\"') + data['severity'] = str(msg.severity) + data['node'] = msg.node + data['stamp'] = str(msg.stamp[0]) + '.' + str(msg.stamp[1]).zfill(9) + data['topics'] = ','.join(msg.topics) + data['location'] = msg.location + line = [] + for column in MessageDataModel.columns: + line.append('"%s"' % data[column]) + handle.write(';'.join(line) + '\n') + except Exception as e: + qWarning('File save failed: %s' % str(e)) + return False + finally: + handle.close() + return True def _handle_pause_clicked(self, checked): - self._datamodel._paused = checked - if self._datamodel._paused: + self._paused = checked + if self._paused: self.pause_button.setIcon(self._recordicon) self.pause_button.setText(self.tr('Resume')) else: @@ -526,22 +644,21 @@ def _handle_column_resize_clicked(self): def _delete_selected_rows(self): rowlist = [] for current in self.table_view.selectionModel().selectedIndexes(): - rowlist.append(self._proxymodel.mapToSource(current).row()) + rowlist.append(self._proxy_model.mapToSource(current).row()) rowlist = list(set(rowlist)) - return self._datamodel.remove_rows(rowlist) + return self._model.remove_rows(rowlist) def _handle_custom_keypress(self, event, old_keyPressEvent=QTableView.keyPressEvent): """ Handles the delete key. The delete key removes the tableview's selected rows from the datamodel """ - if event.key() == Qt.Key_Delete and len(self._datamodel.get_message_list()) > 0: + if event.key() == Qt.Key_Delete and len(self._model._messages) > 0: delete = QMessageBox.Yes if len(self.table_view.selectionModel().selectedIndexes()) == 0: delete = QMessageBox.question(self, self.tr('Message'), self.tr("Are you sure you want to delete all messages?"), QMessageBox.Yes | QMessageBox.No, QMessageBox.No) if delete == QMessageBox.Yes and event.key() == Qt.Key_Delete and event.modifiers() == Qt.NoModifier: if self._delete_selected_rows(): - self.update_status() event.accept() return old_keyPressEvent(self.table_view, event) @@ -563,6 +680,7 @@ def save_settings(self, plugin_settings, instance_settings): instance_settings.set_value('table_splitter', self.table_splitter.saveState()) instance_settings.set_value('filter_splitter', self.filter_splitter.saveState()) + instance_settings.set_value('paused', self.pause_button.isChecked()) instance_settings.set_value('show_highlighted_only', self.highlight_exclude_button.isChecked()) exclude_filters = [] @@ -578,20 +696,20 @@ def save_settings(self, plugin_settings, instance_settings): filter_settings = instance_settings.get_settings('highlight_filter_' + str(index)) item[1].save_settings(filter_settings) instance_settings.set_value('highlight_filters', pack(highlight_filters)) - instance_settings.set_value('message_limit', self._datamodel._message_limit) + instance_settings.set_value('message_limit', self._model.get_message_limit()) def restore_settings(self, pluggin_settings, instance_settings): if instance_settings.contains('table_splitter'): self.table_splitter.restoreState(instance_settings.value('table_splitter')) - else: - self.table_splitter.setSizes([1000, 100]) if instance_settings.contains('filter_splitter'): self.filter_splitter.restoreState(instance_settings.value('filter_splitter')) else: - self.table_splitter.setSizes([500, 500]) + self.filter_splitter.setSizes([1, 1]) + self.pause_button.setChecked(instance_settings.value('paused') in [True, 'true']) + self._handle_pause_clicked(self.pause_button.isChecked()) self.highlight_exclude_button.setChecked(instance_settings.value('show_highlighted_only') in [True, 'true']) - self._proxymodel.set_show_highlighted_only(self.highlight_exclude_button.isChecked()) + self._proxy_model.set_show_highlighted_only(self.highlight_exclude_button.isChecked()) for item in self._exclude_filters: item[1].delete_button.setChecked(True) @@ -620,4 +738,4 @@ def restore_settings(self, pluggin_settings, instance_settings): self._add_highlight_filter('message') if instance_settings.contains('message_limit'): - self._datamodel._message_limit = int(instance_settings.value('message_limit')) + self._model.set_message_limit(int(instance_settings.value('message_limit'))) diff --git a/rqt_console/src/rqt_console/filters/base_filter.py b/rqt_console/src/rqt_console/filters/base_filter.py index 471fbe1a..8dda1006 100644 --- a/rqt_console/src/rqt_console/filters/base_filter.py +++ b/rqt_console/src/rqt_console/filters/base_filter.py @@ -35,7 +35,8 @@ class BaseFilter(QObject): """ - Contains basic functions common to all filters. Handles enabled code and + Contains basic functions common to all filters. + Handles enabled logic and change notification. """ filter_changed_signal = Signal() @@ -68,3 +69,9 @@ def set_enabled(self, checked): """ self._enabled = checked self.start_emit_timer(200) + + def has_filter(self): + raise NotImplementedError() + + def test_message(self, message): + raise NotImplementedError() diff --git a/rqt_console/src/rqt_console/filters/custom_filter.py b/rqt_console/src/rqt_console/filters/custom_filter.py index bfe628d1..2e42e473 100644 --- a/rqt_console/src/rqt_console/filters/custom_filter.py +++ b/rqt_console/src/rqt_console/filters/custom_filter.py @@ -41,42 +41,53 @@ class CustomFilter(BaseFilter): """ Contains filter logic for the custom filter which allows message, severity, node and topic filtering simultaniously. All of these filters must match - together or the custom filter does not match + together (if they are used) or the custom filter does not match. """ def __init__(self): super(CustomFilter, self).__init__() self._message = MessageFilter() - self._message.filter_changed_signal.connect(self.relay_emit_signal) self._severity = SeverityFilter() - self._severity.filter_changed_signal.connect(self.relay_emit_signal) self._node = NodeFilter() - self._node.filter_changed_signal.connect(self.relay_emit_signal) self._topic = TopicFilter() - self._topic.filter_changed_signal.connect(self.relay_emit_signal) + + self._all_filters = [self._message, self._severity, self._node, self._topic] + for f in self._all_filters: + f.filter_changed_signal.connect(self._relay_signal) def set_enabled(self, checked): """ :signal: emits filter_changed_signal :param checked: enables the filters if checked is True''bool'' """ - self._message.set_enabled(checked) - self._severity.set_enabled(checked) - self._node.set_enabled(checked) - self._topic.set_enabled(checked) + for f in self._all_filters: + f.set_enabled(checked) super(CustomFilter, self).set_enabled(checked) - def relay_emit_signal(self): + def _relay_signal(self): """ Passes any signals emitted by the child filters along """ self.start_emit_timer(1) + def has_filter(self): + for f in self._all_filters: + if f.has_filter(): + return True + return False + def test_message(self, message): """ Tests if the message matches the filter. :param message: the message to be tested against the filters, ''Message'' :returns: True if the message matches all child filters, ''bool'' """ - return self._message.test_message(message) and self._severity.test_message(message) and self._node.test_message(message) and self._topic.test_message(message) + if not self.is_enabled(): + return False + # if non of the subfilters contains any input the custom filter does not match + if not self.has_filter(): + return False + # the custom filter matches when all subfilters which contain input match + all_filters = [not f.has_filter() or f.test_message(message) for f in self._all_filters] + return False not in all_filters diff --git a/rqt_console/src/rqt_console/filters/custom_filter_widget.py b/rqt_console/src/rqt_console/filters/custom_filter_widget.py index c2e89abd..dc954589 100644 --- a/rqt_console/src/rqt_console/filters/custom_filter_widget.py +++ b/rqt_console/src/rqt_console/filters/custom_filter_widget.py @@ -35,13 +35,13 @@ from python_qt_binding import loadUi from python_qt_binding.QtCore import Qt -from python_qt_binding.QtGui import QWidget +from python_qt_binding.QtGui import QPalette, QWidget from rqt_py_common.ini_helper import pack, unpack class CustomFilterWidget(QWidget): - def __init__(self, parentfilter, display_list_args): + def __init__(self, parentfilter, item_providers): super(CustomFilterWidget, self).__init__() rp = rospkg.RosPack() ui_file = os.path.join(rp.get_path('rqt_console'), 'resource/filters', 'custom_filter_widget.ui') @@ -49,6 +49,11 @@ def __init__(self, parentfilter, display_list_args): self.setObjectName('CustomFilterWidget') self._parentfilter = parentfilter # When data is changed it is stored in the parent filter + # keep color for highlighted items even when not active + for list_widget in [self.severity_list, self.node_list, self.topic_list]: + active_color = list_widget.palette().brush(QPalette.Active, QPalette.Highlight).color().name() + list_widget.setStyleSheet('QListWidget:item:selected:!active { background: %s; }' % active_color) + # Text Filter Initialization self.text_edit.textChanged.connect(self.handle_text_changed) self.regex_check_box.clicked[bool].connect(self.handle_regex_clicked) @@ -56,34 +61,30 @@ def __init__(self, parentfilter, display_list_args): # Severity Filter Initialization self.severity_list.itemSelectionChanged.connect(self.handle_severity_item_changed) - newlist = display_list_args[0]() - for item in newlist: + new_items = item_providers[0]() + for key in sorted(new_items.keys()): + item = new_items[key] self.severity_list.addItem(item) + self.severity_list.item(self.severity_list.count() - 1).setData(Qt.UserRole, key) # Node Filter Initialization - self._node_list_populate_function = display_list_args[1] - self._node_function_argument = False - self._node_function_argument = display_list_args[2] + self._node_list_populate_function = item_providers[1] self.node_list.itemSelectionChanged.connect(self.handle_node_item_changed) - self._node_display_list = [] # Topic Filter Initialization - self._topic_list_populate_function = display_list_args[3] - self._topic_function_argument = False - self._topic_function_argument = display_list_args[4] + self._topic_list_populate_function = item_providers[2] self.topic_list.itemSelectionChanged.connect(self.handle_topic_item_changed) - self._topic_display_list = [] self.repopulate() def handle_node_item_changed(self): - self._parentfilter._node.set_list(self.node_list.selectedItems()) + self._parentfilter._node.set_selected_items(self.node_list.selectedItems()) def handle_topic_item_changed(self): - self._parentfilter._topic.set_list(self.topic_list.selectedItems()) + self._parentfilter._topic.set_selected_items(self.topic_list.selectedItems()) def handle_severity_item_changed(self): - self._parentfilter._severity.set_list(self.severity_list.selectedItems()) + self._parentfilter._severity.set_selected_items(self.severity_list.selectedItems()) def handle_text_changed(self): self._parentfilter._message.set_text(self.text_edit.text()) @@ -96,19 +97,25 @@ def repopulate(self): Repopulates the display widgets based on the function arguments passed in during initialization """ - newlist = self._topic_list_populate_function(self._topic_function_argument) - if len(newlist) != len(self._topic_display_list): - for item in newlist: - if item not in self._topic_display_list: - self.topic_list.addItem(item) - self._topic_display_list = list(set(newlist + self._topic_display_list)) - - newlist = self._node_list_populate_function(self._node_function_argument) - if len(newlist) != len(self._node_display_list): - for item in newlist: - if item not in self._node_display_list: - self.node_list.addItem(item) - self._node_display_list = list(set(newlist + self._node_display_list)) + newset = self._topic_list_populate_function() + for item in newset: + if len(self.topic_list.findItems(item, Qt.MatchExactly)) == 0: + self._add_item(self.topic_list, item) + + newset = self._node_list_populate_function() + for item in newset: + if len(self.node_list.findItems(item, Qt.MatchExactly)) == 0: + self._add_item(self.node_list, item) + + def _add_item(self, list_widget, item): + """ + Insert item in alphabetical order. + """ + for i in range(list_widget.count()): + if item <= list_widget.item(i).text(): + list_widget.insertItem(i, item) + return + list_widget.addItem(item) def save_settings(self, settings): """ @@ -118,13 +125,11 @@ def save_settings(self, settings): settings.set_value('text', self._parentfilter._message._text) settings.set_value('regex', self._parentfilter._message._regex) - settings.set_value('severityitemlist', pack(self._parentfilter._severity._list)) + settings.set_value('severityitemlist', pack(self._parentfilter._severity._selected_items)) - settings.set_value('topicdisplaylist', pack(self._topic_display_list)) - settings.set_value('topicitemlist', pack(self._parentfilter._topic._list)) + settings.set_value('topicitemlist', pack(self._parentfilter._topic._selected_items)) - settings.set_value('nodedisplaylist', pack(self._node_display_list)) - settings.set_value('nodeitemlist', pack(self._parentfilter._node._list)) + settings.set_value('nodeitemlist', pack(self._parentfilter._node._selected_items)) return @@ -152,28 +157,24 @@ def restore_settings(self, settings): self.handle_severity_item_changed() #Restore Topics - self._topic_display_list = unpack(settings.value('topicdisplaylist')) - for item in self._topic_display_list: - if len(self.topic_list.findItems(item, Qt.MatchExactly)) == 0: - self.topic_list.addItem(item) for index in range(self.topic_list.count()): self.topic_list.item(index).setSelected(False) topic_item_list = unpack(settings.value('topicitemlist')) for item in topic_item_list: + if len(self.topic_list.findItems(item, Qt.MatchExactly)) == 0: + self.topic_list.addItem(item) items = self.topic_list.findItems(item, Qt.MatchExactly) for item in items: item.setSelected(True) self.handle_topic_item_changed() #Restore Nodes - self._node_display_list = unpack(settings.value('nodedisplaylist')) - for item in self._node_display_list: - if len(self.node_list.findItems(item, Qt.MatchExactly)) == 0: - self.node_list.addItem(item) for index in range(self.node_list.count()): self.node_list.item(index).setSelected(False) node_item_list = unpack(settings.value('nodeitemlist')) for item in node_item_list: + if len(self.node_list.findItems(item, Qt.MatchExactly)) == 0: + self.node_list.addItem(item) items = self.node_list.findItems(item, Qt.MatchExactly) for item in items: item.setSelected(True) diff --git a/rqt_console/src/rqt_console/filters/filter_collection.py b/rqt_console/src/rqt_console/filters/filter_collection.py index be8bc137..841be238 100644 --- a/rqt_console/src/rqt_console/filters/filter_collection.py +++ b/rqt_console/src/rqt_console/filters/filter_collection.py @@ -30,65 +30,39 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -from ..message import Message - class FilterCollection: """ - This class provides an interface to filter Message objects based on - of a set of filters which will be boolean combined with either 'or' - or 'and' based on the combination type passed by the user. - ''True'' for and combine and ''False'' for or combine + Collection of filters to test messages against. """ - def __init__(self, proxymodel): - """ - :param proxymodel: , ''QSortFilterProxyModel'' - """ + def __init__(self): self._filters = [] - self._proxymodel = proxymodel - - def test_message_array(self, message): - """ - test_message function for an array formatted message - :param message: array of the message member data in order ''list'': - message text ''str'', severity ''str'', node ''str'', - time in seconds with decimals ''str'', topic ''str'', - """ - newmessage = Message() - message = newmessage.load_from_array(message) - return self.test_message(message) - def test_message(self, message): + def test_message(self, message, default=False): """ - Tests if the message matches the entire list of filters. - if passed an array of the 6 data elements of a message it will build one + Test if the message matches any filter. :param message: message to be tested against the filters, ''Message'' - :returns: True if the message matches the filters, ''bool'' + :param default: return value when there is no active filter, ''bool'' + :returns: True if the message matches any filter, ''bool'' """ - for item in self._filters: - if item.is_enabled() and item.test_message(message): - return True - return False + match = default + for f in self._filters: + if f.is_enabled() and f.has_filter(): + if f.test_message(message): + return True + else: + match = False + return match - def append(self, newfilter): - """ - Adds a new filter to the filter list and returns the index - :returns: The index of the filter appended, ''int'' - """ - self._filters.append(newfilter) + def append(self, filter): + self._filters.append(filter) def count_enabled_filters(self): - enabled = 0 - for item in self._filters: - if item.is_enabled(): - enabled += 1 - return enabled + enabled = [f for f in self._filters if f.is_enabled()] + return len(enabled) def __len__(self): return len(self._filters) - def count(self): - return len(self._filters) - def __delitem__(self, index): del self._filters[index] diff --git a/rqt_console/src/rqt_console/filters/list_filter_widget.py b/rqt_console/src/rqt_console/filters/list_filter_widget.py index ebbbfbe7..a9b06c4d 100644 --- a/rqt_console/src/rqt_console/filters/list_filter_widget.py +++ b/rqt_console/src/rqt_console/filters/list_filter_widget.py @@ -35,7 +35,7 @@ from python_qt_binding import loadUi from python_qt_binding.QtCore import Qt -from python_qt_binding.QtGui import QWidget +from python_qt_binding.QtGui import QPalette, QWidget from rqt_py_common.ini_helper import pack, unpack @@ -45,13 +45,11 @@ class ListFilterWidget(QWidget): Generic List widget to be used when implementing filters that require limited dynamic selections """ - def __init__(self, parentfilter, display_list_args): + def __init__(self, parentfilter, item_provider): """ :param parentfilter: The filter object, must implement set_list and contain _list ''QObject'' - :param display_list_args: list of arguments which must contain a - function designed to populate a list 'display_list_args[0]' and may - contain an optional variable to pass into that function 'display_list_args[1]' + :param item_provider: a function designed to provide a list or dict """ super(ListFilterWidget, self).__init__() rp = rospkg.RosPack() @@ -60,10 +58,11 @@ def __init__(self, parentfilter, display_list_args): self.setObjectName('ListFilterWidget') self._parentfilter = parentfilter # When data is changed we need to store it in the parent filter - self._list_populate_function = display_list_args[0] - self._function_argument = False - if len(display_list_args) > 1: - self._function_argument = display_list_args[1] + # keep color for highlighted items even when not active + active_color = self.palette().brush(QPalette.Active, QPalette.Highlight).color().name() + self.setStyleSheet('QListWidget:item:selected:!active { background: %s; }' % active_color) + + self._list_populate_function = item_provider self.list_widget.itemSelectionChanged.connect(self.handle_item_changed) self._display_list = [] self.repopulate() @@ -79,44 +78,57 @@ def select_item(self, text): self.handle_item_changed() def handle_item_changed(self): - self._parentfilter.set_list(self.list_widget.selectedItems()) + self._parentfilter.set_selected_items(self.list_widget.selectedItems()) def repopulate(self): """ Repopulates the display widgets based on the function arguments passed in during initialization """ - if not self._function_argument is False: - newlist = self._list_populate_function(self._function_argument) - else: - newlist = self._list_populate_function() + new_items = self._list_populate_function() + + new_set = set(new_items.values() if isinstance(new_items, dict) else new_items) + + if len(new_items) != len(self._display_list): + if isinstance(new_items, dict): + # for dictionaries store the key as user role data + for key in sorted(new_items.keys()): + item = new_items[key] + if item not in self._display_list: + self.list_widget.addItem(item) + self.list_widget.item(self.list_widget.count() - 1).setData(Qt.UserRole, key) + else: + for item in new_items: + if item not in self._display_list: + self._add_item(item) + self._display_list = sorted(set(new_set) | set(self._display_list)) - if len(newlist) != len(self._display_list): - for item in newlist: - if item not in self._display_list: - self.list_widget.addItem(item) - self._display_list = list(set(newlist + self._display_list)) + def _add_item(self, item): + """ + Insert item in alphabetical order. + """ + for i in range(self.list_widget.count()): + if item <= self.list_widget.item(i).text(): + self.list_widget.insertItem(i, item) + return + self.list_widget.addItem(item) def save_settings(self, settings): """ Saves the settings for this filter. :param settings: used to write the settings to an ini file ''qt_gui.settings.Settings'' """ - settings.set_value('displist', pack(self._display_list)) - settings.set_value('itemlist', pack(self._parentfilter._list)) + settings.set_value('itemlist', pack(self._parentfilter._selected_items)) def restore_settings(self, settings): """ Restores the settings for this filter from an ini file. :param settings: used to extract the settings from an ini file ''qt_gui.settings.Settings'' """ - self._display_list = unpack(settings.value('displist')) - for item in self._display_list: - if len(self.list_widget.findItems(item, Qt.MatchExactly)) == 0: - self.list_widget.addItem(item) - for index in range(self.list_widget.count()): self.list_widget.item(index).setSelected(False) item_list = unpack(settings.value('itemlist')) for item in item_list: + if len(self.list_widget.findItems(item, Qt.MatchExactly)) == 0: + self.list_widget.addItem(item) self.select_item(item) diff --git a/rqt_console/src/rqt_console/filters/location_filter.py b/rqt_console/src/rqt_console/filters/location_filter.py index b98abdc3..7d3acb5f 100644 --- a/rqt_console/src/rqt_console/filters/location_filter.py +++ b/rqt_console/src/rqt_console/filters/location_filter.py @@ -30,67 +30,16 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -from python_qt_binding.QtCore import QRegExp -from .base_filter import BaseFilter +from .message_filter import MessageFilter -class LocationFilter(BaseFilter): +class LocationFilter(MessageFilter): """ - Contains filter logic for a single location filter. If the regex flag is False - simple 'is this in that' text matching is used on _text. If the regex flag is True - _text is treated as a regular expression with one exception. If it does not - start with a ^ a .* is appended, and if it does not end with a $ then a .* - is added to the end. - The filter_changed signal should be connected to a slot which notifies the - overall filtering system that it needs to reevaluate all entries. + Contains filter logic for a location filter. """ def __init__(self): super(LocationFilter, self).__init__() - self._text = '' - self._regex = False - - def set_text(self, text): - """ - Setter for _text - :param text: text to set ''str'' - :emits filter_changed_signal: If _enabled is true - """ - self._text = text - if self.is_enabled(): - self.start_emit_timer(500) - - def set_regex(self, checked): - """ - Setter for _regex - :param checked" boolean flag to set ''bool'' - :emits filter_changed_signal: If _enabled is true - """ - self._regex = checked - if self.is_enabled(): - self.start_emit_timer(500) def test_message(self, message): - """ - Tests if the message matches the filter. - If the regex flag is False simple 'is this in that' text matching is used - on _text. If the regex flag is True _text is treated as a regular expression - with one exception. If it does not start with a ^ a .* is appended, and if - it does not end with a $ then a .* is added to the end. - - :param message: the message to be tested against the filters, ''Message'' - :returns: True if the message matches, ''bool'' - """ - if self.is_enabled() and self._text != '': - if self._regex: - temp = self._text - if temp[0] != '^': - temp = '.*' + temp - if temp[-1] != '$': - temp += '.*' - if QRegExp(temp).exactMatch(message._location): - return True - else: - if message._location.find(self._text) != -1: - return True - return False + return self._test_message(message.location) diff --git a/rqt_console/src/rqt_console/filters/message_filter.py b/rqt_console/src/rqt_console/filters/message_filter.py index bb5940a1..21513910 100644 --- a/rqt_console/src/rqt_console/filters/message_filter.py +++ b/rqt_console/src/rqt_console/filters/message_filter.py @@ -36,7 +36,7 @@ class MessageFilter(BaseFilter): """ - Contains filter logic for a single message filter. If the regex flag is False + Contains filter logic for a message filter. If the regex flag is False simple 'is this in that' text matching is used on _text. If the regex flag is True _text is treated as a regular expression with one exception. If it does not start with a ^ a .* is appended, and if it does not end with a $ then a .* @@ -70,6 +70,9 @@ def set_regex(self, checked): if self.is_enabled(): self.start_emit_timer(500) + def has_filter(self): + return self._text != '' + def test_message(self, message): """ Tests if the message matches the filter. @@ -77,20 +80,25 @@ def test_message(self, message): on _text. If the regex flag is True _text is treated as a regular expression with one exception. If it does not start with a ^ a .* is appended, and if it does not end with a $ then a .* is added to the end. + :param message: the message to be tested against the filters, ''Message'' :returns: True if the message matches, ''bool'' """ + return self._test_message(message.message) - if self.is_enabled() and self._text != '': + def _test_message(self, value): + if not self.is_enabled(): + return False + if self._text != '': if self._regex: temp = self._text if temp[0] != '^': temp = '.*' + temp if temp[-1] != '$': temp += '.*' - if QRegExp(temp).exactMatch(message._message): + if QRegExp(temp).exactMatch(value): return True else: - if message._message.find(self._text) != -1: + if value.find(self._text) != -1: return True return False diff --git a/rqt_console/src/rqt_console/filters/node_filter.py b/rqt_console/src/rqt_console/filters/node_filter.py index 62e1f173..7787674f 100644 --- a/rqt_console/src/rqt_console/filters/node_filter.py +++ b/rqt_console/src/rqt_console/filters/node_filter.py @@ -35,25 +35,27 @@ class NodeFilter(BaseFilter): """ - Contains filter logic for a single node filter + Contains filter logic for a single node filter. If the message's node text matches any of the text in the stored list then it is considered a match. """ - def __init__(self): super(NodeFilter, self).__init__() - self._list = [] + self._selected_items = [] - def set_list(self, list_): + def set_selected_items(self, items): """ - Setter for _list + Setter for selected items. :param list_" list of items to store for filtering ''list of QListWidgetItem'' :emits filter_changed_signal: If _enabled is true """ - self._list = list_ + self._selected_items = items if self.is_enabled(): self.start_emit_timer() + def has_filter(self): + return len(self._selected_items) > 0 + def test_message(self, message): """ Tests if the message matches the filter. @@ -62,8 +64,9 @@ def test_message(self, message): :param message: the message to be tested against the filters, ''Message'' :returns: True if the message matches, ''bool'' """ - if self.is_enabled(): - for item in self._list: - if message._node == item.text(): - return True + if not self.is_enabled(): + return False + for item in self._selected_items: + if message.node == item.text(): + return True return False diff --git a/rqt_console/src/rqt_console/filters/severity_filter.py b/rqt_console/src/rqt_console/filters/severity_filter.py index 94221d7e..a4bd2530 100644 --- a/rqt_console/src/rqt_console/filters/severity_filter.py +++ b/rqt_console/src/rqt_console/filters/severity_filter.py @@ -32,27 +32,32 @@ from .base_filter import BaseFilter +from python_qt_binding.QtCore import Qt + class SeverityFilter(BaseFilter): """ - Contains filter logic for a single severity filter + Contains filter logic for a severity filter. If the message's severity text matches any of the text in the stored list then it is considered a match. """ def __init__(self): super(SeverityFilter, self).__init__() - self._list = [] + self._selected_items = [] - def set_list(self, list_): + def set_selected_items(self, items): """ - Setter for _list + Setter for selected items. :param list_: list of items to store for filtering ''list of QListWidgetItem'' :emits filter_changed_signal: If _enabled is true """ - self._list = list_ + self._selected_items = items if self.is_enabled(): self.start_emit_timer() + def has_filter(self): + return len(self._selected_items) > 0 + def test_message(self, message): """ Tests if the message matches the filter. @@ -61,8 +66,9 @@ def test_message(self, message): :param message: the message to be tested against the filters, ''Message'' :returns: True if the message matches, ''bool'' """ - if self.is_enabled(): - for item in self._list: - if message._severity == item.text(): - return True + if not self.is_enabled(): + return False + for item in self._selected_items: + if message.severity == item.data(Qt.UserRole): + return True return False diff --git a/rqt_console/src/rqt_console/filters/text_filter_widget.py b/rqt_console/src/rqt_console/filters/text_filter_widget.py index 3ee8d22c..8fee3105 100644 --- a/rqt_console/src/rqt_console/filters/text_filter_widget.py +++ b/rqt_console/src/rqt_console/filters/text_filter_widget.py @@ -38,11 +38,10 @@ class TextFilterWidget(QWidget): - def __init__(self, parentfilter, display_list_args=None): + def __init__(self, parentfilter): """ Widget for displaying interactive data related to text filtering. :param parentfilter: buddy filter were data is stored, ''TimeFilter'' - :param display_list_args: empty list, ''list'' """ super(TextFilterWidget, self).__init__() rp = rospkg.RosPack() diff --git a/rqt_console/src/rqt_console/filters/time_filter.py b/rqt_console/src/rqt_console/filters/time_filter.py index 5cd991de..37fc08bb 100644 --- a/rqt_console/src/rqt_console/filters/time_filter.py +++ b/rqt_console/src/rqt_console/filters/time_filter.py @@ -36,7 +36,7 @@ class TimeFilter(BaseFilter): """ - Contains filter logic for a single time filter + Contains filter logic for a time filter. If _stop_time_enabled is true then the message's time value must be between the dates provided to be considered a match If _stop_time_enabled is false then the time must simply be after _start_time @@ -78,6 +78,9 @@ def set_stop_time_enabled(self, checked): if self.is_enabled(): self.start_emit_timer() + def has_filter(self): + return True + def test_message(self, message): """ Tests if the message matches the filter. @@ -87,7 +90,9 @@ def test_message(self, message): :param message: the message to be tested against the filters, ''Message'' :returns: True if the message matches, ''bool'' """ - message_time = message._time + if not self.is_enabled(): + return False + message_time = message.get_stamp_as_qdatetime() if message_time < self._start_time: return False if self._stop_time_enabled and self._stop_time < message_time: diff --git a/rqt_console/src/rqt_console/filters/time_filter_widget.py b/rqt_console/src/rqt_console/filters/time_filter_widget.py index e5392cfd..0617fe16 100644 --- a/rqt_console/src/rqt_console/filters/time_filter_widget.py +++ b/rqt_console/src/rqt_console/filters/time_filter_widget.py @@ -40,7 +40,7 @@ class TimeFilterWidget(QWidget): - def __init__(self, parentfilter, display_list_args): + def __init__(self, parentfilter, time_range_provider): """ Widget for displaying interactive data related to time filtering. :param parentfilter: buddy filter were data is stored, ''TimeFilter'' @@ -59,7 +59,7 @@ def __init__(self, parentfilter, display_list_args): self.stop_enabled_check_box.clicked[bool].connect(self.handle_stop_enabled_changed) # Times are passed in unixtimestamp '.' decimal fraction of a second - mintime, maxtime = display_list_args[0]() + mintime, maxtime = time_range_provider() if mintime != -1: mintime = str(mintime).split('.') maxtime = str(maxtime).split('.') diff --git a/rqt_console/src/rqt_console/filters/topic_filter.py b/rqt_console/src/rqt_console/filters/topic_filter.py index 365d6cb2..6a06a2c4 100644 --- a/rqt_console/src/rqt_console/filters/topic_filter.py +++ b/rqt_console/src/rqt_console/filters/topic_filter.py @@ -35,25 +35,27 @@ class TopicFilter(BaseFilter): """ - Contains filter logic for a single topic filter + Contains filter logic for a topic filter. If the message's topic text matches any of the text in the stored list then it is considered a match. """ - def __init__(self): super(TopicFilter, self).__init__() - self._list = [] + self._selected_items = [] - def set_list(self, list_): + def set_selected_items(self, items): """ - Setter for _list + Setter for selected items. :param list_" list of items to store for filtering ''list of QListWidgetItem'' :emits filter_changed_signal: If _enabled is true """ - self._list = list_ + self._selected_items = items if self.is_enabled(): self.start_emit_timer() + def has_filter(self): + return len(self._selected_items) > 0 + def test_message(self, message): """ Tests if the message matches the filter. @@ -62,8 +64,9 @@ def test_message(self, message): :param message: the message to be tested against the filters, ''Message'' :returns: True if the message matches, ''bool'' """ - if self.is_enabled(): - for item in self._list: - if item.text() in message._topics.split(', '): - return True + if not self.is_enabled(): + return False + for item in self._selected_items: + if item.text() in message.topics: + return True return False diff --git a/rqt_console/src/rqt_console/message.py b/rqt_console/src/rqt_console/message.py index 766edab4..901ccfd4 100644 --- a/rqt_console/src/rqt_console/message.py +++ b/rqt_console/src/rqt_console/message.py @@ -30,180 +30,104 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -from python_qt_binding.QtCore import QDateTime, QObject +from rosgraph_msgs.msg import Log +from python_qt_binding.QtCore import QCoreApplication, QDateTime, QObject -class Message(QObject): - """ - Basic Message object. To directly access members use the get_data() function. - """ - def __init__(self, msg=None): - """ - :param msg: a log message to initialize the message object, ''Log'' - """ - super(Message, self).__init__() - self._messagemembers = self.get_message_members() - self._severity = {1: self.tr('Debug'), 2: self.tr('Info'), 4: self.tr('Warn'), 8: self.tr('Error'), 16: self.tr('Fatal')} - self._time_format = None - self.__color = 'black' - if msg is not None: - self._message = msg.msg - self._severity = self._severity[msg.level] - self._node = msg.name - self._time = self.datestamp_to_qdatetime(msg.header.stamp.secs, msg.header.stamp.nsecs) - self._topics = ', '.join(msg.topics) - self._location = msg.file + ':' + msg.function + ':' + str(msg.line) - - def set_color(self, color): - """ - :param color: Color Keyword ''str'' - """ - self.__color = color - - def get_color(self): - """ - :returns: Color Keyword ''str'' - """ - return self.__color - - def _get_time(self): - return self.__time - - def _set_time(self, time): - """ - :param time: date and time to set ''QDateTime'' - """ - self.__time = time - if self._time_format: - self._time_string = self._time.toString(self._time_format) - - _time = property(_get_time, _set_time) - - @staticmethod - def get_message_members(): - return ('_message', '_severity', '_node', '_time', '_topics', '_location') - - @staticmethod - def header_print(): - members = Message.get_message_members() - text = members[2][1:].capitalize() + ';' - text += members[3][1:].capitalize() + ';' - text += members[1][1:].capitalize() + ';' - text += members[4][1:].capitalize() + ';' - text += members[5][1:].capitalize() + ';' - text += members[0][1:].capitalize() + '\n' - return text - def count(self): - return len(self._messagemembers) - - def set_time_format(self, format): - """ - :param format: formatting characters are defined in the QDateTime documentation ''str'' - """ - self._time_format = format - self._time_string = self._time.toString(self._time_format) +class Message(QObject): - def time_as_string(self): - """ - :returns: time in the format provided ''str'' - """ - return self._time.toString(self._time_format) + DEBUG = 1 + INFO = 2 + WARN = 4 + ERROR = 8 + FATAL = 16 - def time_as_datestamp(self): - """ - :returns: seconds with decimal fractions of a second, ''str'' - """ - seconds = self._time.toTime_t() - seconds_in_qdate = QDateTime() - seconds_in_qdate.setTime_t(seconds) - msecs = seconds_in_qdate.msecsTo(self._time) - return str(seconds) + '.' + str(msecs) + SEVERITY_LABELS = { + DEBUG: QCoreApplication.translate('Message', 'Debug'), + INFO: QCoreApplication.translate('Message', 'Info'), + WARN: QCoreApplication.translate('Message', 'Warn'), + ERROR: QCoreApplication.translate('Message', 'Error'), + FATAL: QCoreApplication.translate('Message', 'Fatal'), + } - def datestamp_to_qdatetime(self, secs, nsecs): - """ - :param secs: seconds from a datestamp ''int'' - :param nsecs: nanoseconds from a datestamp ''int'' - :returns: converted time ''QDateTime'' - """ - temp_time = QDateTime() - temp_time.setTime_t(int(secs)) - return temp_time.addMSecs(int(str(nsecs).zfill(9)[:3])) + _next_id = 1 - def load_from_array(self, rowdata): - """ - :param rowdata: - [0] = message, ''str'' - [1] = severity, ''str'' - [2] = node name, ''str'' - [3] = time in seconds including decimal, ''str'' - [4] = topic name, ''str'' - [5] = location value, ''str'' - """ - self._message = rowdata[0] - self._severity = rowdata[1] - self._node = rowdata[2] - self._time = rowdata[3] - self._topics = rowdata[4] - self._location = rowdata[5] - return self - - def file_load(self, text): - """ - :param text: delmited message text as follows, node;time;severity;topics;location;"message" , ''str'' - """ - text = text[1:] - sc_index = text.find('";"') - if sc_index == -1: - raise ValueError('File format is incorrect, missing ";" marker') - self._node = text[:sc_index] - text = text[text.find('";"') + 3:] - sc_index = text.find('";"') - if sc_index == -1: - raise ValueError('File format is incorrect, missing ";" marker') - sec, msec = text[:sc_index].split('.') - self._time = self.datestamp_to_qdatetime(sec, msec + '000000') - text = text[text.find('";"') + 3:] - sc_index = text.find('";"') - if sc_index == -1: - raise ValueError('File format is incorrect, missing ";" marker') - self._severity = text[:sc_index] - text = text[text.find('";"') + 3:] - sc_index = text.find('";"') - if sc_index == -1: - raise ValueError('File format is incorrect, missing ";" marker') - self._topics = text[:sc_index] - text = text[text.find('";"') + 3:] - sc_index = text.find('";"') - if sc_index == -1: - raise ValueError('File format is incorrect, missing ";" marker') - self._location = text[:sc_index] - text = text[sc_index + 2:] - text = text.replace('\\"', '"') - self._message = text[1:-2] - return - - def file_print(self): - text = '"' + self._node + '";' - text += '"' + self.time_as_datestamp() + '";' - text += '"' + self._severity + '";' - text += '"' + self._topics + '";' - text += '"' + self._location + '";' - altered_message = self._message.replace('"', '\\"') - text += '"' + altered_message + '"\n' - return text + def __init__(self): + super(Message, self).__init__() + self.id = Message._next_id + Message._next_id += 1 + + self.message = None + self.severity = None + self.node = None + self.__stamp = (None, None) + self.topics = [] + self.location = None + + self._stamp_compare = None + self._stamp_qdatetime = None + + self._stamp_format = None + self._stamp_string = None + + self.highlighted = True + + def _get_stamp(self): + return self.__stamp + + def _set_stamp(self, stamp): + """ + Update the string representation of the timestamp. + :param stamp: a tuple containing seconds and nano seconds + """ + assert len(stamp) == 2 + self.__stamp = stamp + if None not in self.__stamp: + # shortest string representation to compare stamps + # floats do not provide enough precision + self._stamp_compare = '%08x%08x' % (self.__stamp[0], self.__stamp[1]) + else: + self._stamp_compare = None + self._stamp_qdatetime = self._get_stamp_as_qdatetime(self.__stamp) + if self._stamp_format: + s = self._stamp_qdatetime.toString(self._stamp_format) + if 'ZZZ' in s: + s = s.replace('ZZZ', str(self.__stamp[1]).zfill(9)) + self._stamp_string = s + + stamp = property(_get_stamp, _set_stamp) + + def get_stamp_for_compare(self): + return self._stamp_compare + + def get_stamp_as_qdatetime(self): + return self._stamp_qdatetime + + def _get_stamp_as_qdatetime(self, stamp): + if None in self.__stamp: + return None + dt = QDateTime() + dt.setTime_t(stamp[0]) + dt.addMSecs(int(float(stamp[1]) / 10**6)) + return dt + + def get_stamp_string(self): + return self._stamp_string + + def set_stamp_format(self, format): + self._stamp_format = format + if None not in self.__stamp: + self.stamp = self.__stamp def pretty_print(self): - text = self.tr('Node: ') + self._node + '\n' - text += self.tr('Time: ') + self.time_as_datestamp() + '\n' - text += self.tr('Severity: ') + self._severity + '\n' - text += self.tr('Published Topics: ') + self._topics + '\n' - text += '\n' + self._message + '\n' + text = self.tr('Node: ') + self.node + '\n' + text += self.tr('Time: ') + self.get_stamp_string() + '\n' + text += self.tr('Severity: ') + Message.SEVERITY_LABELS[self.severity] + '\n' + text += self.tr('Published Topics: ') + ', '.join(self.topics) + '\n' + text += '\n' + self.message + '\n' text += '\n' + 'Location:' - text += '\n' + self._location + '\n\n' + text += '\n' + self.location + '\n\n' text += '-' * 100 + '\n\n' return text - - def get_data(self, col): - return getattr(self, Message.get_message_members()[col]) diff --git a/rqt_console/src/rqt_console/message_data_model.py b/rqt_console/src/rqt_console/message_data_model.py index f49eff50..7b32eab3 100644 --- a/rqt_console/src/rqt_console/message_data_model.py +++ b/rqt_console/src/rqt_console/message_data_model.py @@ -30,116 +30,150 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -from message_list import MessageList - from python_qt_binding.QtCore import QAbstractTableModel, QModelIndex, Qt, qWarning -from python_qt_binding.QtGui import QIcon +from python_qt_binding.QtGui import QBrush, QIcon + +from .message import Message +from .message_list import MessageList class MessageDataModel(QAbstractTableModel): + + # the column names must match the message attributes + columns = ['message', 'severity', 'node', 'stamp', 'topics', 'location'] + + severity_colors = { + Message.DEBUG: QBrush(Qt.darkCyan), + Message.INFO: QBrush(Qt.darkBlue), + Message.WARN: QBrush(Qt.darkYellow), + Message.ERROR: QBrush(Qt.darkRed), + Message.FATAL: QBrush(Qt.red), + } + def __init__(self): super(MessageDataModel, self).__init__() self._messages = MessageList() - - self._insert_message_queue = [] - self._paused = False self._message_limit = 20000 - self._error_icon = QIcon.fromTheme('dialog-error') - self._warning_icon = QIcon.fromTheme('dialog-warning') self._info_icon = QIcon.fromTheme('dialog-information') + self._warning_icon = QIcon.fromTheme('dialog-warning') + self._error_icon = QIcon.fromTheme('dialog-error') # BEGIN Required implementations of QAbstractTableModel functions def rowCount(self, parent=None): - return len(self._messages.get_message_list()) + return len(self._messages) def columnCount(self, parent=None): - return self._messages.column_count() + return len(MessageDataModel.columns) + 1 def data(self, index, role=None): if role is None: role = Qt.DisplayRole - messagelist = self._messages.get_message_list() - if index.row() >= 0 and index.row() < len(messagelist): - if index.column() >= 0 and index.column() < messagelist[index.row()].count(): - elements = self._messages.message_members() + if index.row() >= 0 and index.row() < len(self._messages): + msg = self._messages[index.row()] + if index.column() == 0: + if role == Qt.DisplayRole: + return '#%d' % msg.id + elif index.column() > 0 and index.column() < len(MessageDataModel.columns) + 1: + column = MessageDataModel.columns[index.column() - 1] if role == Qt.DisplayRole or role == Qt.UserRole: - if elements[index.column()] == '_time': - data = messagelist[index.row()].time_as_string() + if column == 'stamp': + if role != Qt.UserRole: + data = msg.get_stamp_string() + else: + data = msg.get_stamp_for_compare() else: - data = getattr(messagelist[index.row()], elements[index.column()]) - if role == Qt.UserRole and elements[index.column()] != '_time': - data += ' (%d)' % index.row() + data = getattr(msg, column) + # map severity enum to label + if role == Qt.DisplayRole and column == 'severity': + data = Message.SEVERITY_LABELS[data] + # implode topic names + if column == 'topics': + data = ', '.join(data) + # append row number to define strict order + if role == Qt.UserRole: + # append row number to define strict order + # shortest string representation to compare stamps + #print(column, data, str(index.row()).zfill(len(str(len(self._messages))))) + data = str(data) + ' %08x' % index.row() return data - elif role == Qt.DecorationRole and index.column() == 0: - msgseverity = messagelist[index.row()].get_data(1) - if msgseverity in (self.tr('Debug'), self.tr('Info')): + + # decorate message column with severity icon + if role == Qt.DecorationRole and column == 'message': + if msg.severity in [Message.DEBUG, Message.INFO]: return self._info_icon - elif msgseverity in (self.tr('Warn')): + elif msg.severity in [Message.WARN]: return self._warning_icon - elif msgseverity in (self.tr('Error'), self.tr('Fatal')): + elif msg.severity in [Message.ERROR, Message.FATAL]: return self._error_icon - elif role == Qt.ToolTipRole: - if elements[index.column()] == '_time': - data = messagelist[index.row()].time_as_string() + + # colorize severity label + if role == Qt.ForegroundRole and column =='severity': + assert msg.severity in MessageDataModel.severity_colors, 'Unknown severity type: %s' % msg.severity + return MessageDataModel.severity_colors[msg.severity] + + if role == Qt.ToolTipRole and column != 'severity': + if column == 'stamp': + data = msg.get_stamp_string() + elif column == 'topics': + data = ', '.join(msg.topics) else: - data = getattr(messagelist[index.row()], elements[index.column()]) - # tag enables word wrap by forcing rich text - return '' + data + '

' + self.tr('Right click for menu.') + '
' + data = getattr(msg, column) + # tag enables word wrap by forcing rich text + return '' + data + '

' + self.tr('Right click for menu.') + '
' def headerData(self, section, orientation, role=None): if role is None: role = Qt.DisplayRole - if role == Qt.DisplayRole: - if orientation == Qt.Horizontal: - sections = self._messages.message_members() - retval = sections[section][1:].capitalize() - return retval - elif orientation == Qt.Vertical: - return '#%d' % (section + 1) + if orientation == Qt.Horizontal: + if role == Qt.DisplayRole: + if section == 0: + return self.tr('#') + else: + return MessageDataModel.columns[section - 1].capitalize() + if role == Qt.ToolTipRole: + if section == 0: + return self.tr('Sort the rows by serial number in descendig order') + else: + return self.tr('Sorting the table by a column other then the serial number slows down the interaction especially when recording high frequency data') + # END Required implementations of QAbstractTableModel functions + def get_message_limit(self): + return self._message_limit + def set_message_limit(self, new_limit): self._message_limit = new_limit - self.manage_message_limit() + self._enforce_message_limit(self._message_limit) - def manage_message_limit(self): - if len(self.get_message_list()) > self._message_limit: - self.beginRemoveRows(QModelIndex(), 0, len(self.get_message_list()) - self._message_limit - 1) - del self.get_message_list()[0:len(self.get_message_list()) - self._message_limit] + def _enforce_message_limit(self, limit): + if len(self._messages) > limit: + self.beginRemoveRows(QModelIndex(), limit, len(self._messages) - 1) + del self._messages[limit:len(self._messages)] self.endRemoveRows() def insert_rows(self, msgs): - """ - Wraps the insert_row function to minimize gui notification calls - """ - if len(msgs) == 0: - return - self.beginInsertRows(QModelIndex(), len(self._messages.get_message_list()), len(self._messages.get_message_list()) + len(msgs) - 1) - for msg in msgs: - self.insert_row(msg, False) + # never try to insert more message than the limit + if len(msgs) > self._message_limit: + msgs = msgs[-self._message_limit:] + # reduce model before insert + limit = self._message_limit - len(msgs) + self._enforce_message_limit(limit) + # insert newest messages + self.beginInsertRows(QModelIndex(), 0, len(msgs) - 1) + self._messages.extend(msgs) self.endInsertRows() - self.manage_message_limit() - - def insert_row(self, msg, notify_model=True): - if notify_model: - self.beginInsertRows(QModelIndex(), len(self._messages.get_message_list()), len(self._messages.get_message_list())) - self._messages.add_message(msg) - if notify_model: - self.endInsertRows() def remove_rows(self, rowlist): """ :param rowlist: list of row indexes, ''list(int)'' :returns: True if the indexes were removed successfully, ''bool'' - OR - :returns: False if there was an exception removing the rows, ''bool'' """ if len(rowlist) == 0: - if len(self.get_message_list()) > 0: + if len(self._messages) > 0: try: - self.beginRemoveRows(QModelIndex(), 0, len(self.get_message_list())) - del self.get_message_list()[0:len(self.get_message_list())] + self.beginRemoveRows(QModelIndex(), 0, len(self._messages)) + del self._messages[0:len(self._messages)] self.endRemoveRows() except: return False @@ -151,7 +185,7 @@ def remove_rows(self, rowlist): if dellist[-1] - 1 > row: try: self.beginRemoveRows(QModelIndex(), dellist[-1], dellist[0]) - del self.get_message_list()[dellist[-1]:dellist[0] + 1] + del self._messages[dellist[-1]:dellist[0] + 1] self.endRemoveRows() except: return False @@ -160,7 +194,7 @@ def remove_rows(self, rowlist): if len(dellist) > 0: try: self.beginRemoveRows(QModelIndex(), dellist[-1], dellist[0]) - del self.get_message_list()[dellist[-1]:dellist[0] + 1] + del self._messages[dellist[-1]:dellist[0] + 1] self.endRemoveRows() except: return False @@ -177,7 +211,7 @@ def get_selected_text(self, rowlist): text = '' rowlist = list(set(rowlist)) for row in rowlist: - text += self.get_message_list()[row].pretty_print() + text += self._messages[row].pretty_print() return text def get_time_range(self, rowlist): @@ -188,80 +222,46 @@ def get_time_range(self, rowlist): min_ = float("inf") max_ = float("-inf") for row in rowlist: - item = self.get_message_list()[row].time_as_datestamp() + item = self._messages[row].time_as_datestamp() if float(item) > float(max_): max_ = item if float(item) < float(min_): min_ = item return min_, max_ - def get_unique_col_data(self, index, separate_topics=True): - """ - :param index: column index, ''int'' - :param separate_topics: if true separates comma delimited strings into - unique rows, ''bool'' - :returns: list of unique strings in the column, ''list[str]'' - """ - if index == 4 and separate_topics: - unique_list = set() - for topiclists in self._messages.get_unique_col_data(index): - for item in topiclists.split(','): - unique_list.add(item.strip()) - return list(unique_list) - return self._messages.get_unique_col_data(index) - - def get_severity_list(self): - return [self.tr('Debug'), self.tr('Info'), self.tr('Warn'), self.tr('Error'), self.tr('Fatal')] + def get_unique_nodes(self): + nodes = set([]) + for message in self._messages: + nodes.add(message.node) + return nodes - def get_data(self, row, col): - return self._messages.get_data(row, col) + def get_unique_severities(self): + severities = set([]) + for message in self._messages: + severities.add(message.severity) + return severities - def message_members(self): - return self._messages.message_members() + def get_unique_topics(self): + topics = set([]) + for message in self._messages: + for topic in message.topics: + topics.add(topic) + return topics - def load_from_file(self, filehandle): - """ - Saves to an already open filehandle. - :returns: True if loaded successfully, ''bool'' - OR - :returns: False if load fails, ''bool'' - """ - line = filehandle.readline() - lines = [] - if line == self._messages.header_print(): - while 1: - line = filehandle.readline() - if not line: - break - while line[-2] != "\"": - newline = filehandle.readline() - if not line: - qWarning('File does not appear to be a rqt_console message file: missing " at end of file') - return False - line = line + newline - lines.append(line) - self.beginInsertRows(QModelIndex(), len(self._messages.get_message_list()), len(self._messages.get_message_list()) + len(lines) - 1) - for line in lines: - try: - self._messages.append_from_text(line) - except ValueError: - qWarning('File does not appear to be a rqt_console message file: File line is malformed %s' % line) - self.endInsertRows() - self._paused = True - return True - else: - qWarning('File does not appear to be a rqt_console message file: missing file header.') - return False + def get_severity_dict(self): + return Message.SEVERITY_LABELS - def get_message_list(self, start_time=None, end_time=None): + def get_message_between(self, start_time, end_time=None): """ :param start_time: time to start in timestamp form (including decimal - fractions of a second is acceptable, ''unixtimestamp'' (Optional) + fractions of a second is acceptable, ''unixtimestamp'' :param end_time: time to end in timestamp form (including decimal fractions of a second is acceptable, ''unixtimestamp'' (Optional) :returns: list of messages in the time range ''list[message]'' """ - if start_time is not None: - return self._messages.get_messages_in_time_range(start_time, end_time) - else: - return self._messages.get_message_list() + msgs = [] + for message in self._messages: + msg_time = message.stamp[0] + float(message.stamp[1]) / 10**9 + if msg_time >= float(start_time) and (end_time is None or msg_time <= float(end_time)): + msgs.append(message) + return msgs diff --git a/rqt_console/src/rqt_console/message_list.py b/rqt_console/src/rqt_console/message_list.py index 24c8d269..b0c1c910 100644 --- a/rqt_console/src/rqt_console/message_list.py +++ b/rqt_console/src/rqt_console/message_list.py @@ -1,6 +1,6 @@ # Software License Agreement (BSD License) # -# Copyright (c) 2012, Willow Garage, Inc. +# Copyright (c) 2013, Open Source Robotics Foundation Inc. # All rights reserved. # # Redistribution and use in source and binary forms, with or without @@ -30,77 +30,34 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -from .message import Message - class MessageList(object): - """ - Partially simulates a two dimensional list with a single dimensional list of - message objects. Also provides utility functions to provide data in useful formats - """ - def __init__(self): - self._messagelist = [] - self._time_format = 'hh:mm:ss.zzz (yyyy-MM-dd)' - - def column_count(self): - return len(Message.get_message_members()) - def get_message_list(self): - return self._messagelist - - def message_members(self): - return Message.get_message_members() + def __init__(self): + super(MessageList, self).__init__() + self._messages = [] - def append_from_text(self, text): - newmessage = Message() - newmessage.file_load(text) - newmessage.set_time_format(self._time_format) - self._messagelist.append(newmessage) + def __getitem__(self, key): + return self._messages[len(self._messages) - key - 1] - def get_data(self, row, col): - if row >= 0 and row < len(self.get_message_list()) and col >= 0 and col < len(Message.get_message_members()): - return self.get_message_list()[row].get_data(col) + def __delitem__(self, key): + if isinstance(key, slice): + assert key.step is None or key.step == 1, 'MessageList.__delitem__ not implemented for slices with step argument different than 1' + del self._messages[len(self._messages) - key.stop:len(self._messages) - key.start] else: - raise IndexError + del self._messages[len(self._messages) - key - 1] - def get_unique_col_data(self, index): - """ - :param index: col index, ''int'' - :returns: a unique list of data index, ''list[str]'' - """ - uniques_list = set() - for message in self._messagelist: - uniques_list.add(getattr(message, self.message_members()[index])) - return list(uniques_list) + def __iter__(self): + return reversed(self._messages) - def add_message(self, msg): - message = Message(msg) - message.set_time_format(self._time_format) - self._messagelist.append(message) + def __reversed__(self): + return iter(self._messages) - def set_time_format(self, format): - """ - :param format: formatting characters are defined in the QDateTime documentation ''str'' - """ - self._time_format = format - for message in self._messagelist: - message.set_time_format(self._time_format) + def __contains__(self, item): + return item in self._messages - def header_print(self): - return Message.header_print() + def __len__(self): + return len(self._messages) - def get_messages_in_time_range(self, start_time, end_time=None): - """ - :param start_time: time to start in timestamp form (including decimal - fractions of a second is acceptable, ''unixtimestamp'' - :param end_time: time to end in timestamp form (including decimal - fractions of a second is acceptable, ''unixtimestamp'' (Optional) - :returns: list of messages in the time range ''list[message]'' - """ - message_list = self.get_message_list() - time_range_list = [] - for message in message_list: - msg_time = message.time_as_datestamp() - if float(msg_time) >= float(start_time) and (end_time is None or float(msg_time) <= float(end_time)): - time_range_list.append(message) - return time_range_list + def extend(self, item): + self._messages.extend(item) diff --git a/rqt_console/src/rqt_console/message_proxy_model.py b/rqt_console/src/rqt_console/message_proxy_model.py index af3e7342..62554733 100644 --- a/rqt_console/src/rqt_console/message_proxy_model.py +++ b/rqt_console/src/rqt_console/message_proxy_model.py @@ -34,80 +34,85 @@ from python_qt_binding.QtGui import QBrush, QColor, QSortFilterProxyModel from .filters.filter_collection import FilterCollection +from .message import Message class MessageProxyModel(QSortFilterProxyModel): """ Provides sorting and filtering capabilities for the MessageDataModel. - Filtering is based on subclassed Filters stored in the FilterCollections. + Filtering is based on a collection of exclude and highlight filters. """ + def __init__(self): super(MessageProxyModel, self).__init__() - self._filters = [] self.setDynamicSortFilter(True) - self._show_highlighted_only = False - - self._exclude_filters = FilterCollection(self) - self._highlight_filters = FilterCollection(self) self.setFilterRole(Qt.UserRole) + self.setSortCaseSensitivity(Qt.CaseInsensitive) self.setSortRole(Qt.UserRole) + self._exclude_filters = FilterCollection() + self._highlight_filters = FilterCollection() + self._show_highlighted_only = False + + # caching source model locally for better performance of filterAcceptsRow() + self._source_model = None + + def setSourceModel(self, source_model): + super(MessageProxyModel, self).setSourceModel(source_model) + self._source_model = self.sourceModel() + # BEGIN Required implementations of QSortFilterProxyModel functions + def filterAcceptsRow(self, sourcerow, sourceparent): """ - returns: True if the row does not match the exclude filters AND (_show_highlighted_only is False OR it matches the _highlight_filters, ''bool'' - OR - returns: False if the row matches the exclude filters OR (_show_highlighted_only is True and it doesn't match the _highlight_filters, ''bool'' + returns: True if the row does not match any exclude filter AND (_show_highlighted_only is False OR it matches any highlight filter), ''bool'' """ - rowdata = [] - for index in range(self.sourceModel().columnCount()): - rowdata.append(self.sourceModel().index(sourcerow, index, sourceparent).data(Qt.UserRole)) + msg = self._source_model._messages[sourcerow] + if self._exclude_filters.test_message(msg): + # hide excluded message + return False - if self._exclude_filters.test_message_array(rowdata): + highlighted = True + if self._highlight_filters.count_enabled_filters() > 0: + highlighted = self._highlight_filters.test_message(msg, default=True) + if self._show_highlighted_only and not highlighted: + # hide messages which are not highlighted when only highlightes messages should be visible return False - if self._highlight_filters.count_enabled_filters() == 0: - return True - match = self._highlight_filters.test_message_array(rowdata) - if match: - color = 'black' - else: - color = 'gray' - self.sourceModel()._messages.get_message_list()[sourcerow].set_color(color) - return not self._show_highlighted_only or match - def data(self, index, role=None): + # update message state + msg.highlighted = highlighted + + return True + + def data(self, proxy_index, role=None): """ - Sets colors of items based on highlight filters and severity type + Set colors of items based on highlight filters. """ - messagelist = self.sourceModel()._messages.get_message_list() - index = self.mapToSource(index) - if index.row() >= 0 or index.row() < len(messagelist): - if index.column() >= 0 or index.column() < messagelist[index.row()].count(): - if role == Qt.ForegroundRole: - if index.column() == 1: - data = index.data() - severity_levels = {'Debug': QBrush(Qt.cyan), \ - 'Info': QBrush(Qt.darkCyan), \ - 'Warn': QBrush(Qt.darkYellow), \ - 'Error': QBrush(Qt.darkRed), \ - 'Fatal': QBrush(Qt.red)} - if data in severity_levels.keys(): - return severity_levels[data] - else: - raise KeyError('Unknown severity type: %s' % data) - if self._highlight_filters.count_enabled_filters() > 0: - return QBrush(QColor(messagelist[index.row()].get_color())) - else: - return QBrush(Qt.black) - return self.sourceModel().data(index, role) + index = self.mapToSource(proxy_index) + if role == Qt.ForegroundRole: + msg = self._source_model._messages[index.row()] + if not msg.highlighted: + return QBrush(Qt.gray) + return self._source_model.data(index, role) + # END Required implementations of QSortFilterProxyModel functions - def handle_filters_changed(self): + def handle_exclude_filters_changed(self): """ - Invalidates filters and triggers refiltering + Invalidate filters and trigger refiltering. """ self.invalidateFilter() + def handle_highlight_filters_changed(self): + """ + Invalidate filters and trigger refiltering. + """ + if self._show_highlighted_only: + self.invalidateFilter() + else: + self.invalidateFilter() + self.dataChanged.emit(self.index(0, 0), self.index(self.rowCount() - 1, self.columnCount() - 1)) + def add_exclude_filter(self, newfilter): self._exclude_filters.append(newfilter) @@ -115,36 +120,13 @@ def add_highlight_filter(self, newfilter): self._highlight_filters.append(newfilter) def delete_exclude_filter(self, index): - if index < self._exclude_filters.count() and index >= 0: - del self._exclude_filters[index] - self.reset() - return True - return False + del self._exclude_filters[index] + self.handle_exclude_filters_changed() def delete_highlight_filter(self, index): - if index < self._highlight_filters.count() and index >= 0: - del self._highlight_filters[index] - self.reset() - return True - return False + del self._highlight_filters[index] + self.handle_highlight_filters_changed() def set_show_highlighted_only(self, show_highlighted_only): self._show_highlighted_only = show_highlighted_only - self.reset() - - def save_to_file(self, filehandle): - """ - Saves to an already open filehandle. - :return: True if file write is successful, ''bool'' - OR - :return: False if file write fails, ''bool'' - """ - try: - filehandle.write(self.sourceModel()._messages.header_print()) - for index in range(self.rowCount()): - row = self.mapToSource(self.index(index, 0)).row() - filehandle.write(self.sourceModel()._messages.get_message_list()[row].file_print()) - except Exception as e: - qWarning('File save failed: %s' % str(e)) - return False - return True + self.invalidateFilter()