robot_monitor.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2012, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions
00008 # are met:
00009 #
00010 #  * Redistributions of source code must retain the above copyright
00011 #    notice, this list of conditions and the following disclaimer.
00012 #  * Redistributions in binary form must reproduce the above
00013 #    copyright notice, this list of conditions and the following
00014 #    disclaimer in the documentation and/or other materials provided
00015 #    with the distribution.
00016 #  * Neither the name of Willow Garage, Inc. nor the names of its
00017 #    contributors may be used to endorse or promote products derived
00018 #    from this software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 # POSSIBILITY OF SUCH DAMAGE.
00032 #
00033 # Author: Isaac Saito, Ze'ev Klapow, Austin Hendrix
00034 
00035 import os
00036 import rospkg
00037 
00038 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus
00039 from python_qt_binding import loadUi
00040 from python_qt_binding.QtCore import QTimer, Signal, Qt, Slot
00041 from python_qt_binding.QtGui import QPalette, QWidget
00042 import rospy
00043 
00044 from .inspector_window import InspectorWindow
00045 from .status_item import StatusItem
00046 from .timeline_pane import TimelinePane
00047 from .timeline import Timeline
00048 import util_robot_monitor as util
00049 
00050 class RobotMonitorWidget(QWidget):
00051     """
00052     NOTE: RobotMonitorWidget.shutdown function needs to be called
00053     when the instance of this class terminates.
00054 
00055     RobotMonitorWidget itself doesn't store previous diagnostic states.
00056     It instead delegates that function to Timeline class.
00057     """
00058 
00059     _TREE_ALL = 1
00060     _TREE_WARN = 2
00061     _TREE_ERR = 3
00062 
00063     message_updated = Signal(DiagnosticArray)
00064 
00065     def __init__(self, context, topic=None):
00066         """
00067         :param context: plugin context hook to enable adding widgets as a
00068                         ROS_GUI pane, 'PluginContext'
00069         :param topic: Diagnostic topic to subscribe to 'str'
00070         """
00071 
00072         super(RobotMonitorWidget, self).__init__()
00073         rp = rospkg.RosPack()
00074         ui_file = os.path.join(rp.get_path('rqt_robot_monitor'), 'resource',
00075                                'robotmonitor_mainwidget.ui')
00076         loadUi(ui_file, self)
00077 
00078         obj_name = 'Robot Monitor'
00079         self.setObjectName(obj_name)
00080         self.setWindowTitle(obj_name)
00081 
00082         self.message_updated.connect(self.message_cb)
00083 
00084         # if we're given a topic, create a timeline. otherwise, don't
00085         #  this can be used later when writing an rqt_bag plugin
00086         if topic:
00087             # create timeline data structure
00088             self._timeline = Timeline(topic, DiagnosticArray)
00089             self._timeline.message_updated.connect(self.message_updated)
00090 
00091             # create timeline pane widget
00092             self.timeline_pane = TimelinePane(self)
00093 
00094             self.timeline_pane.set_timeline(self._timeline)
00095 
00096             self.vlayout_top.addWidget(self.timeline_pane)
00097             self.timeline_pane.show()
00098         else:
00099             self._timeline = None
00100             self.timeline_pane = None
00101 
00102         self._inspectors = {}
00103         # keep a copy of the current message for opening new inspectors
00104         self._current_msg = None
00105 
00106         self.tree_all_devices.itemDoubleClicked.connect(self._tree_clicked)
00107         self.warn_flattree.itemDoubleClicked.connect(self._tree_clicked)
00108         self.err_flattree.itemDoubleClicked.connect(self._tree_clicked)
00109         # TODO: resize on itemCollapsed and itemExpanded
00110 
00111         self._is_stale = False
00112 
00113         self._timer = QTimer()
00114         self._timer.timeout.connect(self._update_message_state)
00115         self._timer.start(1000)
00116 
00117         palette = self.tree_all_devices.palette()
00118         self._original_base_color = palette.base().color()
00119         self._original_alt_base_color = palette.alternateBase().color()
00120 
00121         self._tree = StatusItem(self.tree_all_devices.invisibleRootItem())
00122         self._warn_tree = StatusItem(self.warn_flattree.invisibleRootItem())
00123         self._err_tree = StatusItem(self.err_flattree.invisibleRootItem())
00124 
00125     @Slot(DiagnosticArray)
00126     def message_cb(self, msg):
00127         """ DiagnosticArray message callback """
00128         self._current_msg = msg
00129 
00130         # Walk the status array and update the tree
00131         for status in msg.status:
00132             # Compute path and walk to appropriate subtree
00133             path = status.name.split('/')
00134             if path[0] == '':
00135                 path = path[1:]
00136             tmp_tree = self._tree
00137             for p in path:
00138                 tmp_tree = tmp_tree[p]
00139             tmp_tree.update(status, util.get_resource_name(status.name))
00140 
00141             # Check for warnings
00142             if status.level == DiagnosticStatus.WARN:
00143                 name = status.name
00144                 self._warn_tree[name].update(status, status.name)
00145 
00146             # Check for errors
00147             if status.level == DiagnosticStatus.ERROR:
00148                 name = status.name
00149                 self._err_tree[name].update(status, status.name)
00150 
00151         # For any items in the tree that were not updated, remove them
00152         self._tree.prune()
00153         self._warn_tree.prune()
00154         self._err_tree.prune()
00155 
00156         # TODO(ahendrix): implement
00157         # Insight: for any item that is not OK, it only provides additional
00158         #          information if all of it's children are OK
00159         #
00160         #          otherwise, it's just an aggregation of its children
00161         #          and doesn't provide any additional value when added to
00162         #          the warning and error flat trees
00163 
00164         self.tree_all_devices.resizeColumnToContents(0)
00165         self.warn_flattree.resizeColumnToContents(0)
00166         self.err_flattree.resizeColumnToContents(0)
00167 
00168     def resizeEvent(self, evt):
00169         """Overridden from QWidget"""
00170         rospy.logdebug('RobotMonitorWidget resizeEvent')
00171         if self.timeline_pane:
00172             self.timeline_pane.redraw()
00173 
00174     @Slot(str)
00175     def _inspector_closed(self, name):
00176         """ Called when an inspector window is closed """
00177         if name in self._inspectors:
00178             del self._inspectors[name]
00179 
00180     def _tree_clicked(self, item, column):
00181         """
00182         Slot to QTreeWidget.itemDoubleClicked
00183 
00184         :type item: QTreeWidgetItem
00185         :type column: int
00186         """
00187         rospy.logdebug('RobotMonitorWidget _tree_clicked col=%d', column)
00188         if item.name in self._inspectors:
00189             self._inspectors[item.name].activateWindow()
00190         else:
00191             self._inspectors[item.name] = InspectorWindow(self, item.name,
00192                     self._current_msg, self._timeline)
00193             self._inspectors[item.name].closed.connect(self._inspector_closed)
00194             self.message_updated.connect(self._inspectors[item.name].message_updated)
00195 
00196     def _update_message_state(self):
00197         """ Update the display if it's stale """
00198         if self._timeline is not None:
00199             if self._timeline.has_messages:
00200                 previous_stale_state = self._is_stale
00201                 self._is_stale = self._timeline.is_stale
00202 
00203                 time_diff = int(self._timeline.data_age())
00204 
00205                 msg_template = "Last message received %s %s ago"
00206                 if time_diff == 1:
00207                     msg = msg_template % (time_diff, "second")
00208                 else:
00209                     msg = msg_template % (time_diff, "seconds")
00210                 self.timeline_pane._msg_label.setText(msg)
00211                 if previous_stale_state != self._is_stale:
00212                     self._update_background_color()
00213             else:
00214                 # no messages received yet
00215                 self.timeline_pane._msg_label.setText("No messages received")
00216 
00217     def _update_background_color(self):
00218         """ Update the background color based on staleness """
00219         p = self.tree_all_devices.palette()
00220         if self._is_stale:
00221             p.setColor(QPalette.Base, Qt.darkGray)
00222             p.setColor(QPalette.AlternateBase, Qt.lightGray)
00223         else:
00224             p.setColor(QPalette.Base, self._original_base_color)
00225             p.setColor(QPalette.AlternateBase, self._original_alt_base_color)
00226         self.tree_all_devices.setPalette(p)
00227         self.warn_flattree.setPalette(p)
00228         self.err_flattree.setPalette(p)
00229 
00230     def shutdown(self):
00231         """
00232         This needs to be called whenever this class terminates.
00233         This closes all the instances on all trees.
00234         Also unregisters ROS' subscriber, stops timer.
00235         """
00236         rospy.logdebug('RobotMonitorWidget in shutdown')
00237 
00238         names = self._inspectors.keys()
00239         for name in names:
00240             self._inspectors[name].close()
00241 
00242         if self._timeline:
00243             self._timeline.shutdown()
00244 
00245         self._timer.stop()
00246         del self._timer
00247 
00248     def save_settings(self, plugin_settings, instance_settings):
00249         instance_settings.set_value('splitter', self.splitter.saveState())
00250         # TODO(ahendrix): persist the device paths, positions and sizes of any
00251         #                 inspector windows
00252 
00253     def restore_settings(self, plugin_settings, instance_settings):
00254         if instance_settings.contains('splitter'):
00255             self.splitter.restoreState(instance_settings.value('splitter'))
00256         else:
00257             self.splitter.setSizes([100, 100, 200])
00258         # TODO(ahendrix): restore inspector windows


rqt_robot_monitor
Author(s): Austin Hendrix, Isaac Saito, Ze'ev Klapow, Kevin Watts, Josh Faust
autogenerated on Fri Aug 28 2015 12:50:47