$search
00001 # Software License Agreement (BSD License) 00002 # 00003 # Copyright (c) 2008, 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 the Willow Garage 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 00033 import roslib 00034 roslib.load_manifest('turtlebot_dashboard') 00035 00036 import wx 00037 import rospy 00038 import string 00039 import turtlebot_node.srv 00040 00041 from status_control import StatusControl 00042 00043 from os import path 00044 00045 breaker_prefixes = ("digitalzero", "digitalone", "digitaltwo") 00046 00047 class BreakerControl(StatusControl): 00048 def __init__(self, parent, id, breaker_index, breaker_name, icons_path): 00049 StatusControl.__init__(self, parent, id, icons_path, breaker_prefixes[breaker_index], True) 00050 00051 self.Bind(wx.EVT_BUTTON, self.on_click) 00052 self._index = breaker_index 00053 self._name = breaker_name 00054 self.raw_byte = 0 00055 self._breaker_state = 0 00056 self._power_control = rospy.ServiceProxy('turtlebot_node/set_digital_outputs', turtlebot_node.srv.SetDigitalOutputs) 00057 self.digital_outs =[0,0,0] 00058 00059 00060 00061 def on_click(self, evt): 00062 self.control(0) 00063 return True 00064 00065 def control(self, cmd): 00066 if (not self._breaker_state): 00067 wx.MessageBox("Cannot control breakers until we have received a power board state message", "Error", wx.OK|wx.ICON_ERROR) 00068 return False 00069 00070 try: 00071 tmp = self._raw_byte 00072 for i in range(0,3): 00073 self.digital_outs[i]=tmp%2 00074 tmp = tmp >> 1 00075 self.digital_outs[self._index] = not self.digital_outs[self._index] 00076 power_cmd = turtlebot_node.srv.SetDigitalOutputsRequest(self.digital_outs[0], self.digital_outs[1], self.digital_outs[2]) 00077 #print power_cmd 00078 self._power_control(power_cmd) 00079 00080 return True 00081 except rospy.ServiceException, e: 00082 wx.MessageBox("Service call failed with error: %s"%(e), "Error", wx.OK|wx.ICON_ERROR) 00083 return False 00084 00085 return False 00086 00087 00088 def set_breaker_state(self, msg): 00089 self._breaker_state = True 00090 self._raw_byte = string.atoi(msg['Raw Byte']) 00091 tmp = self._raw_byte 00092 for i in range(0,3): 00093 self.digital_outs[i]=tmp%2 00094 tmp = tmp >> 1 00095 00096 if(self.digital_outs[self._index]==0): 00097 self.set_error() 00098 status_msg = "Disabled" 00099 else: 00100 self.set_ok() 00101 status_msg = "Enabled" 00102 00103 00104 def reset(self): 00105 self.set_stale() 00106 self.SetToolTip(wx.ToolTip("%s: Stale"%(self._name)))