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 Signal, Slot
00036 from python_qt_binding.QtWidgets import QPushButton, QTextEdit, QVBoxLayout, QWidget
00037 import rospy
00038
00039 from .status_snapshot import StatusSnapshot, level_to_text
00040 from .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
00049 def __init__(self, parent, name, status, timeline):
00050 """
00051 :type status: DiagnosticStatus
00052 :param close_callback: When the instance of this class
00053 (InspectorWindow) terminates, this callback gets
00054 called.
00055 """
00056
00057
00058
00059 super(InspectorWindow, self).__init__()
00060 self.setWindowTitle(name)
00061 self._name = name
00062
00063 self.layout_vertical = QVBoxLayout(self)
00064
00065 self.disp = StatusSnapshot(parent=self)
00066
00067 self.layout_vertical.addWidget(self.disp, 1)
00068
00069 if timeline is not None:
00070 self.timeline_pane = TimelinePane(self)
00071 self.timeline_pane.set_timeline(timeline, name)
00072 self.layout_vertical.addWidget(self.timeline_pane, 0)
00073
00074 self.snapshot = QPushButton("Snapshot")
00075 self.snapshot.clicked.connect(self._take_snapshot)
00076 self.layout_vertical.addWidget(self.snapshot)
00077
00078 self.snaps = []
00079
00080 self.setLayout(self.layout_vertical)
00081
00082 self.resize(400, 600)
00083 self.show()
00084 self.message_updated(status)
00085
00086 def closeEvent(self, event):
00087 """ called when this window is closed
00088
00089 Calls close on all snapshots, and emits the closed signal
00090 """
00091
00092
00093
00094 for snap in self.snaps:
00095 snap.close()
00096 self.closed.emit(self._name)
00097
00098 @Slot(DiagnosticArray)
00099 def message_updated(self, msg):
00100 status = util.get_status_by_name(msg, self._name)
00101 scroll_value = self.disp.verticalScrollBar().value()
00102
00103 rospy.logdebug('InspectorWin message_updated')
00104
00105 self.status = status
00106 self.disp.write_status.emit(status)
00107
00108 if self.disp.verticalScrollBar().maximum() < scroll_value:
00109 scroll_value = self.disp.verticalScrollBar().maximum()
00110 self.disp.verticalScrollBar().setValue(scroll_value)
00111
00112 def _take_snapshot(self):
00113 snap = StatusSnapshot(status=self.status)
00114 self.snaps.append(snap)
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