Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

rewrite of rqt_console #186

Merged
merged 1 commit into from
Sep 29, 2013
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>ConsoleSubscriberDialog</class>
<widget class="QDialog" name="ConsoleSubscriberDialog">
<class>ConsoleSettingsDialog</class>
<widget class="QDialog" name="ConsoleSettingsDialog">
<property name="windowModality">
<enum>Qt::ApplicationModal</enum>
</property>
Expand All @@ -10,7 +10,7 @@
<x>0</x>
<y>0</y>
<width>368</width>
<height>119</height>
<height>123</height>
</rect>
</property>
<property name="windowTitle">
Expand Down Expand Up @@ -71,8 +71,7 @@
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="levelsLayout">
</layout>
<layout class="QHBoxLayout" name="levelsLayout"/>
</item>
<item>
<widget class="QDialogButtonBox" name="buttonBox">
Expand All @@ -88,7 +87,7 @@
<connection>
<sender>buttonBox</sender>
<signal>accepted()</signal>
<receiver>ConsoleSubscriberDialog</receiver>
<receiver>ConsoleSettingsDialog</receiver>
<slot>accept()</slot>
<hints>
<hint type="sourcelabel">
Expand All @@ -104,7 +103,7 @@
<connection>
<sender>buttonBox</sender>
<signal>rejected()</signal>
<receiver>ConsoleSubscriberDialog</receiver>
<receiver>ConsoleSettingsDialog</receiver>
<slot>reject()</slot>
<hints>
<hint type="sourcelabel">
Expand Down
28 changes: 15 additions & 13 deletions rqt_console/resource/console_widget.ui
Original file line number Diff line number Diff line change
Expand Up @@ -131,21 +131,30 @@
<widget class="QWidget" name="PlaceHolder">
<layout class="QVBoxLayout" name="verticalLayout_3">
<item>
<widget class="ConsoleTableView" name="table_view">
<widget class="QTableView" name="table_view">
<property name="alternatingRowColors">
<bool>true</bool>
</property>
<property name="selectionBehavior">
<enum>QAbstractItemView::SelectRows</enum>
</property>
<property name="iconSize">
<size>
<width>16</width>
<height>16</height>
</size>
</property>
<property name="horizontalScrollMode">
<enum>QAbstractItemView::ScrollPerPixel</enum>
</property>
<property name="sortingEnabled">
<bool>true</bool>
</property>
<attribute name="verticalHeaderDefaultSectionSize">
<number>18</number>
<attribute name="horizontalHeaderShowSortIndicator" stdset="0">
<bool>false</bool>
</attribute>
<attribute name="verticalHeaderMinimumSectionSize">
<number>18</number>
<attribute name="verticalHeaderVisible">
<bool>false</bool>
</attribute>
</widget>
</item>
Expand Down Expand Up @@ -218,7 +227,7 @@
</widget>
<widget class="QGroupBox" name="highlight_group_box">
<property name="toolTip">
<string>Message matching ANY of these rules will be highlighted</string>
<string>Messages matching ANY of these rules will be highlighted</string>
</property>
<property name="title">
<string>Highlight Messages...</string>
Expand Down Expand Up @@ -313,13 +322,6 @@
</item>
</layout>
</widget>
<customwidgets>
<customwidget>
<class>ConsoleTableView</class>
<extends>QTableView</extends>
<header>rqt_console.console_widget</header>
</customwidget>
</customwidgets>
<resources/>
<connections/>
</ui>
27 changes: 26 additions & 1 deletion rqt_console/resource/filters/custom_filter_widget.ui
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<layout class="QHBoxLayout" name="horizontalLayout_2" stretch="0,0,0,0,1">
<property name="spacing">
<number>0</number>
</property>
Expand All @@ -79,14 +79,27 @@
<property name="editTriggers">
<set>QAbstractItemView::NoEditTriggers</set>
</property>
<property name="alternatingRowColors">
<bool>true</bool>
</property>
<property name="selectionMode">
<enum>QAbstractItemView::MultiSelection</enum>
</property>
<property name="flow">
<enum>QListView::LeftToRight</enum>
</property>
<property name="spacing">
<number>1</number>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="leftMargin">
<number>20</number>
</property>
</layout>
</item>
<item>
<widget class="QLabel" name="label_3">
<property name="text">
Expand All @@ -108,12 +121,18 @@
<property name="editTriggers">
<set>QAbstractItemView::NoEditTriggers</set>
</property>
<property name="alternatingRowColors">
<bool>true</bool>
</property>
<property name="selectionMode">
<enum>QAbstractItemView::MultiSelection</enum>
</property>
<property name="flow">
<enum>QListView::LeftToRight</enum>
</property>
<property name="spacing">
<number>1</number>
</property>
</widget>
</item>
</layout>
Expand Down Expand Up @@ -144,12 +163,18 @@
<property name="editTriggers">
<set>QAbstractItemView::NoEditTriggers</set>
</property>
<property name="alternatingRowColors">
<bool>true</bool>
</property>
<property name="selectionMode">
<enum>QAbstractItemView::MultiSelection</enum>
</property>
<property name="flow">
<enum>QListView::LeftToRight</enum>
</property>
<property name="spacing">
<number>1</number>
</property>
</widget>
</item>
</layout>
Expand Down
6 changes: 6 additions & 0 deletions rqt_console/resource/filters/list_filter_widget.ui
Original file line number Diff line number Diff line change
Expand Up @@ -33,12 +33,18 @@
<property name="editTriggers">
<set>QAbstractItemView::NoEditTriggers</set>
</property>
<property name="alternatingRowColors">
<bool>true</bool>
</property>
<property name="selectionMode">
<enum>QAbstractItemView::MultiSelection</enum>
</property>
<property name="flow">
<enum>QListView::LeftToRight</enum>
</property>
<property name="spacing">
<number>1</number>
</property>
</widget>
</item>
</layout>
Expand Down
91 changes: 61 additions & 30 deletions rqt_console/src/rqt_console/console.py
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand All @@ -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
Original file line number Diff line number Diff line change
Expand Up @@ -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
Loading