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
00034
00035 from python_qt_binding.QtCore import Qt, Signal, Slot
00036 from python_qt_binding.QtWidgets import QPushButton, QTextEdit, QVBoxLayout, QWidget
00037 import rospy
00038
00039 from rqt_robot_monitor.status_snapshot import StatusSnapshot, level_to_text
00040 from rqt_robot_monitor.timeline_pane import TimelinePane
00041 import rqt_robot_monitor.util_robot_monitor as util
00042
00043 from diagnostic_msgs.msg import DiagnosticArray
00044
00045
00046 class InspectorWindow(QWidget):
00047 closed = Signal(str)
00048 _message_updated = Signal(dict)
00049 _queue_updated = Signal()
00050
00051 def __init__(self, parent, name, timeline):
00052 """
00053 :param name: Name of inspecting diagnostic status
00054 :param timeline: Timeline object from which a status is fetched
00055 """
00056
00057
00058 super(InspectorWindow, self).__init__(parent=parent)
00059 self.setWindowTitle(name)
00060 self._name = name
00061
00062 self.layout_vertical = QVBoxLayout(self)
00063
00064 self.disp = StatusSnapshot(parent=self)
00065
00066 self.layout_vertical.addWidget(self.disp, 1)
00067
00068 self._message_updated_processing = False
00069 self._queue_updated_processing = False
00070
00071 self.timeline = timeline
00072 self.timeline.message_updated.connect(
00073 self.message_updated, Qt.DirectConnection)
00074 self.timeline.queue_updated.connect(
00075 self.queue_updated, Qt.DirectConnection)
00076 self._message_updated.connect(
00077 self._signal_message_updated, Qt.QueuedConnection)
00078 self._queue_updated.connect(
00079 self._signal_queue_updated, Qt.QueuedConnection)
00080
00081 self.timeline_pane = TimelinePane(self, self.timeline.paused)
00082 self.timeline_pane.pause_changed.connect(self.timeline.set_paused)
00083 self.timeline_pane.position_changed.connect(self.timeline.set_position)
00084 self.timeline.pause_changed.connect(self.timeline_pane.set_paused)
00085 self.timeline.position_changed.connect(self.timeline_pane.set_position)
00086 self.layout_vertical.addWidget(self.timeline_pane, 0)
00087
00088 self.snapshot = QPushButton("Snapshot")
00089 self.snapshot.clicked.connect(self._take_snapshot)
00090 self.layout_vertical.addWidget(self.snapshot)
00091
00092 self.snaps = []
00093
00094 self.setLayout(self.layout_vertical)
00095
00096 self.resize(400, 600)
00097
00098 def closeEvent(self, event):
00099 """ called when this window is closed
00100
00101 Calls close on all snapshots, and emits the closed signal
00102 """
00103
00104
00105
00106 for snap in self.snaps:
00107 snap.close()
00108 self.closed.emit(self._name)
00109
00110 @Slot()
00111 def queue_updated(self):
00112 '''
00113 This method just calls _signal_queue_updated in 'best effort' manner.
00114 This method should be called by signal with DirectConnection.
00115 '''
00116 if self._queue_updated_processing:
00117 return
00118 self._queue_updated_processing = True
00119 self._queue_updated.emit()
00120
00121 @Slot()
00122 def _signal_queue_updated(self):
00123
00124
00125 status = self.timeline.get_all_status_by_name(self._name)
00126 self.timeline_pane.set_levels([s.level for s in status])
00127 self.timeline_pane.set_position(self.timeline.position)
00128 self.timeline_pane.redraw.emit()
00129 self._queue_updated_processing = False
00130
00131 @Slot(dict)
00132 def message_updated(self, status):
00133 '''
00134 This method just calls _signal_message_updated in 'best effort' manner.
00135 This method should be called by signal with DirectConnection.
00136 '''
00137 if self._message_updated_processing:
00138 return
00139 self._message_updated_processing = True
00140 self._message_updated.emit(status)
00141
00142 @Slot(dict)
00143 def _signal_message_updated(self, status):
00144 rospy.logdebug('InspectorWin message_updated')
00145
00146 status = status[self._name]
00147 scroll_value = self.disp.verticalScrollBar().value()
00148
00149 self.status = status
00150 self.disp.write_status.emit(status)
00151
00152 if self.disp.verticalScrollBar().maximum() < scroll_value:
00153 scroll_value = self.disp.verticalScrollBar().maximum()
00154 self.disp.verticalScrollBar().setValue(scroll_value)
00155 self._message_updated_processing = False
00156
00157 def _take_snapshot(self):
00158 snap = StatusSnapshot(status=self.status)
00159 self.snaps.append(snap)
rqt_robot_monitor
Author(s): Austin Hendrix, Isaac Saito, Ze'ev Klapow, Kevin Watts, Josh Faust
autogenerated on Thu May 16 2019 03:10:09