diagnostics.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2015 Airbus
00004 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00005 #
00006 # Licensed under the Apache License, Version 2.0 (the "License");
00007 # you may not use this file except in compliance with the License.
00008 # You may obtain a copy of the License at
00009 #
00010 #   http://www.apache.org/licenses/LICENSE-2.0
00011 #
00012 # Unless required by applicable law or agreed to in writing, software
00013 # distributed under the License is distributed on an "AS IS" BASIS,
00014 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00015 # See the License for the specific language governing permissions and
00016 # limitations under the License.
00017 import rospy
00018 import os
00019 import sys
00020 import threading
00021 from roslib.packages import get_pkg_dir
00022 from python_qt_binding.QtGui import *
00023 from python_qt_binding.QtCore import *
00024 from python_qt_binding import loadUi
00025 from airbus_cobot_gui.res import R
00026 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus
00027 from airbus_pyqt_extend.QtAgiGui import QAgiPopup
00028 from rqt_robot_monitor.status_item import StatusItem
00029 import rqt_robot_monitor.util_robot_monitor as util
00030 
00031 ## @class DiagnosticsStatus
00032 ## @brief Class for difine different control status.
00033 
00034     
00035 #OK = 0
00036 #WARN = 1
00037 #ERROR = 2
00038 #STALE = 3
00039 
00040 
00041 class DiagnosticsWidget(QPushButton):
00042     
00043     DIAGNOSTICS_TOPLEVEL_TOPIC_NAME = rospy.get_param('diagnostics_toplevel_topic_name','/diagnostics_toplevel_state')
00044     state = "status_stale"
00045     msg = "No diagnostic messages received"
00046 
00047     def __init__(self, context):
00048         """! The constructor."""
00049         QPushButton.__init__(self)
00050         self._context = context
00051 
00052         # Diagnostics top level: update the color of the button depending on the current diagnostics toplevel message
00053         self.connect(self, SIGNAL("stateChanged"), self.update_state)
00054         self.emit(SIGNAL('stateChanged'), self.state, self.msg)
00055         self._diagnostics_toplevel_state_sub = rospy.Subscriber(self.DIAGNOSTICS_TOPLEVEL_TOPIC_NAME , DiagnosticStatus, self.toplevel_state_callback)
00056 
00057         # Diagnostics: when button pressed open a new window with a detailed list of components and diagnostic messages
00058         self.connect(self,SIGNAL('clicked(bool)'),self._trigger_button)
00059 
00060     def update_state(self, state, msg):
00061         self.setIcon(R.getIconById(state))
00062         self.setIconSize(QSize(40,40))
00063         self.setToolTip(msg)
00064 
00065     def toplevel_state_callback(self, msg):
00066         self.state = msg.level
00067         if msg.level == 0:
00068           self.state= "status_ok"
00069           self.msg = "OK"
00070         if msg.level == 1 :
00071           self.state= "status_warning"
00072           self.msg = "WARNING"
00073         if msg.level == 2 :
00074           self.state= "status_error"
00075           self.msg = "ERROR"
00076         if msg.level == 3 :
00077           self.state= "status_stale"
00078           self.msg = "STALE"
00079         self.emit(SIGNAL('stateChanged'), self.state, self.msg)
00080 
00081     def _trigger_button(self, checked):
00082         popup = DiagnosticsPopup(self, self._context)
00083         popup.show_()
00084 
00085 class DiagnosticsPopup(QAgiPopup):
00086 
00087     def __init__(self, parent, context):
00088         """! The constructor."""
00089         QAgiPopup.__init__(self, parent)
00090 
00091         self._context = context
00092         self._parent = parent
00093         self.setRelativePosition(QAgiPopup.TopRight, QAgiPopup.BottomRight)
00094         loadUi(R.layouts.diagnostics_popup, self)
00095         self._inspectors = {}
00096         self._current_msg = None
00097         palette = self.tree_all_devices.palette()
00098         self._original_base_color = palette.base().color()
00099         self._original_alt_base_color = palette.alternateBase().color()
00100         self._tree = StatusItem(self.tree_all_devices.invisibleRootItem())
00101         self.adjustSize()
00102 
00103         # Diagnostics subscriber
00104         DIAGNOSTICS_TOPIC_NAME = rospy.get_param('diagnostics_topic_name','/diagnostics_agg')
00105         self.connect(self,SIGNAL("UpdateDiagnostics"), self.update_diag)
00106         self._diagnostics_agg_sub = rospy.Subscriber(DIAGNOSTICS_TOPIC_NAME, DiagnosticArray, self.message_cb)
00107 
00108     def update_diag(self):
00109         #update the tree
00110         self._tree.prune()
00111         self.tree_all_devices.resizeColumnToContents(0)
00112         self.adjustSize()
00113 
00114     def message_cb(self,msg):
00115         """ DiagnosticArray message callback """
00116         for status in msg.status:
00117             path = status.name.split('/')
00118             if path[0] == '':
00119                 path = path[1:]
00120             tmp_tree = self._tree
00121             for p in path:
00122                 tmp_tree = tmp_tree[p]
00123             tmp_tree.update(status, util.get_resource_name(status.name))
00124         self.emit(SIGNAL('UpdateDiagnostics'))
00125 
00126 if __name__ == "__main__":
00127     from airbus_cobot_gui.context import Context
00128     app = QApplication(sys.argv)
00129     main = QMainWindow()
00130     main.setCentralWidget(TranslatorUi(Context(main)))
00131     main.show()
00132     app.exec_()
00133     
00134 #End of file


airbus_cobot_gui
Author(s): Martin Matignon
autogenerated on Thu Jun 6 2019 17:59:19