class CobDashboard(Dashboard): """ Dashboard for Care-O-bots :param context: the plugin context :type context: qt_gui.plugin.Plugin """ def setup(self, context): self.name = 'CobDashboard' self.max_icon_size = QSize(50, 30) self.message = None self._dashboard_message = None self._last_dashboard_message_time = 0.0 self._raw_byte = None self.digital_outs = [0, 0, 0] self._console = ConsoleDashWidget(self.context, minimal=False) self._monitor = MonitorDashWidget(self.context) self._runstop = COBRunstops('RunStops') self._battery = COBBattery(self.context) self._dashboard_agg_sub = rospy.Subscriber("/dashboard_agg", DashboardState, self.db_agg_cb) def get_widgets(self): return [[self._monitor, self._console], [self._runstop], [self._battery]] def db_agg_cb(self, msg): self._last_dashboard_message_time = rospy.get_time() self._battery.set_power_state(msg.power_state) if(msg.emergency_stop_state.emergency_state == 0): self._runstop.set_ok() self._runstop.setToolTip(self.tr("Button stop: OK\nScanner stop: OK")) else: if msg.emergency_stop_state.emergency_button_stop: self._runstop.set_button_stop() elif msg.emergency_stop_state.scanner_stop: self._runstop.set_scanner_stop() else: rospy.logerr("reason for emergency stop not known") 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)))) def shutdown_dashboard(self): self._dashboard_agg_sub.unregister() def save_settings(self, plugin_settings, instance_settings): self._console.save_settings(plugin_settings, instance_settings) self._monitor.save_settings(plugin_settings, instance_settings) def restore_settings(self, plugin_settings, instance_settings): self._console.restore_settings(plugin_settings, instance_settings) self._monitor.restore_settings(plugin_settings, instance_settings)
class NaoDCMDashboard(Dashboard): def setup(self, context): self._dashboard_message = None self._last_dashboard_message_time = 0.0 self.name = "NaoDCM Dashboard" rospy.sleep(0.5) self.motor_bat = NaoDCMBatteryWidget("Battery") self.console = ConsoleDashWidget(self.context) self.monitor = MonitorDashWidget(self.context) self.monitor._show_monitor() self.nav = NavViewDashWidget(self.context) self.cam = CameraViewDashWidget(self.context, 'nao_dcm/CameraTop/image_raw', 'CameraTop') self.cam._show_cam_view() self.camBot = CameraViewDashWidget(self.context, 'nao_dcm/CameraBottom/image_raw', 'CameraBottom') self.camBot._show_cam_view() self.stiff = NaoDCMStiffnessWidget("Stiffness") # This is what gets dashboard_callback going eagerly self._dashboard_agg_sub = rospy.Subscriber('diagnostics_agg', diagnostic_msgs.msg.DiagnosticArray, self.dashboard_callback) def get_widgets(self): return [[self.monitor, self.console],[self.motor_bat],[self.nav],[self.cam, self.camBot],[self.stiff]] def dashboard_callback(self, msg): self._dashboard_message = msg self._last_dashboard_message_time = rospy.get_time() battery_status = {} # Used to store Battery status info for status in msg.status: if status.name == "/Nao/Battery/Battery": for value in status.values: battery_status[value.key]=value.value # If battery diagnostics were found, calculate percentages and stuff if (battery_status): self.motor_bat.set_power_state(battery_status['Battery Charge']) def shutdown_dashboard(self): self._dashboard_agg_sub.unregister() def save_settings(self, plugin_settings, instance_settings): self.console.save_settings(plugin_settings, instance_settings) self.monitor.save_settings(plugin_settings, instance_settings) def restore_settings(self, plugin_settings, instance_settings): self.console.restore_settings(plugin_settings, instance_settings) self.monitor.restore_settings(plugin_settings, instance_settings)
class MovoDashboard(Dashboard): def setup(self, context): super(Dashboard, self).__init__(context) self.name = 'Movo Dashboard' self.message = None self._console = ConsoleDashWidget(self.context, minimal=False) self._monitor = MonitorDashWidget(self.context) self._bat = BatteryWidget("Battery Power") self._dashboard_message = None self._last_dashboard_message_time = 0.0 self._bat_sub = rospy.Subscriber('/movo/feedback/battery', Battery, self._battery_callback) self._last_dashboard_message_time = rospy.get_time() self._system_charging = False def get_widgets(self): return [[self._console, self._monitor], [self._bat]] def _battery_callback(self, msg): self._bat.update_perc(msg.battery_soc) self._bat.update_time(msg.battery_soc) if (0x1000 == (msg.battery_status & 0x1000)): self._bat.set_charging(True) self._system_charging = True else: self._bat.set_charging(False) self._system_charging = False def shutdown_dashboard(self): self._bat_sub.unregister() def save_settings(self, plugin_settings, instance_settings): self._console.save_settings(plugin_settings, instance_settings) self._monitor.save_settings(plugin_settings, instance_settings) def restore_settings(self, plugin_settings, instance_settings): self._console.restore_settings(plugin_settings, instance_settings) self._monitor.restore_settings(plugin_settings, instance_settings)
class VectorDashboard(Dashboard): def setup(self, context): super(Dashboard, self).__init__(context) self.name = 'Vector Dashboard' self.message = None self._console = ConsoleDashWidget(self.context, minimal=False) self._monitor = MonitorDashWidget(self.context) self._bat = BatteryWidget("Battery Power") self._dashboard_message = None self._last_dashboard_message_time = 0.0 self._bat_sub = rospy.Subscriber('/vector/feedback/battery', Battery, self._battery_callback) self._last_dashboard_message_time = rospy.get_time() self._system_charging = False def get_widgets(self): return [[self._console, self._monitor], [self._bat]] def _battery_callback(self,msg): self._bat.update_perc(msg.battery_soc) self._bat.update_time(msg.battery_soc) if (0x1000 == (msg.battery_status & 0x1000)): self._bat.set_charging(True) self._system_charging = True else: self._bat.set_charging(False) self._system_charging = False def shutdown_dashboard(self): self._bat_sub.unregister() def save_settings(self, plugin_settings, instance_settings): self._console.save_settings(plugin_settings, instance_settings) self._monitor.save_settings(plugin_settings, instance_settings) def restore_settings(self, plugin_settings, instance_settings): self._console.restore_settings(plugin_settings, instance_settings) self._monitor.restore_settings(plugin_settings, instance_settings)
class CobDashboard(Dashboard): """ Dashboard for Care-O-bots :param context: the plugin context :type context: qt_gui.plugin.Plugin """ def setup(self, context): self.name = 'CobDashboard' self.max_icon_size = QSize(50, 30) self.message = None self._dashboard_message = None self._last_dashboard_message_time = 0.0 self._raw_byte = None self.digital_outs = [0, 0, 0] self._console = ConsoleDashWidget(self.context, minimal=False) self._monitor = MonitorDashWidget(self.context) self._runstop = PR2Runstops('RunStops') self._batteries = [COBBattery(self.context)] self._dashboard_agg_sub = rospy.Subscriber('dashboard_agg', DashboardState, self.dashboard_callback) def get_widgets(self): return [[self._monitor, self._console], [self._runstop], self._batteries] def dashboard_callback(self, msg): """ callback to process dashboard_agg messages :param msg: dashboard_agg DashboardState message :type msg: pr2_msgs.msg.DashboardState """ self._dashboard_message = msg self._last_dashboard_message_time = rospy.get_time() if (msg.power_state_valid): self._batteries[0].set_power_state(msg.power_state) else: self._batteries[0].set_stale() if (msg.power_board_state_valid): if msg.power_board_state.run_stop: self._runstop.set_ok() self._runstop.setToolTip( self.tr("Physical Runstop: OK\nWireless Runstop: OK")) elif msg.power_board_state.wireless_stop: self._runstop.set_physical_engaged() self._runstop.setToolTip( self.tr("Physical Runstop: Pressed\nWireless Runstop: OK")) if not msg.power_board_state.wireless_stop: self._runstop.set_wireless_engaged() self._runstop.setToolTip( self. tr("Physical Runstop: Unknown\nWireless Runstop: Pressed")) else: self._runstop.set_stale() self._runstop.setToolTip( self.tr("Physical Runstop: Stale\nWireless Runstop: Stale")) def shutdown_dashboard(self): self._dashboard_agg_sub.unregister() def save_settings(self, plugin_settings, instance_settings): self._console.save_settings(plugin_settings, instance_settings) self._monitor.save_settings(plugin_settings, instance_settings) def restore_settings(self, plugin_settings, instance_settings): self._console.restore_settings(plugin_settings, instance_settings) self._monitor.restore_settings(plugin_settings, instance_settings)
class CobDashboard(Dashboard): """ Dashboard for Care-O-bots :param context: the plugin context :type context: qt_gui.plugin.Plugin """ def setup(self, context): self.name = 'CobDashboard' self.max_icon_size = QSize(50, 30) self.message = None self._dashboard_message = None self._last_dashboard_message_time = 0.0 self._raw_byte = None self.digital_outs = [0, 0, 0] self._console = ConsoleDashWidget(self.context, minimal=False) self._monitor = MonitorDashWidget(self.context) self._runstop = COBRunstops('RunStops') self._batteries = [COBBattery(self.context)] self._dashboard_agg_sub = rospy.Subscriber("/dashboard_agg", DashboardState, self.db_agg_cb) self.em_sub = rospy.Subscriber("/emergency_stop_state", EmergencyStopState, self.emcb) self._powerstate_sub = rospy.Subscriber('/power_state', PowerState, self.dashboard_callback) def get_widgets(self): return [[self._monitor, self._console], [self._runstop], self._batteries] def db_agg_cb(self, msg): pass def emcb(self, msg): self._last_dashboard_message_time = rospy.get_time() if (not msg.emergency_button_stop): self._runstop.set_button_engaged() self._runstop.setToolTip(self.tr("Button Runstop: Pressed")) if (not msg.scanner_stop): self._runstop.set_scanner_engaged() self._runstop.setToolTip( self.tr("Button Runstop: Unknown\nScanner Runstop: Active")) if (msg.emergency_button_stop and msg.scanner_stop): self._runstop.set_ok() self._runstop.setToolTip( self.tr("Button Runstop: OK\nScanner Runstop: OK")) def dashboard_callback(self, msg): self._last_dashboard_message_time = rospy.get_time() self._batteries[0].set_power_state(msg) def shutdown_dashboard(self): self._dashboard_agg_sub.unregister() def save_settings(self, plugin_settings, instance_settings): self._console.save_settings(plugin_settings, instance_settings) self._monitor.save_settings(plugin_settings, instance_settings) def restore_settings(self, plugin_settings, instance_settings): self._console.restore_settings(plugin_settings, instance_settings) self._monitor.restore_settings(plugin_settings, instance_settings)