00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 PKG = 'rxbag'
00034 import roslib; roslib.load_manifest(PKG)
00035
00036 import wx
00037
00038 from rxbag import bag_helper
00039 from message_view import MessageView
00040
00041 class TopicMessageView(MessageView):
00042 """
00043 A message view with a toolbar for navigating messages in a single topic.
00044 """
00045 def __init__(self, timeline, parent):
00046 MessageView.__init__(self, timeline)
00047
00048 self._parent = parent
00049 self._topic = None
00050 self._stamp = None
00051
00052 self._toolbar = self.parent.CreateToolBar()
00053 self._setup_toolbar()
00054
00055 self.parent.StatusBar = TopicMessageViewStatusBar(self.parent, self)
00056
00057 self.parent.Bind(wx.EVT_CLOSE, self._on_close)
00058
00059 @property
00060 def parent(self): return self._parent
00061
00062 @property
00063 def topic(self): return self._topic
00064
00065 @property
00066 def stamp(self): return self._stamp
00067
00068
00069
00070 def message_viewed(self, bag, msg_details):
00071 self._topic, _, self._stamp = msg_details[:3]
00072
00073 wx.CallAfter(self.parent.StatusBar.update)
00074
00075
00076
00077 def _on_close(self, event):
00078
00079 if self._topic:
00080 self.timeline.remove_view(self._topic, self)
00081
00082 event.Skip()
00083
00084 def navigate_first(self):
00085 if not self.topic:
00086 return
00087
00088 for entry in self.timeline.get_entries(self._topic, *self.timeline.play_region):
00089 self.timeline.playhead = entry.time
00090 break
00091
00092 def navigate_previous(self):
00093 if not self.topic:
00094 return
00095
00096 last_entry = None
00097 for entry in self.timeline.get_entries(self._topic, self.timeline.start_stamp, self.timeline.playhead):
00098 if entry.time < self.timeline.playhead:
00099 last_entry = entry
00100
00101 if last_entry:
00102 self.timeline.playhead = last_entry.time
00103
00104 def navigate_next(self):
00105 if not self.topic:
00106 return
00107
00108 for entry in self.timeline.get_entries(self._topic, self.timeline.playhead, self.timeline.end_stamp):
00109 if entry.time > self.timeline.playhead:
00110 self.timeline.playhead = entry.time
00111 break
00112
00113 def navigate_last(self):
00114 if not self.topic:
00115 return
00116
00117 last_entry = None
00118 for entry in self.timeline.get_entries(self._topic, *self.timeline.play_region):
00119 last_entry = entry
00120
00121 if last_entry:
00122 self.timeline.playhead = last_entry.time
00123
00124 def _setup_toolbar(self):
00125 self._toolbar.ClearTools()
00126
00127 icons_dir = roslib.packages.get_pkg_dir(PKG) + '/icons/'
00128
00129 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')
00130 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')
00131 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')
00132 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')
00133
00134 self._toolbar.Bind(wx.EVT_TOOL, lambda e: self.navigate_first(), navigate_first_tool)
00135 self._toolbar.Bind(wx.EVT_TOOL, lambda e: self.navigate_previous(), navigate_previous_tool)
00136 self._toolbar.Bind(wx.EVT_TOOL, lambda e: self.navigate_next(), navigate_next_tool)
00137 self._toolbar.Bind(wx.EVT_TOOL, lambda e: self.navigate_last(), navigate_last_tool)
00138
00139 self._toolbar.Realize()
00140
00141 class TopicMessageViewStatusBar(wx.StatusBar):
00142 def __init__(self, parent, message_view):
00143 wx.StatusBar.__init__(self, parent, -1)
00144
00145 self.message_view = message_view
00146
00147 self.timestamp_field = 1
00148 self.human_readable_field = 2
00149 self.elapsed_field = 3
00150
00151 self.timestamp_width = 125
00152 self.human_readable_width = 180
00153 self.elapsed_width = 110
00154
00155 self.SetFieldsCount(4)
00156
00157 parent.Bind(wx.EVT_SIZE, self.on_size)
00158
00159 self.update()
00160
00161 def on_size(self, event):
00162 main_width = max(10, self.Size[0] - (self.timestamp_width + self.human_readable_width + self.elapsed_width))
00163 self.SetStatusWidths([main_width, self.timestamp_width, self.human_readable_width, self.elapsed_width])
00164 event.Skip()
00165
00166 def update(self):
00167 if self.message_view.stamp is None or self.message_view.timeline.start_stamp is None:
00168 return
00169
00170
00171 self.SetStatusText('%d.%s' % (self.message_view.stamp.secs, str(self.message_view.stamp.nsecs)[:3]), self.timestamp_field)
00172
00173
00174 self.SetStatusText(bag_helper.stamp_to_str(self.message_view.stamp), self.human_readable_field)
00175
00176
00177 self.SetStatusText('%.3fs' % (self.message_view.stamp - self.message_view.timeline.start_stamp).to_sec(), self.elapsed_field)