viewer.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Copyright (c) 2010, Willow Garage, Inc.
00003 # All rights reserved.
00004 # 
00005 # Redistribution and use in source and binary forms, with or without
00006 # modification, are permitted provided that the following conditions are met:
00007 # 
00008 #     * Redistributions of source code must retain the above copyright
00009 #       notice, this list of conditions and the following disclaimer.
00010 #     * Redistributions in binary form must reproduce the above copyright
00011 #       notice, this list of conditions and the following disclaimer in the
00012 #       documentation and/or other materials provided with the distribution.
00013 #     * Neither the name of the Willow Garage, Inc. nor the names of its
00014 #       contributors may be used to endorse or promote products derived from
00015 #       this software without specific prior written permission.
00016 # 
00017 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027 # POSSIBILITY OF SUCH DAMAGE.
00028 #
00029 # Author: Jonathan Bohren 
00030 
00031 import rospy
00032 
00033 import sys
00034 import xdot
00035 import wx
00036 
00037 DOTCODE= """digraph G {
00038   rankdir=LR;
00039   _included_talker [label="/included/talker"];
00040   _included_wg2_talker [label="/included/wg2/talker"];
00041   _included2_talker [label="/included2/talker"];
00042   _included2_listener [label="/included2/listener"];
00043   _included_wg2_listener [label="/included/wg2/listener"];
00044   _rosout [label="/rosout"];
00045   _included_listener [label="/included/listener"];
00046   _wg_listener [label="/wg/listener"];
00047   _wg_talker2 [label="/wg/talker2"];
00048   _wg_talker1 [label="/wg/talker1"];
00049   _included2_wg2_talker [label="/included2/wg2/talker"];
00050   _included2_wg2_listener [label="/included2/wg2/listener"];
00051     _wg_talker1->_rosout [label="/rosout"]
00052     _included2_wg2_listener->_rosout [label="/rosout"]
00053     _wg_talker2->_wg_listener [label="/wg/hello"]
00054     _wg_talker2->_rosout [label="/rosout"]
00055     _included2_wg2_talker->_included2_wg2_listener [label="/included2/wg2/chatter"]
00056     _included2_listener->_rosout [label="/rosout"]
00057     _included_wg2_listener->_rosout [label="/rosout"]
00058     _wg_talker1->_wg_listener [label="/wg/hello"]
00059     _included2_talker->_included2_listener [label="/included2/chatter"]
00060     _wg_listener->_rosout [label="/rosout"]
00061     _included_wg2_talker->_included_wg2_listener [label="/included/wg2/chatter"]
00062     _included_talker->_included_listener [label="/included/chatter"]
00063     _included_wg2_talker->_rosout [label="/rosout"]
00064     _included2_talker->_rosout [label="/rosout"]
00065     _included2_wg2_talker->_rosout [label="/rosout"]
00066     _included_talker->_rosout [label="/rosout"]
00067     _included_listener->_rosout [label="/rosout"]}
00068 """
00069 
00070 class RxGraphViewerFrame(wx.Frame):
00071   def __init__(self):
00072     wx.Frame.__init__(self, None, -1, "rxgraph", size=(720,480))
00073 
00074     # TODO: convert to read-only property
00075     self.ns_filter = None
00076     self.quiet = False
00077     self.topic_boxes = False
00078     
00079     self._needs_refresh = False
00080     self._new_info_text = None
00081 
00082     # setup UI
00083     vbox = wx.BoxSizer(wx.VERTICAL)
00084     
00085     # Create Splitter
00086     self.content_splitter = wx.SplitterWindow(self, -1,style = wx.SP_LIVE_UPDATE)
00087     self.content_splitter.SetMinimumPaneSize(24)
00088     self.content_splitter.SetSashGravity(0.85)
00089 
00090     # Create viewer pane
00091     viewer = wx.Panel(self.content_splitter,-1)
00092 
00093     # Setup the graph panel
00094     graph_view = wx.Panel(viewer, -1)
00095     gv_vbox = wx.BoxSizer(wx.VERTICAL)
00096     graph_view.SetSizer(gv_vbox)
00097 
00098     viewer_box = wx.BoxSizer()
00099     viewer_box.Add(graph_view,1,wx.EXPAND | wx.ALL, 4)
00100     viewer.SetSizer(viewer_box)
00101     
00102     # Construct toolbar
00103     toolbar = wx.ToolBar(graph_view, -1)
00104 
00105     toolbar.AddControl(wx.StaticText(toolbar,-1,"Path: "))
00106 
00107     self._ns_combo = wx.ComboBox(toolbar, -1, style=wx.CB_DROPDOWN)
00108     self._ns_combo .Bind(wx.EVT_COMBOBOX, self._ns_combo_event)
00109     self._ns_combo.Append('/')
00110     self._ns_combo.SetValue('/')
00111     self._namespaces = ['/']
00112 
00113     # display options
00114     quiet_check = wx.CheckBox(toolbar, -1, label="Quiet")
00115     quiet_check.Bind(wx.EVT_CHECKBOX, self._quiet_check_event)
00116     topic_check = wx.CheckBox(toolbar, -1, label="All topics")
00117     topic_check.Bind(wx.EVT_CHECKBOX, self._topic_check_event)
00118     
00119     toolbar.AddControl(self._ns_combo)
00120 
00121     toolbar.AddControl(wx.StaticText(toolbar,-1,"  "))
00122     toolbar.AddControl(quiet_check)
00123     toolbar.AddControl(wx.StaticText(toolbar,-1,"  "))
00124     toolbar.AddControl(topic_check)
00125 
00126     toolbar.AddControl(wx.StaticText(toolbar,-1,"  "))
00127     toolbar.AddLabelTool(wx.ID_HELP, 'Help',
00128         wx.ArtProvider.GetBitmap(wx.ART_HELP,wx.ART_OTHER,(16,16)) )
00129     toolbar.Realize()
00130 
00131     self.Bind(wx.EVT_TOOL, self.ShowControlsDialog, id=wx.ID_HELP)
00132 
00133     # Create dot graph widget
00134     self._widget = xdot.wxxdot.WxDotWindow(graph_view, -1)
00135     self._widget.set_dotcode(DOTCODE)
00136     self._widget.zoom_to_fit()
00137 
00138     gv_vbox.Add(toolbar, 0, wx.EXPAND)
00139     gv_vbox.Add(self._widget, 1, wx.EXPAND)
00140 
00141     # Create userdata widget
00142     borders = wx.LEFT | wx.RIGHT | wx.TOP
00143     border = 4
00144     self.info_win = wx.ScrolledWindow(self.content_splitter, -1)
00145     self.info_sizer = wx.BoxSizer(wx.VERTICAL)
00146     self.info_sizer.Add(wx.StaticText(self.info_win,-1,"Info:"),0, borders, border)
00147     self.info_txt = wx.TextCtrl(self.info_win,-1,style=wx.TE_MULTILINE | wx.TE_READONLY)
00148     self.info_sizer.Add(self.info_txt,1,wx.EXPAND | borders, border)
00149     self.info_win.SetSizer(self.info_sizer)
00150 
00151     # Set content splitter
00152     self.content_splitter.SplitVertically(viewer, self.info_win, 512)
00153 
00154     vbox.Add(self.content_splitter, 1, wx.EXPAND | wx.ALL)
00155     self.SetSizer(vbox)
00156     self.Center()
00157 
00158     self.Bind(wx.EVT_IDLE,self.OnIdle)
00159 
00160   def register_select_cb(self, callback):
00161     self._widget.register_select_callback(callback)
00162 
00163   def OnIdle(self, event):
00164     if self._new_info_text is not None:
00165       self.info_txt.SetValue(self._new_info_text)
00166       self._new_info_text = None
00167     if self._needs_refresh:
00168       self.Refresh()
00169       self._needs_refresh = False
00170 
00171   def _quiet_check_event(self, event):
00172     self.quiet = event.Checked()
00173 
00174   def _topic_check_event(self, event):
00175     self.topic_boxes = event.Checked()
00176     
00177   def _ns_combo_event(self, event):
00178     self.ns_filter = self._ns_combo.GetValue()
00179     self._needs_zoom = True
00180     
00181   def set_info_text(self, text):
00182     self._new_info_text = text
00183 
00184   def update_namespaces(self, namespaces):
00185     # unfortunately this routine will not alphanumerically sort
00186     curr = self._namespaces
00187     new_filters = [n for n in namespaces if n not in curr]
00188     for f in new_filters:
00189       self._ns_combo.Append(f)
00190     curr.extend(new_filters)
00191 
00192   def ShowControlsDialog(self,event):
00193     dial = wx.MessageDialog(None,
00194         "Pan: Arrow Keys\nZoom: PageUp / PageDown\nZoom To Fit: F\n",
00195         'Keyboard Controls', wx.OK)
00196     dial.ShowModal()
00197 
00198   def set_dotcode(self, dotcode, zoom=True):
00199     if self._widget.set_dotcode(dotcode, None):
00200       self.SetTitle('rxgraph')
00201       if zoom or self._needs_zoom:
00202         self._widget.zoom_to_fit()
00203         self._needs_zoom = False
00204       self._needs_refresh = True
00205       wx.PostEvent(self.GetEventHandler(), wx.IdleEvent())
00206 
00207     


rxgraph
Author(s): Ken Conley
autogenerated on Mon Oct 6 2014 07:26:06