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 import roslib
00019 import rospy
00020
00021 from cob_msgs.msg import DashboardState
00022
00023 from rqt_robot_dashboard.dashboard import Dashboard
00024 from rqt_robot_dashboard.widgets import MonitorDashWidget, ConsoleDashWidget
00025
00026 from python_qt_binding.QtCore import QSize
00027 try:
00028 from python_qt_binding.QtWidgets import QMessageBox
00029 except ImportError:
00030 from python_qt_binding.QtGui import QMessageBox
00031
00032 from cob_battery import COBBattery
00033 from cob_runstops import COBRunstops
00034
00035
00036 class CobDashboard(Dashboard):
00037 """
00038 Dashboard for Care-O-bots
00039
00040 :param context: the plugin context
00041 :type context: qt_gui.plugin.Plugin
00042 """
00043 def setup(self, context):
00044 self.name = 'CobDashboard'
00045 self.max_icon_size = QSize(50, 30)
00046 self.message = None
00047
00048 self._dashboard_message = None
00049 self._last_dashboard_message_time = 0.0
00050
00051 self._raw_byte = None
00052 self.digital_outs = [0, 0, 0]
00053
00054 self._console = ConsoleDashWidget(self.context, minimal=False)
00055 self._monitor = MonitorDashWidget(self.context)
00056 self._runstop = COBRunstops('RunStops')
00057 self._battery = COBBattery(self.context)
00058
00059 self._dashboard_agg_sub = rospy.Subscriber("/dashboard_agg", DashboardState, self.db_agg_cb)
00060
00061 def get_widgets(self):
00062 return [[self._monitor, self._console], [self._runstop], [self._battery]]
00063
00064 def db_agg_cb(self, msg):
00065 self._last_dashboard_message_time = rospy.get_time()
00066 self._battery.set_power_state(msg.power_state)
00067
00068 if(msg.emergency_stop_state.emergency_state == 0):
00069 self._runstop.set_ok()
00070 self._runstop.setToolTip(self.tr("Button stop: OK\nScanner stop: OK"))
00071 else:
00072 if msg.emergency_stop_state.emergency_button_stop:
00073 self._runstop.set_button_stop()
00074 elif msg.emergency_stop_state.scanner_stop:
00075 self._runstop.set_scanner_stop()
00076 else:
00077 rospy.error("reason for emergency stop not known")
00078 self._runstop.setToolTip(self.tr("Button stop: %s\nScanner stop: %s" %(str(msg.emergency_stop_state.emergency_button_stop), str(msg.emergency_stop_state.scanner_stop))))
00079
00080 def shutdown_dashboard(self):
00081 self._dashboard_agg_sub.unregister()
00082
00083 def save_settings(self, plugin_settings, instance_settings):
00084 self._console.save_settings(plugin_settings, instance_settings)
00085 self._monitor.save_settings(plugin_settings, instance_settings)
00086
00087 def restore_settings(self, plugin_settings, instance_settings):
00088 self._console.restore_settings(plugin_settings, instance_settings)
00089 self._monitor.restore_settings(plugin_settings, instance_settings)