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
00034
00035 import os
00036
00037 import roslib;roslib.load_manifest('rqt_robot_monitor')
00038 import rospy
00039
00040 from python_qt_binding.QtGui import QWidget, QVBoxLayout, QTextEdit, QPushButton
00041 from python_qt_binding.QtCore import Signal, Qt
00042
00043 from .abst_status_widget import AbstractStatusWidget
00044 from .time_pane import TimelinePane
00045 from .util_robot_monitor import Util
00046
00047 class InspectorWindow(AbstractStatusWidget):
00048 _sig_write = Signal(str, str)
00049 _sig_newline = Signal()
00050 _sig_close_window = Signal()
00051 _sig_clear = Signal()
00052
00053 def __init__(self, status, close_callback):
00054 """
00055
00056 @todo: UI construction that currently is done in this method,
00057 needs to be done in .ui file.
00058
00059 @param status: DiagnosticStatus
00060 @param close_callback: When the instance of this class (InspectorWindow)
00061 terminates, this callback gets called.
00062 """
00063
00064 super(InspectorWindow, self).__init__()
00065 self.status = status
00066 self._close_callback = close_callback
00067 self.setWindowTitle(status.name)
00068 self.paused = False
00069
00070 self.layout_vertical = QVBoxLayout(self)
00071
00072 self.disp = QTextEdit(self)
00073 self.snapshot = QPushButton("Snapshot")
00074
00075 self.timeline_pane = TimelinePane(self, Util._SECONDS_TIMELINE,
00076 self._cb,
00077 self.get_color_for_value
00078 )
00079
00080 self.layout_vertical.addWidget(self.disp, 1)
00081 self.layout_vertical.addWidget(self.timeline_pane, 0)
00082 self.layout_vertical.addWidget(self.snapshot)
00083
00084 self.snaps = []
00085 self.snapshot.clicked.connect(self._take_snapshot)
00086
00087 self._sig_write.connect(self._write_key_val)
00088 self._sig_newline.connect(lambda: self.disp.insertPlainText('\n'))
00089 self._sig_clear.connect(lambda: self.disp.clear())
00090 self._sig_close_window.connect(self._close_callback)
00091
00092 self.setLayout(self.layout_vertical)
00093 self.setGeometry(0, 0, 400, 600)
00094 self.show()
00095 self.update_status_display(status)
00096
00097 def get_color_for_value(self, queue_diagnostic, color_index):
00098 rospy.logdebug('InspectorWindow get_color_for_value ' +
00099 'queue_diagnostic=%d, color_index=%d',
00100 len(queue_diagnostic), color_index)
00101 lv_index = queue_diagnostic[color_index - 1].level
00102 return Util._COLOR_DICT[lv_index]
00103
00104 '''
00105 Delegated from super class.
00106 @author: Isaac Saito
00107 '''
00108 def closeEvent(self, event):
00109
00110 self._sig_close_window.emit()
00111 self.close()
00112
00113 def _write_key_val(self, k, v):
00114 self.disp.setFontWeight(75)
00115 self.disp.insertPlainText(k)
00116 self.disp.insertPlainText(': ')
00117
00118 self.disp.setFontWeight(50)
00119 self.disp.insertPlainText(v)
00120 self.disp.insertPlainText('\n')
00121
00122 def pause(self, msg):
00123 """
00124 @todo: Create a superclass for this and RobotMonitorWidget that has
00125 pause func.
00126 """
00127
00128 rospy.logdebug('InspectorWin pause PAUSED')
00129 self.paused = True
00130 self.update_status_display(msg);
00131
00132 def unpause(self, msg):
00133 rospy.logdebug('InspectorWin pause UN-PAUSED')
00134 self.paused = False
00135
00136
00137 def _cb(self, msg, is_forced = False):
00138 """
00139
00140 @param status: DiagnosticsStatus
00141
00142 Overriden
00143 """
00144
00145 if not self.paused:
00146
00147
00148 self.update_status_display(msg)
00149 rospy.logdebug('InspectorWin _cb len of queue=%d self.paused=%s',
00150 len(self.timeline_pane._queue_diagnostic), self.paused)
00151
00152 else:
00153 if is_forced:
00154 self.update_status_display(msg, True)
00155 rospy.logdebug('@@@InspectorWin _cb PAUSED window updated')
00156 else:
00157 rospy.logdebug('@@@InspectorWin _cb PAUSED not updated')
00158
00159 def update_status_display(self, status, is_forced = False):
00160 """
00161 @param status: DiagnosticsStatus
00162 """
00163
00164 if not self.paused or (self.paused and is_forced):
00165 self.timeline_pane.new_diagnostic(status)
00166
00167 rospy.logdebug('InspectorWin update_status_display 1')
00168
00169 self.status = status
00170 self._sig_clear.emit()
00171 self._sig_write.emit("Full Name", status.name)
00172 self._sig_write.emit("Component", status.name.split('/')[-1])
00173 self._sig_write.emit("Hardware ID", status.hardware_id)
00174 self._sig_write.emit("Level", str(status.level))
00175 self._sig_write.emit("Message", status.message)
00176 self._sig_newline.emit()
00177
00178 for v in status.values:
00179 self._sig_write.emit(v.key, v.value)
00180
00181 def _take_snapshot(self):
00182 snap = Snapshot(self.status)
00183 self.snaps.append(snap)
00184
00185 def enable(self):
00186
00187
00188 self.setEnabled(True)
00189 self.timeline_pane.enable()
00190 self.timeline_pane.pause_button.setDown(False)
00191
00192 def disable(self):
00193 """Supposed to be called upon pausing."""
00194
00195
00196 self.setEnable(False)
00197 self.timeline_pane.disable()
00198 self.pause_button.Disable()
00199 self.unpause()
00200 self.timeline_pane.pause_button.setDown(True)
00201
00202 class Snapshot(QTextEdit):
00203 """Display a single static status message. Helps facilitate copy/paste"""
00204
00205 def __init__(self, status):
00206 super(Snapshot, self).__init__()
00207
00208 self._write("Full Name", status.name)
00209 self._write("Component", status.name.split('/')[-1])
00210 self._write("Hardware ID", status.hardware_id)
00211 self._write("Level", status.level)
00212 self._write("Message", status.message)
00213 self.insertPlainText('\n')
00214
00215 for value in status.values:
00216 self._write(value.key, value.value)
00217
00218 self.setGeometry(0, 0, 300, 400)
00219 self.show()
00220
00221 def _write(self, k, v):
00222 self.setFontWeight(75)
00223 self.insertPlainText(str(k))
00224 self.insertPlainText(': ')
00225
00226 self.setFontWeight(50)
00227 self.insertPlainText(str(v))
00228 self.insertPlainText('\n')