elektron_frame.py
Go to the documentation of this file.
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('elektron_dashboard')
00035 
00036 import wx
00037 import wx.aui
00038 import wx.py.shell
00039 import rxtools
00040 import rxtools.cppwidgets as rxtools
00041 
00042 import robot_monitor
00043 from robot_monitor.robot_monitor_panel import RobotMonitorPanel
00044 import diagnostic_msgs.msg
00045 import std_msgs.msg
00046 import std_srvs.srv
00047 #import turtlebot_node.msg
00048 #import turtlebot_node.srv
00049 
00050 import rospy
00051 from roslib import rosenv
00052 
00053 from os import path
00054 import threading
00055 
00056 #from breaker_control import BreakerControl
00057 from status_control import StatusControl
00058 from power_state_control import PowerStateControl
00059 from wifi_control import WifiControl
00060 from diagnostics_frame import DiagnosticsFrame
00061 from rosout_frame import RosoutFrame
00062 from cpu_frame import CpuFrame
00063 from mem_frame import MemFrame
00064 from main_power_control import MainPowerControl
00065 
00066 class ElektronFrame(wx.Frame):
00067     _CONFIG_WINDOW_X = "/Window/X"
00068     _CONFIG_WINDOW_Y = "/Window/Y"
00069 
00070     def __init__(self, parent, id=wx.ID_ANY, title='Elektron Dashboard', pos=wx.DefaultPosition, size=(400, 50), style=wx.CAPTION | wx.CLOSE_BOX | wx.STAY_ON_TOP):
00071         wx.Frame.__init__(self, parent, id, title, pos, size, style)
00072 
00073         wx.InitAllImageHandlers()
00074 
00075         rospy.init_node('elektron_dashboard', anonymous=True)
00076         try:
00077             getattr(rxtools, "initRoscpp")
00078             rxtools.initRoscpp("elektron_dashboard_cpp", anonymous=True)
00079         except AttributeError:
00080             pass
00081 
00082         self.SetTitle('Elektron Dashboard (%s)' % rosenv.get_master_uri())
00083 
00084         icons_path = path.join(roslib.packages.get_pkg_dir('elektron_dashboard'), "icons/")
00085 
00086         sizer = wx.BoxSizer(wx.HORIZONTAL)
00087         self.SetSizer(sizer)
00088 
00089         static_sizer = wx.StaticBoxSizer(wx.StaticBox(self, wx.ID_ANY, "Diagnostic"), wx.HORIZONTAL)
00090         sizer.Add(static_sizer, 0)
00091         
00092         # Diagnostics
00093         self._diagnostics_button = StatusControl(self, wx.ID_ANY, icons_path, "diag", True)
00094         self._diagnostics_button.SetToolTip(wx.ToolTip("Diagnostics"))
00095         static_sizer.Add(self._diagnostics_button, 0)
00096 
00097         # Rosout
00098         self._rosout_button = StatusControl(self, wx.ID_ANY, icons_path, "rosout", True)
00099         self._rosout_button.SetToolTip(wx.ToolTip("Rosout"))
00100         static_sizer.Add(self._rosout_button, 0)
00101 #~
00102         #~ # Motors
00103         #~ self._motors_button = StatusControl(self, wx.ID_ANY, icons_path, "motor", True)
00104         #~ self._motors_button.SetToolTip(wx.ToolTip("Mode"))
00105         #~ static_sizer.Add(self._motors_button, 0)
00106         #~ self._motors_button.Bind(wx.EVT_LEFT_DOWN, self.on_motors_clicked)
00107 #~
00108         #~ static_sizer = wx.StaticBoxSizer(wx.StaticBox(self, wx.ID_ANY, "Breakers"), wx.HORIZONTAL)
00109         #~ sizer.Add(static_sizer, 0)
00110 #~
00111         #~ # Breakers
00112         #~ breaker_names = ["Digital Out 1", "Digital Out 1", "Digital Out 2"]
00113         #~ self._breaker_ctrls = []
00114         #~ for i in xrange(0, 3):
00115           #~ ctrl = BreakerControl(self, wx.ID_ANY, i, breaker_names[i], icons_path)
00116           #~ ctrl.SetToolTip(wx.ToolTip("%s"%(breaker_names[i])))
00117           #~ self._breaker_ctrls.append(ctrl)
00118           #~ static_sizer.Add(ctrl, 0)
00119 
00120 #        static_sizer = wx.StaticBoxSizer(wx.StaticBox(self, wx.ID_ANY, "Runstops"), wx.HORIZONTAL)
00121 #        sizer.Add(static_sizer, 0)
00122 
00123         # run-stop
00124 #        self._runstop_ctrl = StatusControl(self, wx.ID_ANY, icons_path, "runstop", False)
00125 #        self._runstop_ctrl.SetToolTip(wx.ToolTip("Physical Runstop: Unknown"))
00126 #        static_sizer.Add(self._runstop_ctrl, 0)
00127 
00128         # Wireless run-stop
00129 #        self._wireless_runstop_ctrl = StatusControl(self, wx.ID_ANY, icons_path, "runstop-wireless", False)
00130 #        self._wireless_runstop_ctrl.SetToolTip(wx.ToolTip("Wireless Runstop: Unknown"))
00131 #        static_sizer.Add(self._wireless_runstop_ctrl, 0)
00132 
00133         #~ static_sizer = wx.StaticBoxSizer(wx.StaticBox(self, wx.ID_ANY, "Battery"), wx.HORIZONTAL)
00134         #~ sizer.Add(static_sizer, 0)
00135 #~
00136         #~ # Battery State
00137         #~ self._power_state_ctrl = PowerStateControl(self, wx.ID_ANY, icons_path)
00138         #~ self._power_state_ctrl.SetToolTip(wx.ToolTip("Battery: Stale"))
00139         #~ static_sizer.Add(self._power_state_ctrl, 1, wx.EXPAND)
00140 
00141         static_sizer = wx.StaticBoxSizer(wx.StaticBox(self, wx.ID_ANY, "CPU0"), wx.HORIZONTAL)
00142         sizer.Add(static_sizer, 0)
00143         
00144         self._cpu0_state = CpuFrame(self, wx.ID_ANY)
00145         static_sizer.Add(self._cpu0_state, 1, wx.EXPAND)
00146         
00147         static_sizer = wx.StaticBoxSizer(wx.StaticBox(self, wx.ID_ANY, "CPU1"), wx.HORIZONTAL)
00148         sizer.Add(static_sizer, 0)
00149         
00150         self._cpu1_state = CpuFrame(self, wx.ID_ANY)
00151         static_sizer.Add(self._cpu1_state, 1, wx.EXPAND)
00152         
00153         static_sizer = wx.StaticBoxSizer(wx.StaticBox(self, wx.ID_ANY, "Memory"), wx.HORIZONTAL)
00154         sizer.Add(static_sizer, 0)
00155         
00156         self._mem_state = MemFrame(self, wx.ID_ANY)
00157         static_sizer.Add(self._mem_state, 1, wx.EXPAND)
00158 
00159 
00160         # WiFi State
00161         self.wlan_interface = rospy.get_param('~wlan_interface', 'eth1')
00162         self.wlan_power = rospy.get_param('~wlan_power', 100)
00163         
00164         static_sizer = wx.StaticBoxSizer(wx.StaticBox(self, wx.ID_ANY, "WiFi: %s" % self.wlan_interface), wx.HORIZONTAL)
00165         sizer.Add(static_sizer, 0)
00166         
00167         
00168         self._wifi_state = WifiControl(self, wx.ID_ANY, icons_path, self.wlan_interface, self.wlan_power)
00169         self._wifi_state.SetToolTip(wx.ToolTip("WiFi: Stale"))
00170         static_sizer.Add(self._wifi_state, 1, wx.EXPAND)
00171         
00172         # Laptop Battery State
00173         static_sizer = wx.StaticBoxSizer(wx.StaticBox(self, wx.ID_ANY, "Laptop"), wx.HORIZONTAL)
00174         sizer.Add(static_sizer, 0)
00175         
00176         self._power_state_ctrl_laptop = PowerStateControl(self, wx.ID_ANY, icons_path)
00177         self._power_state_ctrl_laptop.SetToolTip(wx.ToolTip("Laptop Battery: Stale"))
00178         static_sizer.Add(self._power_state_ctrl_laptop, 1, wx.EXPAND)
00179         
00180         
00181         
00182         # Laptop Battery State
00183         static_sizer = wx.StaticBoxSizer(wx.StaticBox(self, wx.ID_ANY, "Main power"), wx.HORIZONTAL)
00184         sizer.Add(static_sizer, 0)
00185         
00186         self._main_power_ctrl = MainPowerControl(self, wx.ID_ANY, icons_path)
00187         static_sizer.Add(self._main_power_ctrl, 1, wx.EXPAND)
00188         
00189 
00190         self._config = wx.Config("elektron_dashboard")
00191 
00192         self.Bind(wx.EVT_CLOSE, self.on_close)
00193 
00194         self.Layout()
00195         self.Fit()
00196 
00197         self._diagnostics_frame = DiagnosticsFrame(self, wx.ID_ANY, "Diagnostics")
00198         self._diagnostics_frame.Hide()
00199         self._diagnostics_frame.Center()
00200         self._diagnostics_button.Bind(wx.EVT_BUTTON, self.on_diagnostics_clicked)
00201 
00202         self._rosout_frame = RosoutFrame(self, wx.ID_ANY, "Rosout")
00203         self._rosout_frame.Hide()
00204         self._rosout_frame.Center()
00205         self._rosout_button.Bind(wx.EVT_BUTTON, self.on_rosout_clicked)
00206 
00207         self.load_config()
00208 
00209         self._timer = wx.Timer(self)
00210         self.Bind(wx.EVT_TIMER, self.on_timer)
00211         self._timer.Start(500)
00212 
00213         self._dashboard_agg_sub = rospy.Subscriber('diagnostics_agg', diagnostic_msgs.msg.DiagnosticArray, self.dashboard_callback)
00214 
00215         self._dashboard_message = None
00216         self._last_dashboard_message_time = 0.0
00217 
00218     #~ def __del__(self):
00219         #~ self._dashboard_agg_sub.unregister()
00220 
00221     def on_timer(self, evt):
00222       level = self._diagnostics_frame._diagnostics_panel.get_top_level_state()
00223       if (level == -1 or level == 3):
00224          if (self._diagnostics_button.set_stale()):
00225             self._diagnostics_button.SetToolTip(wx.ToolTip("Diagnostics: Stale"))
00226       elif (level >= 2):
00227          if (self._diagnostics_button.set_error()):
00228             self._diagnostics_button.SetToolTip(wx.ToolTip("Diagnostics: Error"))
00229       elif (level == 1):
00230          if (self._diagnostics_button.set_warn()):
00231             self._diagnostics_button.SetToolTip(wx.ToolTip("Diagnostics: Warning"))
00232       else:
00233          if (self._diagnostics_button.set_ok()):
00234             self._diagnostics_button.SetToolTip(wx.ToolTip("Diagnostics: OK"))
00235 
00236       self.update_rosout()
00237 
00238       #~ if (rospy.get_time() - self._last_dashboard_message_time > 5.0):
00239           #~ self._motors_button.set_stale()
00240           #~ self._power_state_ctrl.set_stale()
00241           #~ self._power_state_ctrl_laptop.set_stale()
00242           #~ [ctrl.reset() for ctrl in self._breaker_ctrls]
00243 #~ #          self._runstop_ctrl.set_stale()
00244 #~ #          self._wireless_runstop_ctrl.set_stale()
00245           #~ ctrls = [self._motors_button, self._power_state_ctrl, self._power_state_ctrl_laptop]
00246           #~ ctrls.extend(self._breaker_ctrls)
00247           #~ for ctrl in ctrls:
00248               #~ ctrl.SetToolTip(wx.ToolTip("No message received on dashboard_agg in the last 5 seconds"))
00249 
00250       if (rospy.is_shutdown()):
00251         self.Close()
00252 
00253     def on_diagnostics_clicked(self, evt):
00254         self._diagnostics_frame.Show()
00255         self._diagnostics_frame.Raise()
00256 
00257     def on_rosout_clicked(self, evt):
00258         self._rosout_frame.Show()
00259         self._rosout_frame.Raise()
00260 
00261     #~ def on_motors_clicked(self, evt):
00262       #~ menu = wx.Menu()
00263       #~ menu.Bind(wx.EVT_MENU, self.on_passive_mode, menu.Append(wx.ID_ANY, "Passive Mode"))
00264       #~ menu.Bind(wx.EVT_MENU, self.on_safe_mode, menu.Append(wx.ID_ANY, "Safety Mode"))
00265       #~ menu.Bind(wx.EVT_MENU, self.on_full_mode, menu.Append(wx.ID_ANY, "Full Mode"))
00266       #~ self._motors_button.toggle(True)
00267       #~ self.PopupMenu(menu)
00268       #~ self._motors_button.toggle(False)
00269 #~
00270     #~ def on_passive_mode(self, evt):
00271       #~ passive = rospy.ServiceProxy("/turtlebot_node/set_operation_mode",turtlebot_node.srv.SetTurtlebotMode )
00272       #~ try:
00273         #~ passive(turtlebot_node.msg.TurtlebotSensorState.OI_MODE_PASSIVE)
00274       #~ except rospy.ServiceException, e:
00275         #~ wx.MessageBox("Failed to put the turtlebot in passive mode: service call failed with error: %s"%(e), "Error", wx.OK|wx.ICON_ERROR)
00276 #~
00277     #~ def on_safe_mode(self, evt):
00278       #~ safe = rospy.ServiceProxy("/turtlebot_node/set_operation_mode",turtlebot_node.srv.SetTurtlebotMode)
00279       #~ try:
00280         #~ safe(turtlebot_node.msg.TurtlebotSensorState.OI_MODE_SAFE)
00281       #~ except rospy.ServiceException, e:
00282         #~ wx.MessageBox("Failed to put the turtlebot in safe mode: service call failed with error: %s"%(e), "Error", wx.OK|wx.ICON_ERROR)
00283 #~
00284     #~ def on_full_mode(self, evt):
00285       #~ full = rospy.ServiceProxy("/turtlebot_node/set_operation_mode", turtlebot_node.srv.SetTurtlebotMode)
00286       #~ try:
00287         #~ full(turtlebot_node.msg.TurtlebotSensorState.OI_MODE_FULL)
00288       #~ except rospy.ServiceException, e:
00289         #~ wx.MessageBox("Failed to put the turtlebot in full mode: service call failed with error: %s"%(e), "Error", wx.OK|wx.ICON_ERROR)
00290 #~
00291 #~
00292 #~
00293     def dashboard_callback(self, msg):
00294       wx.CallAfter(self.new_dashboard_message, msg)
00295 
00296     def new_dashboard_message(self, msg):
00297       self._dashboard_message = msg
00298       self._last_dashboard_message_time = rospy.get_time()
00299 
00300       battery_status = {}
00301       laptop_battery_status = {}
00302       breaker_status = {}
00303       wifi_status = {}
00304       cpu0_status = {}
00305       cpu1_status = {}
00306       mem_status = {}
00307       main_power_status = {}
00308       op_mode = None
00309       for status in msg.status:
00310           if status.name == "/Power System/Battery":
00311               for value in status.values:
00312                   battery_status[value.key] = value.value
00313           if status.name == "/Power System/Laptop Battery":
00314               for value in status.values:
00315                   laptop_battery_status[value.key] = value.value
00316               if status.message == "Stale":
00317                   laptop_battery_status = {}
00318           if status.name == "/Mode/Operating Mode":
00319               op_mode = status.message
00320           if status.name == "/Digital IO/Digital Outputs":
00321               for value in status.values:
00322                   breaker_status[value.key] = value.value
00323           if status.name == "/Network/%s" % self.wlan_interface:
00324               for value in status.values:
00325                   wifi_status[value.key] = value.value
00326           if status.name == "/System/cpu0":
00327               for value in status.values:
00328                   cpu0_status[value.key] = value.value
00329           if status.name == "/System/cpu1":
00330               for value in status.values:
00331                   cpu1_status[value.key] = value.value
00332           if status.name == "/System/Memory":
00333               for value in status.values:
00334                   mem_status[value.key] = value.value
00335           if status.name == "/Robot/Main Battery":
00336               for value in status.values:
00337                   main_power_status[value.key] = value.value
00338 
00339       #~ if (battery_status):
00340         #~ self._power_state_ctrl.set_power_state(battery_status)
00341       #~ else:
00342         #~ self._power_state_ctrl.set_stale()
00343 
00344       if (laptop_battery_status):
00345         self._power_state_ctrl_laptop.set_power_state(laptop_battery_status)
00346       else:
00347         self._power_state_ctrl_laptop.set_stale()
00348         
00349       if (cpu0_status):
00350         self._cpu0_state.set_state(cpu0_status)
00351       
00352       if (cpu1_status):
00353         self._cpu1_state.set_state(cpu1_status)
00354 
00355       if (mem_status):
00356         self._mem_state.set_state(mem_status)
00357         
00358       if (main_power_status):
00359         self._main_power_ctrl.set_power_state(main_power_status)
00360                 
00361       if (wifi_status):
00362         self._wifi_state.set_wifi_state(wifi_status)
00363       else:
00364         self._wifi_state.set_stale()
00365 
00366       #~ if (op_mode):
00367         #~ if (op_mode=='Full'):
00368           #~ if (self._motors_button.set_ok()):
00369               #~ self._motors_button.SetToolTip(wx.ToolTip("Mode: Full"))
00370         #~ elif(op_mode=='Safe'):
00371           #~ if (self._motors_button.set_warn()):
00372               #~ self._motors_button.SetToolTip(wx.ToolTip("Mode: Safe"))
00373         #~ elif(op_mode=='Passive'):
00374           #~ if (self._motors_button.set_error()):
00375               #~ self._motors_button.SetToolTip(wx.ToolTip("Mode: Passive"))
00376       #~ else:
00377           #~ if (self._motors_button.set_stale()):
00378               #~ self._motors_button.SetToolTip(wx.ToolTip("Mode: Stale"))
00379 
00380       #~ if (breaker_status):
00381           #~ [ctrl.set_breaker_state(breaker_status) for ctrl in self._breaker_ctrls]
00382 
00383 
00384     def update_rosout(self):
00385         summary_dur = 30.0
00386         #if (rospy.get_time() < 30.0):
00387         #    summary_dur = rospy.get_time() - 1.0
00388 
00389         #if (summary_dur < 0):
00390         #    summary_dur = 0.0
00391 
00392         summary = self._rosout_frame.get_panel().getMessageSummary(summary_dur)
00393 
00394         if (summary.fatal or summary.error):
00395             self._rosout_button.set_error()
00396         elif (summary.warn):
00397             self._rosout_button.set_warn()
00398         else:
00399             self._rosout_button.set_ok()
00400 
00401         tooltip = ""
00402         if (summary.fatal):
00403             tooltip += "\nFatal: %s"%(summary.fatal)
00404         if (summary.error):
00405             tooltip += "\nError: %s"%(summary.error)
00406         if (summary.warn):
00407             tooltip += "\nWarn: %s"%(summary.warn)
00408         if (summary.info):
00409             tooltip += "\nInfo: %s"%(summary.info)
00410         if (summary.debug):
00411             tooltip += "\nDebug: %s"%(summary.debug)
00412         
00413         if (len(tooltip) == 0):
00414             tooltip = "Rosout: no recent activity"
00415         else:
00416             tooltip = "Rosout: recent activity:" + tooltip
00417         
00418         if (tooltip != self._rosout_button.GetToolTip().GetTip()):
00419             self._rosout_button.SetToolTip(wx.ToolTip(tooltip))
00420 
00421 
00422 
00423     def load_config(self):
00424       # Load our window options
00425       (x, y) = self.GetPositionTuple()
00426       (width, height) = self.GetSizeTuple()
00427       if (self._config.HasEntry(self._CONFIG_WINDOW_X)):
00428           x = self._config.ReadInt(self._CONFIG_WINDOW_X)
00429       if (self._config.HasEntry(self._CONFIG_WINDOW_Y)):
00430           y = self._config.ReadInt(self._CONFIG_WINDOW_Y)
00431 
00432       self.SetPosition((x, y))
00433       self.SetSize((width, height))
00434 
00435 
00436 
00437     def save_config(self):
00438       config = self._config
00439 
00440       (x, y) = self.GetPositionTuple()
00441       (width, height) = self.GetSizeTuple()
00442       config.WriteInt(self._CONFIG_WINDOW_X, x)
00443       config.WriteInt(self._CONFIG_WINDOW_Y, y)
00444 
00445       config.Flush()
00446 
00447     def on_close(self, event):
00448       self.save_config()
00449 
00450       self.Destroy()
00451 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


elektron_dashboard
Author(s): Maciej StefaƄczyk
autogenerated on Thu Nov 14 2013 11:57:53