$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; roslib.load_manifest('generic_dashboard') 00034 00035 WXVER = '2.8' 00036 import wxversion 00037 if wxversion.checkInstalled(WXVER): 00038 wxversion.select(WXVER) 00039 else: 00040 print >> sys.stderr, "This application requires wxPython version %s"%(WXVER) 00041 sys.exit(1) 00042 00043 import wx 00044 import wx.aui 00045 import wx.py.shell 00046 import rxtools 00047 import rxtools.cppwidgets as rxtools 00048 00049 import robot_monitor 00050 from robot_monitor.robot_monitor_panel import RobotMonitorPanel 00051 import std_msgs.msg 00052 import std_srvs.srv 00053 import rospy 00054 from roslib import rosenv 00055 from diagnostics_control import DiagnosticsControl 00056 import diagnostic_msgs.msg 00057 import collections 00058 from os import path 00059 import threading 00060 00061 class GenericFrame(wx.Frame): 00062 _CONFIG_WINDOW_X="/Window/X" 00063 _CONFIG_WINDOW_Y="/Window/Y" 00064 00065 def __init__(self, parent=None, id=wx.ID_ANY, title='Dashboard', pos=wx.DefaultPosition, size=(400, 50), style=wx.CAPTION|wx.CLOSE_BOX|wx.STAY_ON_TOP, app = wx.App()): 00066 wx.Frame.__init__(self, parent, id, title, pos, size, style) 00067 00068 wx.InitAllImageHandlers() 00069 00070 rospy.init_node('dashboard', anonymous=True) 00071 try: 00072 getattr(rxtools, "initRoscpp") 00073 rxtools.initRoscpp("dashboard_cpp", anonymous=True) 00074 except AttributeError: 00075 pass 00076 00077 self._dashboard_agg_sub = rospy.Subscriber('diagnostics_agg', diagnostic_msgs.msg.DiagnosticArray, self.dashboard_callback) 00078 self._dashboard_message = None 00079 self._last_dashboard_message_time = 0.0 00080 00081 self.SetTitle('%s (%s)'%(title, rosenv.get_master_uri())) 00082 self._app = app 00083 self._triggers = collections.defaultdict(list) 00084 00085 def init(self, components): 00086 sizer = wx.BoxSizer(wx.HORIZONTAL) 00087 self.SetSizer(sizer) 00088 00089 self._components_list = [] 00090 00091 self.recursive_init(sizer, components) 00092 static_sizer = wx.StaticBoxSizer(wx.StaticBox(self, wx.ID_ANY, "Breakers"), wx.HORIZONTAL) 00093 sizer.Add(static_sizer, 0) 00094 00095 self._config = wx.Config("dashboard") 00096 00097 self.Bind(wx.EVT_CLOSE, self.on_close) 00098 00099 self.Layout() 00100 self.Fit() 00101 00102 self.load_config() 00103 00104 self._timer = wx.Timer(self) 00105 self.Bind(wx.EVT_TIMER, self.on_timer) 00106 self._timer.Start(500) 00107 00108 def recursive_init(self, parent, components): 00109 if type(components)==type({}): 00110 for category in components: 00111 static_sizer = wx.StaticBoxSizer(wx.StaticBox(self, wx.ID_ANY, category), wx.HORIZONTAL) 00112 parent.Add(static_sizer, 0) 00113 subcomps = self.recursive_init(static_sizer, components[category]) 00114 elif type(components)==type([]): 00115 for component in components: 00116 parent.Add(component, 0) 00117 self.add(component) 00118 00119 def add(self, component): 00120 self._components_list.append(component) 00121 if type(component) == DiagnosticsControl: 00122 self._triggers['*'].append(component) 00123 elif component.trigger: 00124 self._triggers[ component.trigger ].append( component ) 00125 00126 00127 def start(self): 00128 self.Show() 00129 self._app.MainLoop() 00130 00131 def __del__(self): 00132 self._dashboard_agg_sub.unregister() 00133 00134 def on_timer(self, evt): 00135 if (rospy.get_time() - self._last_dashboard_message_time > 5.0): 00136 for component in self._components_list: 00137 component.set_status('stale') 00138 00139 for component in self._components_list: 00140 component.update() 00141 00142 if (rospy.is_shutdown()): 00143 self.Close() 00144 00145 def dashboard_callback(self, msg): 00146 wx.CallAfter(self.new_dashboard_message, msg) 00147 00148 def new_dashboard_message(self, msg): 00149 self._dashboard_message = msg 00150 self._last_dashboard_message_time = rospy.get_time() 00151 00152 for status in msg.status: 00153 path = status.name.split(':')[0] 00154 if path in self._triggers: 00155 for component in self._triggers[path]: 00156 if component.callback: 00157 component.set_data( component.callback(status) ) 00158 """ 00159 for status in msg.status: 00160 if status.name == "/Power System/Battery": 00161 for value in status.values: 00162 battery_status[value.key]=value.value 00163 if status.name == "/Power System/Laptop Battery": 00164 for value in status.values: 00165 laptop_battery_status[value.key]=value.value 00166 if status.name == "/Mode/Operating Mode": 00167 op_mode=status.message 00168 if status.name == "/Digital IO/Digital Outputs": 00169 #print "got digital IO" 00170 for value in status.values: 00171 breaker_status[value.key]=value.value""" 00172 00173 """ 00174 def on_motors_clicked(self, evt): 00175 menu = wx.Menu() 00176 menu.Bind(wx.EVT_MENU, self.on_passive_mode, menu.Append(wx.ID_ANY, "Passive Mode")) 00177 menu.Bind(wx.EVT_MENU, self.on_safe_mode, menu.Append(wx.ID_ANY, "Safety Mode")) 00178 menu.Bind(wx.EVT_MENU, self.on_full_mode, menu.Append(wx.ID_ANY, "Full Mode")) 00179 self._motors_button.toggle(True) 00180 self.PopupMenu(menu) 00181 self._motors_button.toggle(False) 00182 00183 def on_passive_mode(self, evt): 00184 passive = rospy.ServiceProxy("/turtlebot_node/set_operation_mode",turtlebot_node.srv.SetTurtlebotMode ) 00185 try: 00186 passive(turtlebot_node.msg.TurtlebotSensorState.OI_MODE_PASSIVE) 00187 except rospy.ServiceException, e: 00188 wx.MessageBox("Failed to put the turtlebot in passive mode: service call failed with error: %s"%(e), "Error", wx.OK|wx.ICON_ERROR) 00189 00190 def on_safe_mode(self, evt): 00191 safe = rospy.ServiceProxy("/turtlebot_node/set_operation_mode",turtlebot_node.srv.SetTurtlebotMode) 00192 try: 00193 safe(turtlebot_node.msg.TurtlebotSensorState.OI_MODE_SAFE) 00194 except rospy.ServiceException, e: 00195 wx.MessageBox("Failed to put the turtlebot in safe mode: service call failed with error: %s"%(e), "Error", wx.OK|wx.ICON_ERROR) 00196 00197 def on_full_mode(self, evt): 00198 full = rospy.ServiceProxy("/turtlebot_node/set_operation_mode", turtlebot_node.srv.SetTurtlebotMode) 00199 try: 00200 full(turtlebot_node.msg.TurtlebotSensorState.OI_MODE_FULL) 00201 except rospy.ServiceException, e: 00202 wx.MessageBox("Failed to put the turtlebot in full mode: service call failed with error: %s"%(e), "Error", wx.OK|wx.ICON_ERROR) 00203 00204 """ 00205 00206 def load_config(self): 00207 # Load our window options 00208 (x, y) = self.GetPositionTuple() 00209 (width, height) = self.GetSizeTuple() 00210 if (self._config.HasEntry(self._CONFIG_WINDOW_X)): 00211 x = self._config.ReadInt(self._CONFIG_WINDOW_X) 00212 if (self._config.HasEntry(self._CONFIG_WINDOW_Y)): 00213 y = self._config.ReadInt(self._CONFIG_WINDOW_Y) 00214 00215 self.SetPosition((x, y)) 00216 self.SetSize((width, height)) 00217 00218 def save_config(self): 00219 config = self._config 00220 00221 (x, y) = self.GetPositionTuple() 00222 (width, height) = self.GetSizeTuple() 00223 config.WriteInt(self._CONFIG_WINDOW_X, x) 00224 config.WriteInt(self._CONFIG_WINDOW_Y, y) 00225 00226 config.Flush() 00227 00228 def on_close(self, event): 00229 self.save_config() 00230 00231 self.Destroy() 00232