pr2_breaker.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2012, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions
00008 # are met:
00009 #
00010 #  * Redistributions of source code must retain the above copyright
00011 #    notice, this list of conditions and the following disclaimer.
00012 #  * Redistributions in binary form must reproduce the above
00013 #    copyright notice, this list of conditions and the following
00014 #    disclaimer in the documentation and/or other materials provided
00015 #    with the distribution.
00016 #  * Neither the name of Willow Garage, Inc. nor the names of its
00017 #    contributors may be used to endorse or promote products derived
00018 #    from this software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 # POSSIBILITY OF SUCH DAMAGE.
00032 import rospy
00033 
00034 from python_qt_binding.QtCore import QSize
00035 
00036 from pr2_msgs.msg import PowerBoardState
00037 from pr2_power_board.srv import PowerBoardCommand, PowerBoardCommandRequest
00038 
00039 from rqt_robot_dashboard.widgets import MenuDashWidget
00040 
00041 from python_qt_binding.QtGui import QMessageBox
00042 
00043 
00044 class PR2BreakerButton(MenuDashWidget):
00045     """
00046     Dashboard widget to display and interact with the PR2 Breaker state.
00047     """
00048     def __init__(self, breaker_name, breaker_index):
00049         """
00050         :param breaker_name: Name of the breaker
00051         :type breaker_name: str
00052         :param breaker_index: Index of the breaker
00053         :type breaker_index: int
00054         """
00055 
00056         if breaker_name == 'Left Arm':
00057             breaker_icon = 'ic-larm.svg'
00058         elif breaker_name == 'Base':
00059             breaker_icon = 'ic-base.svg'
00060         elif breaker_name == 'Right Arm':
00061             breaker_icon = 'ic-rarm.svg'
00062         else:
00063             breaker_icon = 'ic-breaker.svg'
00064 
00065         ok_icon = ['bg-green.svg', breaker_icon]
00066         warn_icon = ['bg-yellow.svg', breaker_icon, 'ol-warn-badge.svg']
00067         err_icon = ['bg-red.svg', breaker_icon, 'ol-err-badge.svg']
00068         stale_icon = ['bg-grey.svg', breaker_icon, 'ol-stale-badge.svg']
00069 
00070         icons = [ok_icon, warn_icon, err_icon, stale_icon]
00071 
00072         super(PR2BreakerButton, self).__init__('Breaker:' + breaker_name, icons=icons, icon_paths=[['rqt_pr2_dashboard', 'images']])
00073         self.update_state(3)
00074 
00075         self.setFixedSize(self._icons[0].actualSize(QSize(50, 30)))
00076 
00077         self.add_action('Enable', self.on_enable)
00078         self.add_action('Standby', self.on_standby)
00079         self.add_action('Disable', self.on_disable)
00080         self.add_separator()
00081         self.add_action('Enable All Breakers', self.on_enable_all)
00082         self.add_action('Standby All Breakers', self.on_standby_all)
00083         self.add_action('Disable All Breakers', self.on_disable_all)
00084 
00085         self._power_control = rospy.ServiceProxy('power_board/control', PowerBoardCommand)
00086         self._serial = 0
00087         self._index = breaker_index
00088         self._name = breaker_name
00089         self._power_board_state = None
00090         self._last_status_msg = None
00091         self.setToolTip(breaker_name)
00092 
00093     def control(self, breaker, cmd):
00094         """
00095         Sends a PowerBoardCommand srv to the pr2
00096 
00097         :param breaker: breaker index to send command to
00098         :type breaker: int
00099         :param cmd: command to be sent to the pr2 breaker
00100         :type cmd: str
00101         """
00102         if (not self._power_board_state):
00103             QMessageBox.critical(self, "Error", self.tr("Cannot control breakers until we have received a power board state message"))
00104             return False
00105 
00106         if (not self._power_board_state.run_stop or not self._power_board_state.wireless_stop):
00107             if (cmd == "start"):
00108                 QMessageBox.critical(self, "Error", self.tr("Breakers will not enable because one of the runstops is pressed"))
00109                 return False
00110 
00111         try:
00112             power_cmd = PowerBoardCommandRequest()
00113             power_cmd.breaker_number = breaker
00114             power_cmd.command = cmd
00115             power_cmd.serial_number = self._serial
00116             self._power_control(power_cmd)
00117 
00118             return True
00119         except rospy.ServiceException, e:
00120             QMessageBox.critical(self, "Error", "Service call failed with error: %s" % (e), "Error")
00121             return False
00122 
00123         return False
00124 
00125     def control3(self, cmd):
00126         if (not self.control(0, cmd)):
00127             return False
00128         if (not self.control(1, cmd)):
00129             return False
00130         if (not self.control(2, cmd)):
00131             return False
00132         return True
00133 
00134     def on_enable(self):
00135         self.set_enable()
00136 
00137     def on_standby(self):
00138         self.set_standby()
00139 
00140     def on_disable(self):
00141         self.set_disable()
00142 
00143     def on_enable_all(self):
00144         self.set_enable_all()
00145 
00146     def on_standby_all(self):
00147         self.set_standby_all()
00148 
00149     def on_disable_all(self):
00150         self.set_disable_all()
00151 
00152     def set_enable(self):
00153         if (not self.control(self._index, "reset")):
00154             return
00155 
00156         self.control(self._index, "start")
00157 
00158     def set_standby(self):
00159         if (not self.control(self._index, "reset")):
00160             return
00161 
00162         self.control(self._index, "stop")
00163 
00164     def set_disable(self):
00165         self.control(self._index, "disable")
00166 
00167     def set_enable_all(self):
00168         if (not self.control3("reset")):
00169             return
00170 
00171         self.control3("start")
00172 
00173     def set_standby_all(self):
00174         if (not self.control3("reset")):
00175             return
00176 
00177         self.control3("stop")
00178 
00179     def set_disable_all(self):
00180         self.control3("disable")
00181 
00182     def set_power_board_state_msg(self, msg):
00183         """
00184         Sets state of button based on msg
00185 
00186         :param msg: message containing the PR2 powerboard state
00187         :type msg: pr2_msgs.msg.PowerBoardState
00188         """
00189         last_voltage = msg.circuit_voltage[self._index]
00190 
00191         self._power_board_state = msg
00192         self._serial = msg.serial_num
00193 
00194         status_msg = "OK"
00195 
00196         if (msg.circuit_state[self._index] == PowerBoardState.STATE_DISABLED):
00197             self.set_error()
00198             status_msg = "Disabled"
00199         elif (msg.circuit_state[self._index] == PowerBoardState.STATE_NOPOWER):
00200             self.set_error()
00201             status_msg = "No Power"
00202         elif (msg.circuit_state[self._index] == PowerBoardState.STATE_STANDBY):
00203             self.set_warn()
00204             status_msg = "Standby"
00205         else:
00206             self.set_ok()
00207 
00208         if (status_msg != self._last_status_msg or abs(last_voltage - msg.circuit_voltage[self._index]) >= 0.1):
00209             self.setToolTip("Breaker: %s \nVoltage: %.02f \nState: %s" % (self._name, msg.circuit_voltage[self._index], status_msg))
00210             self._last_status_msg = status_msg
00211 
00212     def reset(self):
00213         self.set_stale()
00214         self.setToolTip("Breaker: %s (Stale)" % (self._name))
00215 
00216     def set_ok(self):
00217         self.update_state(0)
00218 
00219     def set_warn(self):
00220         self.update_state(1)
00221 
00222     def set_error(self):
00223         self.update_state(2)
00224 
00225     def set_stale(self):
00226         self.update_state(3)


rqt_pr2_dashboard
Author(s): Aaron Blasdel
autogenerated on Wed Aug 26 2015 16:13:38