00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051 import roslib
00052 roslib.load_manifest('p2os_dashboard')
00053
00054 import wx
00055 import rospy
00056
00057
00058
00059
00060 from status_control import StatusControl
00061
00062 from os import path
00063
00064 breaker_prefixes = ("breakerleft", "breakerbase", "breakerright")
00065
00066 class BreakerControl(StatusControl):
00067 def __init__(self, parent, id, breaker_index, breaker_name, icons_path):
00068 StatusControl.__init__(self, parent, id, icons_path, breaker_prefixes[breaker_index], True)
00069
00070 self.Bind(wx.EVT_LEFT_DOWN, self.on_left_down)
00071
00072 self._power_control = rospy.ServiceProxy('power_board/control', PowerBoardCommand)
00073 self._serial = 0
00074 self._index = breaker_index
00075 self._name = breaker_name
00076 self._power_board_state = None
00077 self._last_status_msg = None
00078
00079 def on_left_down(self, evt):
00080 menu = wx.Menu()
00081 menu.Bind(wx.EVT_MENU, self.on_enable, menu.Append(wx.ID_ANY, "Enable"))
00082 menu.Bind(wx.EVT_MENU, self.on_standby, menu.Append(wx.ID_ANY, "Standby"))
00083 menu.Bind(wx.EVT_MENU, self.on_disable, menu.Append(wx.ID_ANY, "Disable"))
00084 menu.AppendSeparator()
00085 menu.Bind(wx.EVT_MENU, self.on_enable_all, menu.Append(wx.ID_ANY, "Enable All Breakers"))
00086 menu.Bind(wx.EVT_MENU, self.on_standby_all, menu.Append(wx.ID_ANY, "Standby All Breakers"))
00087 menu.Bind(wx.EVT_MENU, self.on_disable_all, menu.Append(wx.ID_ANY, "Disable All Breakers"))
00088
00089 self.toggle(True)
00090 self.PopupMenu(menu)
00091 self.toggle(False)
00092
00093 def control(self, breaker, cmd):
00094 if (not self._power_board_state):
00095 wx.MessageBox("Cannot control breakers until we have received a power board state message", "Error", wx.OK|wx.ICON_ERROR)
00096 return False
00097
00098 if (not self._power_board_state.run_stop or not self._power_board_state.wireless_stop):
00099 if (cmd == "start"):
00100 wx.MessageBox("Breakers will not enable because one of the runstops is pressed", "Error", wx.OK|wx.ICON_ERROR)
00101 return False
00102
00103 try:
00104 power_cmd = PowerBoardCommandRequest()
00105 power_cmd.breaker_number = breaker
00106 power_cmd.command = cmd
00107 power_cmd.serial_number = self._serial
00108 self._power_control(power_cmd)
00109
00110 return True
00111 except rospy.ServiceException, e:
00112 wx.MessageBox("Service call failed with error: %s"%(e), "Error", wx.OK|wx.ICON_ERROR)
00113 return False
00114
00115 return False
00116
00117 def control3(self, cmd):
00118 if (not self.control(0, cmd)):
00119 return False
00120 if (not self.control(1, cmd)):
00121 return False
00122 if (not self.control(2, cmd)):
00123 return False
00124
00125 return True
00126
00127 def on_enable(self, evt):
00128 self.set_enable()
00129
00130 def on_standby(self, evt):
00131 self.set_standby()
00132
00133 def on_disable(self, evt):
00134 self.set_disable()
00135
00136 def on_enable_all(self, evt):
00137 self.set_enable_all()
00138
00139 def on_standby_all(self, evt):
00140 self.set_standby_all()
00141
00142 def on_disable_all(self, evt):
00143 self.set_disable_all()
00144
00145 def set_enable(self):
00146 if (not self.control(self._index, "reset")):
00147 return
00148
00149 self.control(self._index, "start")
00150
00151 def set_standby(self):
00152 if (not self.control(self._index, "reset")):
00153 return
00154
00155 self.control(self._index, "stop")
00156
00157 def set_disable(self):
00158 self.control(self._index, "disable")
00159
00160 def set_enable_all(self):
00161 if (not self.control3("reset")):
00162 return
00163
00164 self.control3("start")
00165
00166 def set_standby_all(self):
00167 if (not self.control3("reset")):
00168 return
00169
00170 self.control3("stop")
00171
00172 def set_disable_all(self):
00173 self.control3("disable")
00174
00175 def set_power_board_state_msg(self, msg):
00176 last_voltage = msg.circuit_voltage[self._index]
00177
00178 self._power_board_state = msg
00179 self._serial = msg.serial_num
00180
00181 status_msg = "OK"
00182
00183 if (msg.circuit_state[self._index] == PowerBoardState.STATE_DISABLED):
00184 self.set_error()
00185 status_msg = "Disabled"
00186 elif (msg.circuit_state[self._index] == PowerBoardState.STATE_NOPOWER):
00187 self.set_error()
00188 status_msg = "No Power"
00189 elif (msg.circuit_state[self._index] == PowerBoardState.STATE_STANDBY):
00190 self.set_warn()
00191 status_msg = "Standby"
00192 else:
00193 self.set_ok()
00194
00195 if (status_msg != self._last_status_msg or abs(last_voltage - msg.circuit_voltage[self._index]) >= 0.1):
00196 self.SetToolTip(wx.ToolTip("Breaker %s (index=[%s], voltage=[%.02f])) State: %s"%(self._name, self._index, msg.circuit_voltage[self._index], status_msg)))
00197 self._last_status_msg = status_msg
00198
00199 def reset(self):
00200 self.set_stale()
00201 self.SetToolTip(wx.ToolTip("Breaker %s: Stale"%(self._name)))