Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 import rospy
00034 from diagnostic_msgs.msg import DiagnosticStatus
00035 from QtCore import QMutex, QMutexLocker, QSize, QTimer
00036 from rqt_robot_monitor import RobotMonitorWidget
00037 from .icon_tool_button import IconToolButton
00038 
00039 
00040 class MonitorDashWidget(IconToolButton):
00041     """
00042     A widget which brings up the rqt_robot_monitor.
00043 
00044     :param context: The plugin context to create the monitor in.
00045     :type context: qt_gui.plugin_context.PluginContext
00046     """
00047     def __init__(self, context, icon_paths=[]):
00048         self._graveyard = []
00049         ok_icon = ['bg-green.svg', 'ic-diagnostics.svg']
00050         warn_icon = ['bg-yellow.svg', 'ic-diagnostics.svg', 'ol-warn-badge.svg']
00051         err_icon = ['bg-red.svg', 'ic-diagnostics.svg', 'ol-err-badge.svg']
00052         stale_icon = ['bg-grey.svg', 'ic-diagnostics.svg', 'ol-stale-badge.svg']
00053 
00054         icons = [ok_icon, warn_icon, err_icon, stale_icon]
00055 
00056         super(MonitorDashWidget, self).__init__('MonitorWidget', icons, icon_paths=icon_paths)
00057 
00058         self.setFixedSize(self._icons[0].actualSize(QSize(50, 30)))
00059 
00060         self._monitor = None
00061         self._close_mutex = QMutex()
00062         self._show_mutex = QMutex()
00063 
00064         self._last_update = rospy.Time.now()
00065 
00066         self.context = context
00067         self.clicked.connect(self._show_monitor)
00068 
00069         self._monitor_shown = False
00070         self.setToolTip('Diagnostics')
00071 
00072         self._diagnostics_toplevel_state_sub = rospy.Subscriber('diagnostics_toplevel_state', DiagnosticStatus, self.toplevel_state_callback)
00073         self._top_level_state = -1
00074         self._stall_timer = QTimer()
00075         self._stall_timer.timeout.connect(self._stalled)
00076         self._stalled()
00077         self._plugin_settings = None
00078         self._instance_settings = None
00079 
00080     def toplevel_state_callback(self, msg):
00081         self._is_stale = False
00082         self._stall_timer.start(5000)
00083 
00084         if self._top_level_state != msg.level:
00085             if (msg.level >= 2):
00086                 self.update_state(2)
00087                 self.setToolTip("Diagnostics: Error")
00088             elif (msg.level == 1):
00089                 self.update_state(1)
00090                 self.setToolTip("Diagnostics: Warning")
00091             else:
00092                 self.update_state(0)
00093                 self.setToolTip("Diagnostics: OK")
00094             self._top_level_state = msg.level
00095 
00096     def _stalled(self):
00097         self._stall_timer.stop()
00098         self._is_stale = True
00099         self.update_state(3)
00100         self.setToolTip("Diagnostics: Stale\nNo message received on dashboard_agg in the last 5 seconds")
00101 
00102     def _show_monitor(self):
00103         with QMutexLocker(self._show_mutex):
00104             try:
00105                 if self._monitor_shown:
00106                     self.context.remove_widget(self._monitor)
00107                     self._monitor_close()
00108                     self._monitor_shown = False
00109                 else:
00110                     self._monitor = RobotMonitorWidget(self.context, 'diagnostics_agg')
00111                     if self._plugin_settings:
00112                         self._monitor.restore_settings(self._plugin_settings, self._instance_settings)
00113                     self.context.add_widget(self._monitor)
00114                     self._monitor_shown = True
00115             except Exception:
00116                 if self._monitor_shown == False:
00117                     raise
00118                 
00119                 self._monitor_shown = False
00120                 self._show_monitor()
00121 
00122     def _monitor_close(self):
00123         if self._monitor_shown:
00124             with QMutexLocker(self._close_mutex):
00125                 if self._plugin_settings:
00126                     self._monitor.save_settings(self._plugin_settings, self._instance_settings)
00127                 self._monitor.shutdown()
00128                 self._monitor.close()
00129                 self._graveyard.append(self._monitor)
00130                 self._monitor = None
00131 
00132     def shutdown_widget(self):
00133         if self._monitor:
00134             self._monitor.shutdown()
00135         self._diagnostics_toplevel_state_sub.unregister()
00136 
00137     def save_settings(self, plugin_settings, instance_settings):
00138         if self._monitor_shown:
00139             self._monitor.save_settings(self._plugin_settings, self._instance_settings)
00140 
00141     def restore_settings(self, plugin_settings, instance_settings):
00142         self._plugin_settings = plugin_settings
00143         self._instance_settings = instance_settings