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
00042 from python_qt_binding.QtWidgets import QWidget
00043 import rospy
00044 
00045 from .inspector_window import InspectorWindow
00046 from .status_item import StatusItem
00047 from .timeline_pane import TimelinePane
00048 from .timeline import Timeline
00049 import rqt_robot_monitor.util_robot_monitor as util
00050 
00051 class RobotMonitorWidget(QWidget):
00052     """
00053     NOTE: RobotMonitorWidget.shutdown function needs to be called
00054     when the instance of this class terminates.
00055 
00056     RobotMonitorWidget itself doesn't store previous diagnostic states.
00057     It instead delegates that function to Timeline class.
00058     """
00059 
00060     _TREE_ALL = 1
00061     _TREE_WARN = 2
00062     _TREE_ERR = 3
00063 
00064     message_updated = Signal(DiagnosticArray)
00065 
00066     def __init__(self, context, topic=None):
00067         """
00068         :param context: plugin context hook to enable adding widgets as a
00069                         ROS_GUI pane, 'PluginContext'
00070         :param topic: Diagnostic topic to subscribe to 'str'
00071         """
00072 
00073         super(RobotMonitorWidget, self).__init__()
00074         rp = rospkg.RosPack()
00075         ui_file = os.path.join(rp.get_path('rqt_robot_monitor'), 'resource',
00076                                'robotmonitor_mainwidget.ui')
00077         loadUi(ui_file, self)
00078 
00079         obj_name = 'Robot Monitor'
00080         self.setObjectName(obj_name)
00081         self.setWindowTitle(obj_name)
00082 
00083         self.message_updated.connect(self.message_cb)
00084 
00085         # if we're given a topic, create a timeline. otherwise, don't
00086         #  this can be used later when writing an rqt_bag plugin
00087         if topic:
00088             # create timeline data structure
00089             self._timeline = Timeline(topic, DiagnosticArray)
00090             self._timeline.message_updated.connect(self.message_updated)
00091 
00092             # create timeline pane widget
00093             self.timeline_pane = TimelinePane(self)
00094 
00095             self.timeline_pane.set_timeline(self._timeline)
00096 
00097             self.vlayout_top.addWidget(self.timeline_pane)
00098             self.timeline_pane.show()
00099         else:
00100             self._timeline = None
00101             self.timeline_pane = None
00102 
00103         self._inspectors = {}
00104         # keep a copy of the current message for opening new inspectors
00105         self._current_msg = None
00106 
00107         self.tree_all_devices.itemDoubleClicked.connect(self._tree_clicked)
00108         self.warn_flattree.itemDoubleClicked.connect(self._tree_clicked)
00109         self.err_flattree.itemDoubleClicked.connect(self._tree_clicked)
00110         # TODO: resize on itemCollapsed and itemExpanded
00111 
00112         self._is_stale = False
00113 
00114         self._timer = QTimer()
00115         self._timer.timeout.connect(self._update_message_state)
00116         self._timer.start(1000)
00117 
00118         palette = self.tree_all_devices.palette()
00119         self._original_base_color = palette.base().color()
00120         self._original_alt_base_color = palette.alternateBase().color()
00121 
00122         self._tree = StatusItem(self.tree_all_devices.invisibleRootItem())
00123         self._warn_tree = StatusItem(self.warn_flattree.invisibleRootItem())
00124         self._err_tree = StatusItem(self.err_flattree.invisibleRootItem())
00125 
00126     @Slot(DiagnosticArray)
00127     def message_cb(self, msg):
00128         """ DiagnosticArray message callback """
00129         self._current_msg = msg
00130 
00131         # Walk the status array and update the tree
00132         for status in msg.status:
00133             # Compute path and walk to appropriate subtree
00134             path = status.name.split('/')
00135             if path[0] == '':
00136                 path = path[1:]
00137             tmp_tree = self._tree
00138             for p in path:
00139                 tmp_tree = tmp_tree[p]
00140             tmp_tree.update(status, util.get_resource_name(status.name))
00141 
00142             # Check for warnings
00143             if status.level == DiagnosticStatus.WARN:
00144                 name = status.name
00145                 self._warn_tree[name].update(status, status.name)
00146 
00147             # Check for errors
00148             if status.level == DiagnosticStatus.ERROR:
00149                 name = status.name
00150                 self._err_tree[name].update(status, status.name)
00151 
00152         # For any items in the tree that were not updated, remove them
00153         self._tree.prune()
00154         self._warn_tree.prune()
00155         self._err_tree.prune()
00156 
00157         # TODO(ahendrix): implement
00158         # Insight: for any item that is not OK, it only provides additional
00159         #          information if all of it's children are OK
00160         #
00161         #          otherwise, it's just an aggregation of its children
00162         #          and doesn't provide any additional value when added to
00163         #          the warning and error flat trees
00164 
00165         self.tree_all_devices.resizeColumnToContents(0)
00166         self.warn_flattree.resizeColumnToContents(0)
00167         self.err_flattree.resizeColumnToContents(0)
00168 
00169     def resizeEvent(self, evt):
00170         """Overridden from QWidget"""
00171         rospy.logdebug('RobotMonitorWidget resizeEvent')
00172         if self.timeline_pane:
00173             self.timeline_pane.redraw()
00174 
00175     @Slot(str)
00176     def _inspector_closed(self, name):
00177         """ Called when an inspector window is closed """
00178         if name in self._inspectors:
00179             del self._inspectors[name]
00180 
00181     def _tree_clicked(self, item, column):
00182         """
00183         Slot to QTreeWidget.itemDoubleClicked
00184 
00185         :type item: QTreeWidgetItem
00186         :type column: int
00187         """
00188         rospy.logdebug('RobotMonitorWidget _tree_clicked col=%d', column)
00189         if item.name in self._inspectors:
00190             self._inspectors[item.name].activateWindow()
00191         else:
00192             self._inspectors[item.name] = InspectorWindow(self, item.name,
00193                     self._current_msg, self._timeline)
00194             self._inspectors[item.name].closed.connect(self._inspector_closed)
00195             self.message_updated.connect(self._inspectors[item.name].message_updated)
00196 
00197     def _update_message_state(self):
00198         """ Update the display if it's stale """
00199         if self._timeline is not None:
00200             if self._timeline.has_messages:
00201                 previous_stale_state = self._is_stale
00202                 self._is_stale = self._timeline.is_stale
00203 
00204                 time_diff = int(self._timeline.data_age())
00205 
00206                 msg_template = "Last message received %s %s ago"
00207                 if time_diff == 1:
00208                     msg = msg_template % (time_diff, "second")
00209                 else:
00210                     msg = msg_template % (time_diff, "seconds")
00211                 self.timeline_pane._msg_label.setText(msg)
00212                 if previous_stale_state != self._is_stale:
00213                     self._update_background_color()
00214             else:
00215                 # no messages received yet
00216                 self.timeline_pane._msg_label.setText("No messages received")
00217 
00218     def _update_background_color(self):
00219         """ Update the background color based on staleness """
00220         p = self.tree_all_devices.palette()
00221         if self._is_stale:
00222             p.setColor(QPalette.Base, Qt.darkGray)
00223             p.setColor(QPalette.AlternateBase, Qt.lightGray)
00224         else:
00225             p.setColor(QPalette.Base, self._original_base_color)
00226             p.setColor(QPalette.AlternateBase, self._original_alt_base_color)
00227         self.tree_all_devices.setPalette(p)
00228         self.warn_flattree.setPalette(p)
00229         self.err_flattree.setPalette(p)
00230 
00231     def shutdown(self):
00232         """
00233         This needs to be called whenever this class terminates.
00234         This closes all the instances on all trees.
00235         Also unregisters ROS' subscriber, stops timer.
00236         """
00237         rospy.logdebug('RobotMonitorWidget in shutdown')
00238 
00239         names = self._inspectors.keys()
00240         for name in names:
00241             self._inspectors[name].close()
00242 
00243         if self._timeline:
00244             self._timeline.shutdown()
00245 
00246         self._timer.stop()
00247         del self._timer
00248 
00249     def save_settings(self, plugin_settings, instance_settings):
00250         instance_settings.set_value('splitter', self.splitter.saveState())
00251         # TODO(ahendrix): persist the device paths, positions and sizes of any
00252         #                 inspector windows
00253 
00254     def restore_settings(self, plugin_settings, instance_settings):
00255         if instance_settings.contains('splitter'):
00256             self.splitter.restoreState(instance_settings.value('splitter'))
00257         else:
00258             self.splitter.setSizes([100, 100, 200])
00259         # TODO(ahendrix): restore inspector windows


rqt_robot_monitor
Author(s): Austin Hendrix, Isaac Saito, Ze'ev Klapow, Kevin Watts, Josh Faust
autogenerated on Tue Sep 26 2017 02:44:21