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 import roslib;roslib.load_manifest('rqt_pr2_dashboard')
00034 import rospy
00035
00036 import argparse
00037 import diagnostic_msgs
00038
00039 from pr2_msgs.msg import PowerState, PowerBoardState, DashboardState
00040 from pr2_power_board.srv import PowerBoardCommand, PowerBoardCommandRequest
00041 import std_msgs.msg
00042 import std_srvs.srv
00043
00044 from rqt_robot_dashboard.dashboard import Dashboard
00045 from rqt_robot_dashboard.widgets import MonitorDashWidget, ConsoleDashWidget
00046
00047 from python_qt_binding.QtCore import QSize
00048 from python_qt_binding.QtGui import QMessageBox
00049
00050 from .pr2_breaker import PR2BreakerButton
00051 from .pr2_battery import PR2Battery
00052 from .pr2_motors import PR2Motors
00053 from .pr2_runstop import PR2Runstops
00054
00055
00056 class PR2Dashboard(Dashboard):
00057 """
00058 Dashboard for PR2s
00059
00060 :param context: the plugin context
00061 :type context: qt_gui.plugin.Plugin
00062 """
00063 def setup(self, context):
00064 self.name = 'PR2 Dashboard'
00065 self.max_icon_size = QSize(50, 30)
00066 self.message = None
00067
00068 self._dashboard_message = None
00069 self._last_dashboard_message_time = 0.0
00070
00071 self._raw_byte = None
00072 self.digital_outs = [0,0,0]
00073
00074 self._console = ConsoleDashWidget(self.context, minimal=False)
00075 self._monitor = MonitorDashWidget(self.context)
00076 self._motors = PR2Motors(self.on_reset_motors, self.on_halt_motors)
00077 self._breakers = [PR2BreakerButton('Left Arm', 0),
00078 PR2BreakerButton('Base', 1),
00079 PR2BreakerButton('Right Arm', 2)]
00080
00081 self._runstop = PR2Runstops('RunStops')
00082 self._batteries = [PR2Battery(self.context)]
00083
00084 self._dashboard_agg_sub = rospy.Subscriber('dashboard_agg', DashboardState, self.dashboard_callback)
00085
00086 def get_widgets(self):
00087 return [[self._monitor, self._console , self._motors], self._breakers, [self._runstop], self._batteries]
00088
00089 def dashboard_callback(self, msg):
00090 """
00091 callback to process dashboard_agg messages
00092
00093 :param msg: dashboard_agg DashboardState message
00094 :type msg: pr2_msgs.msg.DashboardState
00095 """
00096 self._dashboard_message = msg
00097 self._last_dashboard_message_time = rospy.get_time()
00098
00099 if (msg.motors_halted_valid):
00100 if (not msg.motors_halted.data):
00101 self._motors.set_ok()
00102 self._motors.setToolTip(self.tr("Motors: Running"))
00103 else:
00104 self._motors.set_error()
00105 self._motors.setToolTip(self.tr("Motors: Halted"))
00106 else:
00107 self._motors.set_stale()
00108 self._motors.setToolTip(self.tr("Motors: Stale"))
00109
00110 if (msg.power_state_valid):
00111 self._batteries[0].set_power_state(msg.power_state)
00112 else:
00113 self._batteries[0].set_stale()
00114
00115 if (msg.power_board_state_valid):
00116 [breaker.set_power_board_state_msg(msg.power_board_state) for breaker in self._breakers]
00117 if msg.power_board_state.run_stop:
00118 self._runstop.set_ok()
00119 self._runstop.setToolTip(self.tr("Physical Runstop: OK\nWireless Runstop: OK"))
00120 elif msg.power_board_state.wireless_stop:
00121 self._runstop.set_physical_engaged()
00122 self._runstop.setToolTip(self.tr("Physical Runstop: Pressed\nWireless Runstop: OK"))
00123 if not msg.power_board_state.wireless_stop:
00124 self._runstop.set_wireless_engaged()
00125 self._runstop.setToolTip(self.tr("Physical Runstop: Unknown\nWireless Runstop: Pressed"))
00126 else:
00127 [breaker.reset() for breaker in self._breakers]
00128 self._runstop.set_stale()
00129 self._runstop.setToolTip(self.tr("Physical Runstop: Stale\nWireless Runstop: Stale"))
00130
00131 def on_reset_motors(self):
00132
00133 if (self._dashboard_message is not None and self._dashboard_message.power_board_state_valid):
00134 all_breakers_enabled = reduce(lambda x,y: x and y, [state == PowerBoardState.STATE_ON for state in self._dashboard_message.power_board_state.circuit_state])
00135 if (not all_breakers_enabled):
00136 if(QMessageBox.question(self._breakers[0], self.tr('Enable Breakers?'), self.tr("Resetting the motors may not work because not all breakers are enabled. Enable all the breakers first?"),QMessageBox.Yes|QMessageBox.No,QMessageBox.Yes) == QMessageBox.Yes):
00137 [breaker.set_enable() for breaker in self._breakers]
00138 reset = rospy.ServiceProxy("pr2_etherCAT/reset_motors", std_srvs.srv.Empty)
00139 try:
00140 reset()
00141 except rospy.ServiceException, e:
00142 QMessageBox.critical(self._breakers[0], "Error", "Failed to reset the motors: service call failed with error: %s"%(e))
00143
00144
00145 def on_halt_motors(self):
00146 halt = rospy.ServiceProxy("pr2_etherCAT/halt_motors", std_srvs.srv.Empty)
00147 try:
00148 halt()
00149 except rospy.ServiceException, e:
00150 QMessageBox.critical(self._motors, "Error", "Failed to halt the motors: service call failed with error: %s"%(e))
00151
00152 def shutdown_dashboard(self):
00153 self._dashboard_agg_sub.unregister()
00154
00155 def save_settings(self, plugin_settings, instance_settings):
00156 self._console.save_settings(plugin_settings, instance_settings)
00157 self._monitor.save_settings(plugin_settings, instance_settings)
00158
00159 def restore_settings(self, plugin_settings, instance_settings):
00160 self._console.restore_settings(plugin_settings, instance_settings)
00161 self._monitor.restore_settings(plugin_settings, instance_settings)