topic_message_view.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 import roslib.packages
00034 
00035 import wx
00036 
00037 from rxbag import bag_helper
00038 from message_view import MessageView
00039 
00040 class TopicMessageView(MessageView):
00041     """
00042     A message view with a toolbar for navigating messages in a single topic.
00043     """
00044     def __init__(self, timeline, parent):
00045         MessageView.__init__(self, timeline)
00046         
00047         self._parent = parent
00048         self._topic  = None
00049         self._stamp  = None
00050 
00051         self._toolbar = self.parent.CreateToolBar()
00052         self._setup_toolbar()
00053 
00054         self.parent.StatusBar = TopicMessageViewStatusBar(self.parent, self)
00055         
00056         self.parent.Bind(wx.EVT_CLOSE, self._on_close)
00057 
00058     @property
00059     def parent(self): return self._parent
00060 
00061     @property
00062     def topic(self): return self._topic
00063 
00064     @property
00065     def stamp(self): return self._stamp
00066 
00067     ## MessageView implementation
00068 
00069     def message_viewed(self, bag, msg_details):
00070         self._topic, _, self._stamp = msg_details[:3]
00071         
00072         wx.CallAfter(self.parent.StatusBar.update)
00073 
00074     ## Events
00075 
00076     def _on_close(self, event):
00077         # @todo: needs to handle closing when a message hasn't been viewed yet
00078         if self._topic:
00079             self.timeline.remove_view(self._topic, self)
00080 
00081         event.Skip()
00082 
00083     def navigate_first(self):
00084         if not self.topic:
00085             return
00086 
00087         for entry in self.timeline.get_entries(self._topic, *self.timeline.play_region):
00088             self.timeline.playhead = entry.time
00089             break
00090 
00091     def navigate_previous(self):
00092         if not self.topic:
00093             return
00094 
00095         last_entry = None
00096         for entry in self.timeline.get_entries(self._topic, self.timeline.start_stamp, self.timeline.playhead):
00097             if entry.time < self.timeline.playhead:
00098                 last_entry = entry
00099             
00100         if last_entry:
00101             self.timeline.playhead = last_entry.time
00102 
00103     def navigate_next(self):
00104         if not self.topic:
00105             return
00106 
00107         for entry in self.timeline.get_entries(self._topic, self.timeline.playhead, self.timeline.end_stamp):
00108             if entry.time > self.timeline.playhead:
00109                 self.timeline.playhead = entry.time
00110                 break
00111 
00112     def navigate_last(self):
00113         if not self.topic:
00114             return
00115 
00116         last_entry = None
00117         for entry in self.timeline.get_entries(self._topic, *self.timeline.play_region):
00118             last_entry = entry
00119 
00120         if last_entry:
00121             self.timeline.playhead = last_entry.time
00122 
00123     def _setup_toolbar(self):
00124         self._toolbar.ClearTools()
00125         
00126         icons_dir = roslib.packages.get_pkg_dir('rxbag') + '/icons/'
00127 
00128         navigate_first_tool    = self._toolbar.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'navigate_first.png'),    shortHelp='First message',    longHelp='Move playhead to first message on topic')
00129         navigate_previous_tool = self._toolbar.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'navigate_previous.png'), shortHelp='Previous message', longHelp='Move playhead to previous message on topic')
00130         navigate_next_tool     = self._toolbar.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'navigate_next.png'),     shortHelp='Next message',     longHelp='Move playhead to next message on topic')
00131         navigate_last_tool     = self._toolbar.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'navigate_last.png'),     shortHelp='Last message',     longHelp='Move playhead to last message on topic')
00132 
00133         self._toolbar.Bind(wx.EVT_TOOL, lambda e: self.navigate_first(),    navigate_first_tool)
00134         self._toolbar.Bind(wx.EVT_TOOL, lambda e: self.navigate_previous(), navigate_previous_tool)
00135         self._toolbar.Bind(wx.EVT_TOOL, lambda e: self.navigate_next(),     navigate_next_tool)
00136         self._toolbar.Bind(wx.EVT_TOOL, lambda e: self.navigate_last(),     navigate_last_tool)
00137 
00138         self._toolbar.Realize()
00139 
00140 class TopicMessageViewStatusBar(wx.StatusBar):
00141     def __init__(self, parent, message_view):
00142         wx.StatusBar.__init__(self, parent, -1)
00143 
00144         self.message_view = message_view
00145 
00146         self.timestamp_field      = 1
00147         self.human_readable_field = 2
00148         self.elapsed_field        = 3
00149 
00150         self.timestamp_width      = 125
00151         self.human_readable_width = 180
00152         self.elapsed_width        = 110
00153 
00154         self.SetFieldsCount(4)
00155 
00156         parent.Bind(wx.EVT_SIZE, self.on_size)
00157 
00158         self.update()
00159 
00160     def on_size(self, event):
00161         main_width = max(10, self.Size[0] - (self.timestamp_width + self.human_readable_width + self.elapsed_width))
00162         self.SetStatusWidths([main_width, self.timestamp_width, self.human_readable_width, self.elapsed_width])
00163         event.Skip()
00164 
00165     def update(self):
00166         if self.message_view.stamp is None or self.message_view.timeline.start_stamp is None:
00167             return
00168 
00169         # Raw timestamp
00170         self.SetStatusText('%d.%s' % (self.message_view.stamp.secs, str(self.message_view.stamp.nsecs)[:3]), self.timestamp_field)
00171 
00172         # Human-readable time
00173         self.SetStatusText(bag_helper.stamp_to_str(self.message_view.stamp), self.human_readable_field)
00174 
00175         # Elapsed time (in seconds)
00176         self.SetStatusText('%.3fs' % (self.message_view.stamp - self.message_view.timeline.start_stamp).to_sec(), self.elapsed_field)


rxbag
Author(s): Tim Field
autogenerated on Mon Oct 6 2014 07:26:07