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())
84 PR2BreakerButton(
'Base', 1),
85 PR2BreakerButton(
'Right Arm', 2)]
97 callback to process dashboard_agg messages 99 :param msg: dashboard_agg DashboardState message 100 :type msg: pr2_msgs.msg.DashboardState 105 if (msg.motors_halted_valid):
106 if (
not msg.motors_halted.data):
107 self._motors.set_ok()
108 self._motors.setToolTip(self.tr(
"Motors: Running"))
110 self._motors.set_error()
111 self._motors.setToolTip(self.tr(
"Motors: Halted"))
113 self._motors.set_stale()
114 self._motors.setToolTip(self.tr(
"Motors: Stale"))
116 if (msg.power_state_valid):
117 self.
_batteries[0].set_power_state(msg.power_state)
121 if (msg.power_board_state_valid):
122 [breaker.set_power_board_state_msg(msg.power_board_state)
for breaker
in self.
_breakers]
123 if msg.power_board_state.run_stop:
124 self._runstop.set_ok()
125 self._runstop.setToolTip(self.tr(
"Physical Runstop: OK\nWireless Runstop: OK"))
126 elif msg.power_board_state.wireless_stop:
127 self._runstop.set_physical_engaged()
128 self._runstop.setToolTip(self.tr(
"Physical Runstop: Pressed\nWireless Runstop: OK"))
129 if not msg.power_board_state.wireless_stop:
130 self._runstop.set_wireless_engaged()
131 self._runstop.setToolTip(self.tr(
"Physical Runstop: Unknown\nWireless Runstop: Pressed"))
133 [breaker.reset()
for breaker
in self.
_breakers]
134 self._runstop.set_stale()
135 self._runstop.setToolTip(self.tr(
"Physical Runstop: Stale\nWireless Runstop: Stale"))
139 if (self.
_dashboard_message is not None and self._dashboard_message.power_board_state_valid):
140 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])
141 if (
not all_breakers_enabled):
142 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):
143 [breaker.set_enable()
for breaker
in self.
_breakers]
144 reset = rospy.ServiceProxy(
"{}/reset_motors".format(self.
_motor_namespace), std_srvs.srv.Empty)
147 except rospy.ServiceException, e:
148 QMessageBox.critical(self.
_breakers[0],
"Error",
"Failed to reset the motors: service call failed with error: %s" % (e))
151 halt = rospy.ServiceProxy(
"{}/halt_motors".format(self.
_motor_namespace), std_srvs.srv.Empty)
154 except rospy.ServiceException, e:
155 QMessageBox.critical(self.
_motors,
"Error",
"Failed to halt the motors: service call failed with error: %s" % (e))
158 self._dashboard_agg_sub.unregister()
162 group = parser.add_argument_group(
'Options for pr2_dashboard')
164 '--motor-namespace', dest=
'motor_namespace',
165 type=str, default=
'pr2_ethercat')
168 self._console.save_settings(plugin_settings, instance_settings)
169 self._monitor.save_settings(plugin_settings, instance_settings)
172 self._console.restore_settings(plugin_settings, instance_settings)
173 self._monitor.restore_settings(plugin_settings, instance_settings)
def on_reset_motors(self)
def dashboard_callback(self, msg)
def shutdown_dashboard(self)
def save_settings(self, plugin_settings, instance_settings)
def restore_settings(self, plugin_settings, instance_settings)
def add_arguments(parser)
_last_dashboard_message_time