35 roslib.load_manifest(
'rqt_pr2_dashboard')
38 from pr2_msgs.msg
import PowerBoardState, DashboardState
45 from python_qt_binding.QtCore
import QSize
47 from python_qt_binding.QtGui
import QMessageBox
49 from python_qt_binding.QtWidgets
import QMessageBox
51 from .pr2_breaker
import PR2BreakerButton
52 from .pr2_battery
import PR2Battery
53 from .pr2_motors
import PR2Motors
54 from .pr2_runstop
import PR2Runstops
61 :param context: the plugin context
62 :type context: qt_gui.plugin.Plugin
65 self.
name =
'PR2 Dashboard'
69 parser = argparse.ArgumentParser(prog=
'pr2_dashboard', add_help=
False)
70 PR2Dashboard.add_arguments(parser)
71 args = parser.parse_args(context.argv())
101 callback to process dashboard_agg messages
103 :param msg: dashboard_agg DashboardState message
104 :type msg: pr2_msgs.msg.DashboardState
109 if (msg.motors_halted_valid):
110 if (
not msg.motors_halted.data):
112 self.
_motors.setToolTip(self.tr(
"Motors: Running"))
115 self.
_motors.setToolTip(self.tr(
"Motors: Halted"))
118 self.
_motors.setToolTip(self.tr(
"Motors: Stale"))
120 if (msg.power_state_valid):
121 self.
_batteries[0].set_power_state(msg.power_state)
125 if (msg.power_board_state_valid):
126 [breaker.set_power_board_state_msg(msg.power_board_state)
for breaker
in self.
_breakers]
127 if msg.power_board_state.run_stop:
129 self.
_runstop.setToolTip(self.tr(
"Physical Runstop: OK\nWireless Runstop: OK"))
130 elif msg.power_board_state.wireless_stop:
131 self.
_runstop.set_physical_engaged()
132 self.
_runstop.setToolTip(self.tr(
"Physical Runstop: Pressed\nWireless Runstop: OK"))
133 if not msg.power_board_state.wireless_stop:
134 self.
_runstop.set_wireless_engaged()
135 self.
_runstop.setToolTip(self.tr(
"Physical Runstop: Unknown\nWireless Runstop: Pressed"))
137 [breaker.reset()
for breaker
in self.
_breakers]
139 self.
_runstop.setToolTip(self.tr(
"Physical Runstop: Stale\nWireless Runstop: Stale"))
144 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])
145 if (
not all_breakers_enabled):
146 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):
147 [breaker.set_enable()
for breaker
in self.
_breakers]
148 reset = rospy.ServiceProxy(
"{}/reset_motors".format(self.
_motor_namespace), std_srvs.srv.Empty)
151 except rospy.ServiceException
as e:
152 QMessageBox.critical(self.
_breakers[0],
"Error",
"Failed to reset the motors: service call failed with error: %s" % (e))
155 halt = rospy.ServiceProxy(
"{}/halt_motors".format(self.
_motor_namespace), std_srvs.srv.Empty)
158 except rospy.ServiceException
as e:
159 QMessageBox.critical(self.
_motors,
"Error",
"Failed to halt the motors: service call failed with error: %s" % (e))
166 group = parser.add_argument_group(
'Options for pr2_dashboard')
168 '--motor-namespace', dest=
'motor_namespace',
169 type=str, default=
'pr2_ethercat')