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 os.path
00033 import rospy
00034 
00035 from python_qt_binding.QtCore import QSize
00036 
00037 from pr2_msgs.msg import PowerBoardState
00038 from pr2_power_board.srv import PowerBoardCommand, PowerBoardCommandRequest
00039 
00040 from rqt_robot_dashboard.widgets import MonitorDashWidget, ConsoleDashWidget, MenuDashWidget, BatteryDashWidget, IconToolButton
00041 
00042 from python_qt_binding.QtGui import QMessageBox
00043 
00044 
00045 class PR2BreakerButton(MenuDashWidget):
00046     """
00047     Dashboard widget to display and interact with the PR2 Breaker state.
00048     """
00049     def __init__(self, breaker_name, breaker_index):
00050         """
00051         :param breaker_name: Name of the breaker
00052         :type breaker_name: str
00053         :param breaker_index: Index of the breaker
00054         :type breaker_index: int
00055         """
00056 
00057         import rospkg
00058         import os.path
00059         rp = rospkg.RosPack()
00060 
00061         if breaker_name == 'Left Arm':
00062             breaker_icon = 'ic-larm.svg'
00063         elif breaker_name == 'Base':
00064             breaker_icon = 'ic-base.svg'
00065         elif breaker_name == 'Right Arm':
00066             breaker_icon = 'ic-rarm.svg'
00067         else:
00068             breaker_icon = 'ic-breaker.svg'
00069 
00070         ok_icon = ['bg-green.svg', breaker_icon]
00071         warn_icon = ['bg-yellow.svg', breaker_icon, 'ol-warn-badge.svg']
00072         err_icon = ['bg-red.svg', breaker_icon, 'ol-err-badge.svg']
00073         stale_icon = ['bg-grey.svg', breaker_icon, 'ol-stale-badge.svg']
00074 
00075         icons = [ok_icon, warn_icon, err_icon, stale_icon]
00076 
00077         super(PR2BreakerButton, self).__init__('Breaker:' + breaker_name, icons=icons, icon_paths=[['rqt_pr2_dashboard','images']])
00078         self.update_state(3)
00079 
00080         self.setFixedSize(self._icons[0].actualSize(QSize(50,30)))
00081 
00082         self.add_action('Enable', self.on_enable)
00083         self.add_action('Standby', self.on_standby)
00084         self.add_action('Disable', self.on_standby)
00085         self.add_separator()
00086         self.add_action('Enable All Breakers', self.on_enable_all)
00087         self.add_action('Standby All Breakers', self.on_standby_all)
00088         self.add_action('Disable All Breakers', self.on_standby_all)
00089 
00090         self._power_control = rospy.ServiceProxy('power_board/control', PowerBoardCommand)
00091         self._serial = 0
00092         self._index = breaker_index
00093         self._name = breaker_name
00094         self._power_board_state = None
00095         self._last_status_msg = None
00096         self.setToolTip(breaker_name)
00097 
00098     def control(self, breaker, cmd):
00099         """
00100         Sends a PowerBoardCommand srv to the pr2
00101 
00102         :param breaker: breaker index to send command to
00103         :type breaker: int
00104         :param cmd: command to be sent to the pr2 breaker
00105         :type cmd: str
00106         """
00107         if (not self._power_board_state):
00108             QMessageBox.critical(self, "Error", self.tr("Cannot control breakers until we have received a power board state message"))
00109             return False
00110 
00111         if (not self._power_board_state.run_stop or not self._power_board_state.wireless_stop):
00112             if (cmd == "start"):
00113                 QMessageBox.critical(self, "Error", self.tr("Breakers will not enable because one of the runstops is pressed"))
00114                 return False
00115     
00116         try:
00117             power_cmd = PowerBoardCommandRequest()
00118             power_cmd.breaker_number = breaker
00119             power_cmd.command = cmd
00120             power_cmd.serial_number = self._serial
00121             self._power_control(power_cmd)
00122       
00123             return True
00124         except rospy.ServiceException, e:
00125             QMessageBox.critical(self, "Error", "Service call failed with error: %s"%(e), "Error")
00126             return False
00127       
00128         return False
00129   
00130     def control3(self, cmd):
00131         if (not self.control(0, cmd)):
00132             return False
00133         if (not self.control(1, cmd)):
00134             return False
00135         if (not self.control(2, cmd)):
00136             return False
00137         return True
00138   
00139     def on_enable(self):
00140         self.set_enable()
00141   
00142     def on_standby(self):
00143         self.set_standby()
00144   
00145     def on_disable(self):
00146         self.set_disable()
00147     
00148     def on_enable_all(self):
00149         self.set_enable_all()
00150   
00151     def on_standby_all(self):
00152         self.set_standby_all()
00153   
00154     def on_disable_all(self):
00155         self.set_disable_all()
00156     
00157     def set_enable(self):
00158         if (not self.control(self._index, "reset")):
00159             return
00160     
00161         self.control(self._index, "start")
00162     
00163     def set_standby(self):
00164         if (not self.control(self._index, "reset")):
00165             return
00166     
00167         self.control(self._index, "stop")
00168     
00169     def set_disable(self):
00170         self.control(self._index, "disable")
00171     
00172     def set_enable_all(self):
00173         if (not self.control3("reset")):
00174             return
00175     
00176         self.control3("start")
00177   
00178     def set_standby_all(self):
00179         if (not self.control3("reset")):
00180             return
00181     
00182         self.control3("stop")
00183   
00184     def set_disable_all(self):
00185         self.control3("disable")
00186     
00187     def set_power_board_state_msg(self, msg):
00188         """
00189         Sets state of button based on msg
00190 
00191         :param msg: message containing the PR2 powerboard state
00192         :type msg: pr2_msgs.msg.PowerBoardState
00193         """
00194         last_voltage = msg.circuit_voltage[self._index]
00195       
00196         self._power_board_state = msg
00197         self._serial = msg.serial_num
00198     
00199         status_msg = "OK"
00200     
00201         if (msg.circuit_state[self._index] == PowerBoardState.STATE_DISABLED):
00202             self.set_error()
00203             status_msg = "Disabled"
00204         elif (msg.circuit_state[self._index] == PowerBoardState.STATE_NOPOWER):
00205             self.set_error()
00206             status_msg = "No Power"
00207         elif (msg.circuit_state[self._index] == PowerBoardState.STATE_STANDBY):
00208             self.set_warn()
00209             status_msg = "Standby"
00210         else:
00211             self.set_ok()
00212      
00213         if (status_msg != self._last_status_msg or abs(last_voltage - msg.circuit_voltage[self._index]) >= 0.1):  
00214             self.setToolTip("Breaker: %s \nVoltage: %.02f \nState: %s"%(self._name, msg.circuit_voltage[self._index], status_msg))
00215             self._last_status_msg = status_msg
00216     
00217     def reset(self):
00218         self.set_stale()
00219         self.setToolTip("Breaker: %s (Stale)"%(self._name))
00220 
00221     def set_ok(self):
00222         self.update_state(0)
00223 
00224     def set_warn(self):
00225         self.update_state(1)
00226 
00227     def set_error(self):
00228         self.update_state(2)
00229 
00230     def set_stale(self):
00231         self.update_state(3)


rqt_pr2_dashboard
Author(s): Aaron Blasdel
autogenerated on Fri Jan 3 2014 11:57:09