plot_configure_frame.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2009, 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 Willow Garage, Inc. 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 PKG = 'rxbag_plugins'
00034 import roslib; roslib.load_manifest(PKG)
00035 import rospy
00036 
00037 import codecs
00038 import collections
00039 import string
00040 import threading
00041 import time
00042 
00043 import numpy
00044 import wx
00045 
00046 class PlotConfigureFrame(wx.Frame):
00047     """
00048     Choose data to extract from messages.
00049     """
00050     def __init__(self, plot):
00051         wx.Frame.__init__(self, None, title=plot.parent.Title + ' - Configure', size=(600, 400))
00052 
00053         self.plot = plot
00054 
00055         splitter = wx.SplitterWindow(self)
00056         
00057         self._drag_item = None
00058 
00059         self.font = wx.Font(9, wx.FONTFAMILY_MODERN, wx.FONTSTYLE_NORMAL, wx.FONTWEIGHT_NORMAL)
00060 
00061         self.msg_tree = wx.TreeCtrl(splitter, style=wx.TR_DEFAULT_STYLE | wx.TR_HIDE_ROOT)
00062         self.add_msg_object(None, '', 'msg', self.plot._message, self.plot._message._type)
00063         self.msg_tree.Bind(wx.EVT_LEFT_DCLICK, self.on_msg_left_dclick)
00064 
00065         self.plot_tree = wx.TreeCtrl(splitter, style=wx.TR_DEFAULT_STYLE | wx.TR_HIDE_ROOT | wx.TR_HAS_BUTTONS)
00066         
00067         # Disabling dragging of messages between plots - caused weird behavior whereby top frame won't receive EVT_CLOSE after drag event is Allow'ed
00068         #self.plot_tree.Bind(wx.EVT_TREE_BEGIN_DRAG, self.on_plot_begin_drag)
00069         #self.plot_tree.Bind(wx.EVT_TREE_END_DRAG,   self.on_plot_end_drag)
00070         
00071         self.plot_tree.Bind(wx.EVT_LEFT_DCLICK,     self.on_plot_left_dclick)
00072 
00073         size = (16, 16)
00074         self.imagelist = wx.ImageList(*size)
00075         self.plot_image_index = self.imagelist.Add(wx.Bitmap(roslib.packages.get_pkg_dir(PKG) + '/icons/chart_line.png'))
00076         self.plot_tree.SetImageList(self.imagelist)
00077 
00078         splitter.SplitVertically(self.msg_tree, self.plot_tree)
00079         splitter.SashPosition    = 350
00080         splitter.MinimumPaneSize = 100
00081 
00082         self.Bind(wx.EVT_CLOSE, self.on_close)
00083 
00084         self._create_toolbar()
00085 
00086         #
00087 
00088         self.plot_root = self.plot_tree.AddRoot('Plots')
00089 
00090         self.plot_items = []
00091         if len(self.plot.plot_paths) > 0:
00092             for plot in self.plot.plot_paths:
00093                 self.plot_items.append(self.add_plot())
00094                 for path in plot:
00095                     self.plot_add_msg(path)
00096         else:
00097             self.add_plot()
00098             self.plot_tree.SelectItem(self.plot_items[0])
00099 
00100         self._update_msg_tree()
00101 
00102     def on_close(self, event):
00103         self.plot._configure_frame = None
00104         event.Skip()
00105 
00106     def _create_toolbar(self):
00107         icons_dir = roslib.packages.get_pkg_dir(PKG) + '/icons/'
00108 
00109         tb = self.CreateToolBar()
00110         tb.Bind(wx.EVT_TOOL, lambda e: self.plot_add_selected_msg(),    tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'chart_line_add.png')))
00111         tb.Bind(wx.EVT_TOOL, lambda e: self.plot_delete_selected_msg(), tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'chart_line_delete.png')))
00112         tb.Bind(wx.EVT_TOOL, lambda e: self.add_plot(),                 tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'add.png')))
00113         tb.Bind(wx.EVT_TOOL, lambda e: self.delete_plot(),              tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'delete.png')))
00114         tb.Realize()
00115 
00116     def add_msg_object(self, parent, path, name, obj, obj_type):
00117         label = name
00118         
00119         if hasattr(obj, '__slots__'):
00120             subobjs = [(slot, getattr(obj, slot)) for slot in obj.__slots__]
00121         elif type(obj) is list or type(obj) is tuple:
00122             subobjs = [('[%d]' % i, subobj) for (i, subobj) in enumerate(obj)]
00123         else:
00124             subobjs = []
00125             
00126             # Ignore any binary data
00127             obj_repr = codecs.utf_8_decode(str(obj), 'ignore')[0]
00128             
00129             # Truncate long representations
00130             if len(obj_repr) >= 50:
00131                 obj_repr = obj_repr[:50] + '...'
00132             
00133             label += ': ' + obj_repr
00134 
00135         if parent is None:
00136             item = self.msg_tree.AddRoot(label)
00137         else:
00138             item = self.msg_tree.AppendItem(parent, label)
00139 
00140         self.msg_tree.SetItemFont(item, self.font)
00141         self.msg_tree.SetItemPyData(item, (path, obj_type))
00142 
00143         if self.msg_item_is_plottable(item):
00144             self.msg_tree.SetItemTextColour(item, wx.Colour(0, 0, 0))
00145         else:
00146             self.msg_tree.SetItemTextColour(item, wx.Colour(100, 100, 100))
00147 
00148         for subobj_name, subobj in subobjs:
00149             if subobj is None:
00150                 continue
00151             
00152             if path == '':
00153                 subpath = subobj_name                       # root field
00154             elif subobj_name.startswith('['):
00155                 subpath = '%s%s' % (path, subobj_name)      # list, dict, or tuple
00156             else:
00157                 subpath = '%s.%s' % (path, subobj_name)     # attribute (prefix with '.')
00158 
00159             if hasattr(subobj, '_type'):
00160                 subobj_type = subobj._type
00161             else:
00162                 subobj_type = type(subobj).__name__
00163 
00164             self.add_msg_object(item, subpath, subobj_name, subobj, subobj_type)
00165 
00166     def msg_item_is_plottable(self, item):
00167         (path, obj_type) = self.msg_tree.GetItemPyData(item)
00168 
00169         return obj_type in ['int', 'float', 'long']
00170 
00171     ### Plots ###
00172 
00173     def on_plot_left_dclick(self, event):
00174         self.plot_delete_selected_msg()
00175 
00176     def plot_delete_selected_msg(self):
00177         selected_item = self.plot_tree.Selection
00178         if not selected_item.IsOk() or selected_item in self.plot_items:
00179             return
00180 
00181         self.plot_tree.Delete(selected_item)
00182 
00183         self._update_msg_tree()
00184 
00185     def get_plot_paths(self):
00186         items = []
00187         PlotConfigureFrame.traverse(self.plot_tree, self.plot_tree.RootItem, items.append)
00188         
00189         plot_paths = []
00190         for item in items:
00191             if item == self.plot_tree.RootItem:
00192                 continue
00193             
00194             text = str(self.plot_tree.GetItemText(item))
00195             
00196             if item in self.plot_items:
00197                 plot_paths.append([])
00198             elif len(plot_paths) > 0:
00199                 plot_paths[-1].append(text)
00200 
00201         return plot_paths
00202 
00203     def add_plot(self):
00204         item = self.plot_tree.AppendItem(self.plot_root, 'Plot')
00205         self.plot_tree.SetItemImage(item, self.plot_image_index, wx.TreeItemIcon_Normal)
00206         self.plot_items.append(item)
00207         
00208         self._update_msg_tree()
00209         
00210         self.plot_tree.SelectItem(item)
00211 
00212         return item
00213 
00214     def delete_plot(self):
00215         selected_item = self.plot_tree.Selection
00216         if not selected_item.IsOk() or selected_item not in self.plot_items:
00217             return
00218 
00219         self.plot_tree.Delete(selected_item)
00220         self.plot_items.remove(selected_item)
00221 
00222         self._update_msg_tree()
00223 
00224     ### Message ###
00225     
00226     def on_msg_left_dclick(self, event):
00227         self.plot_add_selected_msg()
00228 
00229     def plot_add_selected_msg(self):
00230         if len(self.plot_items) == 0:
00231             return
00232         selected_item = self.msg_tree.Selection
00233         if not selected_item.IsOk() or not self.msg_item_is_plottable(selected_item):
00234             return
00235 
00236         (path, obj_type) = self.msg_tree.GetItemPyData(selected_item)
00237 
00238         self.plot_add_msg(path)
00239 
00240     def plot_add_msg(self, path):
00241         selected_plot = self.plot_tree.Selection
00242         if not selected_plot.IsOk() or selected_plot == self.plot_tree.RootItem:
00243             selected_plot = self.plot_items[-1]
00244 
00245         self.plot_tree.AppendItem(selected_plot, path)
00246         self.plot_tree.ExpandAll()
00247 
00248         self._update_msg_tree()
00249 
00250     def _update_msg_tree(self):
00251         plot_paths = self.get_plot_paths()
00252         
00253         if plot_paths != self.plot.plot_paths:
00254             self.plot.plot_paths = plot_paths
00255 
00256         PlotConfigureFrame.traverse(self.msg_tree, self.msg_tree.RootItem, self._update_msg_tree_item)
00257 
00258     def _update_msg_tree_item(self, item):
00259         (path, obj_type) = self.msg_tree.GetItemPyData(item)
00260 
00261         plotted = False
00262         for paths in self.plot.plot_paths:
00263             if path in paths:
00264                 plotted = True
00265                 break
00266 
00267         self.msg_tree.SetItemBold(item, plotted)
00268 
00269     def on_plot_begin_drag(self, event):
00270         if not self.plot_tree.ItemHasChildren(event.Item):
00271             self._drag_item = event.Item
00272             event.Allow()
00273 
00274     def on_plot_end_drag(self, event):
00275         dest = event.Item
00276 
00277         src = self._drag_item
00278 
00279         if src is None or dest == src:
00280             return
00281 
00282         text = self.plot_tree.GetItemText(src)
00283         data = self.plot_tree.GetItemPyData(src)
00284 
00285         self.plot_tree.Delete(src)
00286 
00287         if dest.IsOk():
00288             is_plot_item = (self.plot_tree.GetItemParent(dest) == self.plot_tree.RootItem) 
00289             if is_plot_item:
00290                 new_item = self.plot_tree.InsertItemBefore(dest, 0, text)
00291             else:
00292                 parent = self.plot_tree.GetItemParent(dest)
00293                 if not parent.IsOk():
00294                     return
00295                 new_item = self.plot_tree.InsertItem(parent, dest, text)
00296 
00297             self.plot_tree.SetItemPyData(new_item, data)
00298 
00299         self.plot_tree.ExpandAll()
00300 
00301         self._update_msg_tree()
00302 
00303     @staticmethod
00304     def traverse(tree, root, function):
00305         if tree.ItemHasChildren(root):
00306             first_child = tree.GetFirstChild(root)[0]
00307             function(first_child)
00308             PlotConfigureFrame.traverse(tree, first_child, function)
00309 
00310         child = tree.GetNextSibling(root)
00311         if child:
00312             function(child)
00313             PlotConfigureFrame.traverse(tree, child, function)


rxbag_plugins
Author(s): Tim Field
autogenerated on Mon Jan 6 2014 11:54:21