timeline.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 """
00034 The rxbag timeline control.
00035 """
00036 
00037 import rospy
00038 
00039 import rosbag
00040 
00041 import bisect
00042 import collections
00043 import math
00044 import os
00045 import sys
00046 import threading
00047 import time
00048 
00049 import cairo
00050 import wx
00051 
00052 import bag_helper
00053 import plugins
00054 from player              import Player
00055 from raw_view            import RawView
00056 from recorder            import Recorder
00057 from timeline_popup_menu import TimelinePopupMenu
00058 from timeline_status_bar import TimelineStatusBar, PlayheadChangedEvent, EVT_PLAYHEAD_CHANGED
00059 from timeline_toolbar    import TimelineToolBar
00060 
00061 class _SelectionMode(object):
00062     NONE        = 'none'          # no region marked or started
00063     LEFT_MARKED = 'left marked'   # one end of the region has been marked
00064     MARKED      = 'marked'        # region has been marked
00065     SHIFTING    = 'shifting'      # region is marked; now shifting
00066     MOVE_LEFT   = 'move left'     # region is marked; changing the left mark
00067     MOVE_RIGHT  = 'move right'    # region is marked; changing the right mark
00068 
00069 class Timeline(wx.Window):
00070     def __init__(self, *args, **kwargs):
00071         wx.Window.__init__(self, *args, **kwargs)
00072 
00073         ## Rendering parameters
00074 
00075         self._sec_divisions = [0.001, 0.005, 0.01, 0.05, 0.1, 0.5,                                 # 1ms, 5ms, 10ms, 50ms, 100ms, 500ms
00076                                1, 5, 15, 30,                                                       # 1s, 5s, 15s, 30s
00077                                1 * 60, 2 * 60, 5 * 60, 10 * 60, 15 * 60, 30 * 60,                  # 1m, 2m, 5m, 10m, 15m, 30m
00078                                1 * 60 * 60, 2 * 60 * 60, 3 * 60 * 60, 6 * 60 * 60, 12 * 60 * 60,   # 1h, 2h, 3h, 6h, 12h
00079                                1 * 60 * 60 * 24, 7 * 60 * 60 * 24]                                 # 1d, 7d
00080         self._minor_spacing = 15
00081         self._major_spacing = 50
00082 
00083         self._time_font_size   = 12.0
00084         self._topic_font_size  = 12.0
00085         self._topic_font_color = (0, 0, 0)
00086 
00087         self._playhead_pointer_size = (6, 6)                # size of playhead pointer
00088         self._playhead_line_width   = 1                     # width of line of playhead
00089         self._playhead_color        = (1, 0, 0, 0.75)       # color of playhead
00090 
00091         self._time_font_height          = None
00092         self._topic_font_height         = None
00093         self._topic_name_sizes          = None
00094         self._topic_name_spacing        = 3                 # minimum pixels between end of topic name and start of history
00095         self._margin_left               = 4
00096         self._margin_right              = 8
00097         self._margin_bottom             = 6
00098         self._history_top               = 30
00099         self._topic_vertical_padding    = 4
00100 
00101         self._bag_end_color             = (0, 0, 0, 0.1)    # color of background of timeline before first message and after last
00102         
00103         self._time_tick_height          = 5
00104 
00105         self._minor_divisions_color_tick   = (0.5, 0.5, 0.5, 0.5)     # color of vertical line above timeline for minor division
00106         self._minor_divisions_color        = (0.6, 0.6, 0.6, 0.5)     # color of vertical line for minor division
00107         self._minor_divisions_dash         = [2, 2]                   # dash pattern for minor division
00108         self._major_divisions_label_indent = 3                        # padding in px between line and label
00109         self._major_divisions_label_color  = (0, 0, 0)                # color of label for major division
00110         self._major_divisions_color        = (0.25, 0.25, 0.25, 0.7)  # color of vertical line for major division
00111         self._major_divisions_dash         = [2, 2]                   # dash pattern for major division
00112 
00113         self._history_background_color_alternate = (0.7, 0.7, 0.7, 0.1)
00114         self._history_background_color           = (0.8, 0.8, 0.8, 0.4)
00115 
00116         self._selected_region_color              = (0.0, 0.7, 0.0, 0.08)
00117         self._selected_region_outline_top_color  = (0.0, 0.3, 0.0, 0.2)
00118         self._selected_region_outline_ends_color = (0.0, 0.3, 0.0, 0.4)
00119 
00120         # Time ticks
00121 
00122         self._default_datatype_color = (0.0, 0.0, 0.4, 0.8)
00123         self._datatype_colors = {
00124             'sensor_msgs/CameraInfo':            (  0,   0, 0.6, 0.8),
00125             'sensor_msgs/Image':                 (  0, 0.3, 0.3, 0.8),
00126             'sensor_msgs/LaserScan':             (0.6,   0,   0, 0.8),
00127             'pr2_msgs/LaserScannerSignal':       (0.6,   0,   0, 0.8),
00128             'pr2_mechanism_msgs/MechanismState': (  0, 0.6,   0, 0.8),
00129             'tf/tfMessage':                      (  0, 0.6,   0, 0.8),
00130         }
00131 
00132         self._default_msg_combine_px    = 1.0
00133         self._active_message_line_width = 3
00134         
00135         ##
00136 
00137         # Zoom
00138 
00139         self._zoom_sensitivity = 0.005
00140         self._min_zoom_speed   = 0.5
00141         self._max_zoom_speed   = 2.0
00142         self._min_zoom         = 0.0001      # max zoom out (in px/s)
00143         self._max_zoom         = 50000.0     # max zoom in  (in px/s)
00144 
00145         # Playhead
00146 
00147         self._max_play_speed = 1024.0          # fastest X play speed
00148         self._min_play_speed = 1.0 / 1024.0    # slowest X play speed
00149 
00150         self._viewer_types       = {}
00151         self._timeline_renderers = {}
00152         self._rendered_topics    = set()
00153 
00154         self.load_plugins()
00155 
00156         ##
00157 
00158         self._clicked_pos = None
00159         self._dragged_pos = None
00160 
00161         self._history_left   = 0
00162         self._history_width  = 0
00163         self._history_bottom = 0
00164         self._history_bounds = {}
00165         
00166         self._selecting_mode = _SelectionMode.NONE
00167         self._selected_left  = None
00168         self._selected_right = None
00169         
00170         self._selection_handle_width = 3.0
00171 
00172         ##
00173 
00174         self._bag_lock = threading.RLock()
00175         self._bags     = []
00176 
00177         self._loading_filename = None
00178 
00179         self._start_stamp        = None
00180         self._end_stamp          = None
00181         self._topics             = []
00182         self._topics_by_datatype = {}
00183 
00184         self._stamp_left  = None      # earliest visible timestamp on the timeline
00185         self._stamp_right = None      # latest visible timestamp on the timeline
00186         
00187         self._playhead_lock = threading.RLock()
00188         self._playhead      = None                   # timestamp of the playhead
00189 
00190         self._paused        = False
00191         self._play_speed    = 0.0
00192         self._play_all      = False
00193         
00194         self._playhead_positions_cvs   = {}
00195         self._playhead_positions       = {}                  # topic -> (bag, position)
00196         self._message_loaders          = {}
00197         self._messages_cvs             = {}
00198         self._messages                 = {}                  # topic -> (bag, msg_data)
00199         self._message_listener_threads = {}                  # listener -> MessageListenerThread
00200 
00201         self.background_task        = None
00202         self.background_task_cancel = False
00203 
00204         self._views = []
00205 
00206         self._listeners = {}
00207 
00208         self.index_cache_cv     = threading.Condition()
00209         self.index_cache        = {}
00210         self.invalidated_caches = set()
00211 
00212         self._recorder = None
00213         self._player   = False
00214 
00215         ## Playing
00216         
00217         self.last_frame       = None
00218         self.last_playhead    = None
00219         self.desired_playhead = None
00220         self.wrap             = True       # should the playhead wrap when it reaches the end?
00221         self.stick_to_end     = False      # should the playhead stick to the end?
00222 
00223         ##
00224 
00225         self._index_cache_thread = IndexCacheThread(self)
00226 
00227         # Trap SIGINT and close wx app
00228         def sigint_handler(signum, frame):
00229             self._close()
00230             wx.GetApp().Exit()
00231         import signal
00232         signal.signal(signal.SIGINT, sigint_handler)
00233 
00234         self.frame.Bind(wx.EVT_CLOSE, self.on_close)
00235 
00236         self.Parent.Bind(wx.EVT_SIZE, self.on_size)
00237 
00238         self.Bind(wx.EVT_IDLE,        self.on_idle)
00239         self.Bind(wx.EVT_PAINT,       self.on_paint)
00240         self.Bind(wx.EVT_KEY_DOWN,    self.on_key_down)
00241         self.Bind(wx.EVT_LEFT_DOWN,   self.on_left_down)
00242         self.Bind(wx.EVT_MIDDLE_DOWN, self.on_middle_down)
00243         self.Bind(wx.EVT_RIGHT_DOWN,  self.on_right_down)
00244         self.Bind(wx.EVT_LEFT_UP,     self.on_left_up)
00245         self.Bind(wx.EVT_MIDDLE_UP,   self.on_middle_up)
00246         self.Bind(wx.EVT_RIGHT_UP,    self.on_right_up)
00247         self.Bind(wx.EVT_MOTION,      self.on_mouse_move)
00248         self.Bind(wx.EVT_MOUSEWHEEL,  self.on_mousewheel)
00249         ##
00250         
00251         self._update_title()
00252 
00253         self.frame.ToolBar   = TimelineToolBar  (self.frame, self)
00254         self.frame.StatusBar = TimelineStatusBar(self.frame, self)
00255 
00256     ###
00257 
00258     # property: play_all
00259 
00260     def _get_play_all(self): return self._play_all
00261 
00262     def _set_play_all(self, play_all):
00263         if play_all == self._play_all:
00264             return
00265     
00266         self._play_all = not self._play_all
00267 
00268         self.last_frame       = None
00269         self.last_playhead    = None
00270         self.desired_playhead = None
00271 
00272     play_all = property(_get_play_all, _set_play_all)
00273 
00274     def toggle_play_all(self):
00275         self.play_all = not self.play_all
00276 
00277     @property
00278     def has_selected_region(self): return self._selected_left is not None and self._selected_right is not None
00279 
00280     @property
00281     def play_region(self):
00282         if self.has_selected_region:
00283             return (rospy.Time.from_sec(self._selected_left), rospy.Time.from_sec(self._selected_right))
00284         else:
00285             return (self.start_stamp, self.end_stamp)
00286 
00287     @property
00288     def frame(self): return wx.GetApp().GetTopWindow()
00289 
00290     # property: loading_filename
00291 
00292     def _get_loading_filename(self): return self._loading_filename
00293     
00294     def _set_loading_filename(self, loading_filename):
00295         self._loading_filename = loading_filename
00296         wx.CallAfter(self._update_title)
00297 
00298     loading_filename = property(_get_loading_filename, _set_loading_filename)
00299 
00300     ## Visual
00301 
00302     @property
00303     def history_left(self): return self._history_left
00304 
00305     @property
00306     def history_top(self): return self._history_top
00307 
00308     @property
00309     def history_bottom(self): return self._history_bottom
00310 
00311     @property
00312     def history_height(self): return self._history_bottom - self._history_top
00313 
00314     @property
00315     def history_right(self): return self._history_left + self._history_width
00316 
00317     ##
00318     
00319     @property
00320     def selected_left(self): return self._selected_left
00321 
00322     @property
00323     def selected_right(self): return self._selected_right
00324 
00325     # property: selecting_mode
00326     
00327     def _get_selecting_mode(self): return self._selecting_mode
00328     
00329     def _set_selecting_mode(self, selecting_mode): self._selecting_mode = selecting_mode
00330 
00331     selecting_mode = property(_get_selecting_mode, _set_selecting_mode)
00332 
00333     ##
00334 
00335     def _close(self):
00336         if self.background_task is not None:
00337             self.background_task_cancel = True
00338 
00339         for renderer in self._timeline_renderers.values(): 
00340             renderer.close()
00341 
00342         self._index_cache_thread.stop()
00343 
00344         if self._player:
00345             self._player.stop()
00346 
00347         if self._recorder:
00348             self._recorder.stop()
00349 
00350     ### Bags
00351 
00352     @property
00353     def bags(self): return self._bags
00354 
00355     def add_bag(self, bag):
00356         self._bags.append(bag)
00357         
00358         bag_topics = bag_helper.get_topics(bag)
00359         
00360         new_topics = set(bag_topics) - set(self._topics)
00361         for topic in new_topics:
00362             self._playhead_positions_cvs[topic] = threading.Condition()
00363             self._messages_cvs[topic]           = threading.Condition()
00364             self._message_loaders[topic]        = MessageLoader(self, topic)
00365 
00366         self._start_stamp        = self._get_start_stamp()
00367         self._end_stamp          = self._get_end_stamp()
00368         self._topics             = self._get_topics()
00369         self._topics_by_datatype = self._get_topics_by_datatype()
00370 
00371         # If this is the first bag, reset the timeline
00372         if self._stamp_left is None:
00373             self.reset_timeline()
00374 
00375         # Invalidate entire index cache for all topics in this bag
00376         with self.index_cache_cv:
00377             for topic in bag_topics:
00378                 self.invalidated_caches.add(topic)
00379                 if topic in self.index_cache:
00380                     del self.index_cache[topic]
00381 
00382             self.index_cache_cv.notify()
00383 
00384         wx.CallAfter(self.frame.ToolBar._setup)
00385         wx.CallAfter(self._update_title)
00386         wx.CallAfter(self.Refresh)
00387 
00388     ### Recording
00389 
00390     def record_bag(self, filename, all=True, topics=[], regex=False, limit=0):
00391         try:
00392             self._recorder = Recorder(filename, bag_lock=self._bag_lock, all=all, topics=topics, regex=regex, limit=limit)
00393         except Exception, ex:
00394             print >> sys.stderr, 'Error opening bag for recording [%s]: %s' % (filename, str(ex))
00395             return
00396 
00397         self._recorder.add_listener(self._message_recorded)
00398 
00399         self.add_bag(self._recorder.bag)
00400 
00401         self._recorder.start()
00402 
00403         self.wrap = False
00404         self._index_cache_thread.period = 0.1
00405 
00406         wx.CallAfter(self.frame.ToolBar._setup)  # record button has been added
00407         self._update_title()
00408 
00409     def toggle_recording(self):
00410         if self._recorder:
00411             self._recorder.toggle_paused()
00412             wx.CallAfter(self.frame.ToolBar._setup)
00413             self._update_title()
00414 
00415     ### Copy messages to...
00416 
00417     def start_background_task(self, background_task):
00418         if self.background_task is not None:
00419             dialog = wx.MessageDialog(None, 'Background operation already running:\n\n%s' % self.background_task, 'Exclamation', wx.OK | wx.ICON_EXCLAMATION)
00420             dialog.ShowModal()
00421             return False
00422 
00423         self.background_task        = background_task
00424         self.background_task_cancel = False
00425         return True
00426 
00427     def stop_background_task(self):
00428         self.background_task = None
00429 
00430     def copy_region_to_bag(self):
00431         dialog = wx.FileDialog(self, 'Copy messages to...', wildcard='Bag files (*.bag)|*.bag', style=wx.FD_SAVE)
00432         if dialog.ShowModal() == wx.ID_OK:
00433             wx.CallAfter(self._export_region, dialog.Path, self.topics, self.play_region[0], self.play_region[1])
00434         dialog.Destroy()
00435 
00436     def _export_region(self, path, topics, start_stamp, end_stamp):
00437         if not self.start_background_task('Copying messages to "%s"' % path):
00438             return
00439 
00440         wx.CallAfter(self.frame.StatusBar.gauge.Show)
00441 
00442         bag_entries = list(self.get_entries_with_bags(topics, start_stamp, end_stamp))
00443 
00444         if self.background_task_cancel:
00445             return
00446 
00447         # Get the total number of messages to copy
00448         total_messages = len(bag_entries)
00449         
00450         # If no messages, prompt the user and return
00451         if total_messages == 0:
00452             wx.MessageDialog(None, 'No messages found', 'rxbag', wx.OK | wx.ICON_EXCLAMATION).ShowModal()
00453             wx.CallAfter(self.frame.StatusBar.gauge.Hide)
00454             return
00455         
00456         # Open the path for writing
00457         try:
00458             export_bag = rosbag.Bag(path, 'w')
00459         except Exception, ex:
00460             wx.MessageDialog(None, 'Error opening bag file [%s] for writing' % path, 'rxbag', wx.OK | wx.ICON_EXCLAMATION).ShowModal()
00461             wx.CallAfter(self.frame.StatusBar.gauge.Hide)
00462             return
00463 
00464         # Run copying in a background thread
00465         self._export_thread = threading.Thread(target=self._run_export_region, args=(export_bag, topics, start_stamp, end_stamp, bag_entries))
00466         self._export_thread.start()
00467 
00468     def _run_export_region(self, export_bag, topics, start_stamp, end_stamp, bag_entries):
00469         total_messages = len(bag_entries)
00470         
00471         update_step = max(1, total_messages / 100)
00472 
00473         message_num = 1
00474 
00475         progress = 0
00476 
00477         def update_progress(v):
00478             self.frame.StatusBar.progress = v
00479 
00480         # Write out the messages
00481         for bag, entry in bag_entries:
00482             if self.background_task_cancel:
00483                 break
00484 
00485             try:
00486                 topic, msg, t = self.read_message(bag, entry.position)
00487                 export_bag.write(topic, msg, t)
00488             except Exception, ex:
00489                 print >> sys.stderr, 'Error exporting message at position %s: %s' % (str(entry.position), str(ex))
00490 
00491             if message_num % update_step == 0 or message_num == total_messages:
00492                 new_progress = int(100.0 * (float(message_num) / total_messages))
00493                 if new_progress != progress:
00494                     progress = new_progress
00495                     if not self.background_task_cancel:
00496                         wx.CallAfter(update_progress, progress)
00497 
00498             message_num += 1
00499 
00500         # Close the bag
00501         try:
00502             export_bag.close()
00503         except Exception, ex:
00504             wx.MessageDialog(None, 'Error closing bag file [%s]: %s' % (export_bag.filename, str(ex)), 'rxbag', wx.OK | wx.ICON_EXCLAMATION).ShowModal()
00505 
00506         if not self.background_task_cancel:
00507             wx.CallAfter(self.frame.StatusBar.gauge.Hide)
00508 
00509         self.stop_background_task()
00510 
00511     ### Publishing
00512 
00513     def is_publishing(self, topic):
00514         return self._player and self._player.is_publishing(topic)
00515 
00516     def start_publishing(self, topic):
00517         if not self._player and not self._create_player():
00518             return False
00519         
00520         self._player.start_publishing(topic)
00521         return True
00522 
00523     def stop_publishing(self, topic):
00524         if not self._player:
00525             return False
00526         
00527         self._player.stop_publishing(topic)
00528         return True
00529     
00530     def _create_player(self):
00531         if not self._player:
00532             try:
00533                 self._player = Player(self)
00534             except Exception, ex:
00535                 print >> sys.stderr, 'Error starting player; aborting publish: %s' % str(ex)
00536                 return False
00537             
00538         return True
00539 
00540     ### Recording
00541 
00542     def _message_recorded(self, topic, msg, t):
00543         if self._start_stamp is None:
00544             self._start_stamp = t
00545             self._end_stamp   = t
00546             self._playhead    = t
00547         elif self._end_stamp is None or t > self._end_stamp:
00548             self._end_stamp = t
00549 
00550         if not self._topics or topic not in self._topics:
00551             self._topics             = self._get_topics()
00552             self._topics_by_datatype = self._get_topics_by_datatype()
00553 
00554             self._playhead_positions_cvs[topic] = threading.Condition()
00555             self._messages_cvs[topic]           = threading.Condition()
00556             self._message_loaders[topic]        = MessageLoader(self, topic)
00557 
00558         if self._stamp_left is None:
00559             self.reset_zoom()
00560 
00561         # Notify the index caching thread that it has work to do
00562         with self.index_cache_cv:
00563             self.invalidated_caches.add(topic)
00564             self.index_cache_cv.notify()
00565 
00566         if topic in self._listeners:
00567             for listener in self._listeners[topic]:
00568                 try:
00569                     listener.timeline_changed()
00570                 except wx.PyDeadObjectError:
00571                     self.remove_listener(topic, listener)
00572                 except Exception, ex:
00573                     print >> sys.stderr, 'Error calling timeline_changed on %s: %s' % (type(listener), str(ex))
00574 
00575     ## Timeline info
00576 
00577     @property
00578     def start_stamp(self): return self._start_stamp
00579 
00580     @property
00581     def end_stamp(self): return self._end_stamp
00582 
00583     @property
00584     def topics(self): return self._topics
00585 
00586     @property
00587     def topics_by_datatype(self): return self._topics_by_datatype
00588     
00589     def _get_start_stamp(self):
00590         with self._bag_lock:
00591             start_stamp = None
00592             for bag in self._bags:
00593                 bag_start_stamp = bag_helper.get_start_stamp(bag)
00594                 if bag_start_stamp is not None and (start_stamp is None or bag_start_stamp < start_stamp):
00595                     start_stamp = bag_start_stamp
00596             return start_stamp
00597     
00598     def _get_end_stamp(self):
00599         with self._bag_lock:
00600             end_stamp = None
00601             for bag in self._bags:
00602                 bag_end_stamp = bag_helper.get_end_stamp(bag)
00603                 if bag_end_stamp is not None and (end_stamp is None or bag_end_stamp > end_stamp):
00604                     end_stamp = bag_end_stamp
00605             return end_stamp
00606     
00607     def _get_topics(self):
00608         with self._bag_lock:
00609             topics = set()
00610             for bag in self._bags:
00611                 for topic in bag_helper.get_topics(bag):
00612                     topics.add(topic)
00613             return sorted(topics)
00614 
00615     def _get_topics_by_datatype(self):
00616         with self._bag_lock:
00617             topics_by_datatype = {}
00618             for bag in self._bags:
00619                 for datatype, topics in bag_helper.get_topics_by_datatype(bag).items():
00620                     topics_by_datatype.setdefault(datatype, []).extend(topics)
00621             return topics_by_datatype
00622 
00623     def get_datatype(self, topic):
00624         with self._bag_lock:
00625             datatype = None
00626             for bag in self._bags:
00627                 bag_datatype = bag_helper.get_datatype(bag, topic)
00628                 if datatype and bag_datatype and (bag_datatype != datatype):
00629                     raise Exception('topic %s has multiple datatypes: %s and %s' % (topic, datatype, bag_datatype))
00630                 datatype = bag_datatype
00631             return datatype
00632 
00633     def get_entries(self, topics, start_stamp, end_stamp):
00634         with self._bag_lock:
00635             from rosbag import bag
00636 
00637             bag_entries = []
00638             for b in self._bags:
00639                 bag_start_time = bag_helper.get_start_stamp(b)
00640                 if bag_start_time is not None and bag_start_time > end_stamp:
00641                     continue
00642 
00643                 bag_end_time = bag_helper.get_end_stamp(b)
00644                 if bag_end_time is not None and bag_end_time < start_stamp:
00645                     continue
00646 
00647                 connections = list(b._get_connections(topics))
00648                 bag_entries.append(b._get_entries(connections, start_stamp, end_stamp))
00649 
00650             for entry, _ in bag._mergesort(bag_entries, key=lambda entry: entry.time):
00651                 yield entry
00652 
00653     def get_entries_with_bags(self, topic, start_stamp, end_stamp):
00654         with self._bag_lock:
00655             from rosbag import bag   # for _mergesort
00656 
00657             bag_entries = []
00658             bag_by_iter = {}
00659             for b in self._bags:
00660                 bag_start_time = bag_helper.get_start_stamp(b)
00661                 if bag_start_time is not None and bag_start_time > end_stamp:
00662                     continue
00663 
00664                 bag_end_time = bag_helper.get_end_stamp(b)
00665                 if bag_end_time is not None and bag_end_time < start_stamp:
00666                     continue
00667 
00668                 connections = list(b._get_connections(topic))                
00669                 it = iter(b._get_entries(connections, start_stamp, end_stamp))
00670                 bag_by_iter[it] = b
00671                 bag_entries.append(it)
00672 
00673             for entry, it in bag._mergesort(bag_entries, key=lambda entry: entry.time):
00674                 yield bag_by_iter[it], entry
00675 
00676     def get_entry(self, t, topic):
00677         with self._bag_lock:
00678             entry_bag, entry = None, None
00679             for bag in self._bags:
00680                 bag_entry = bag._get_entry(t, bag._get_connections(topic))
00681                 if bag_entry and (not entry or bag_entry.time > entry.time):
00682                     entry_bag, entry = bag, bag_entry
00683 
00684             return entry_bag, entry
00685 
00686     def get_entry_after(self, t):
00687         with self._bag_lock:
00688             entry_bag, entry = None, None
00689             for bag in self._bags:
00690                 bag_entry = bag._get_entry_after(t, bag._get_connections())
00691                 if bag_entry and (not entry or bag_entry.time < entry.time):
00692                     entry_bag, entry = bag, bag_entry
00693 
00694             return entry_bag, entry
00695 
00696     def get_next_message_time(self):
00697         if self.playhead is None:
00698             return None
00699 
00700         _, entry = self.get_entry_after(self.playhead)
00701         if entry is None:
00702             return self.start_stamp
00703 
00704         return entry.time
00705 
00706     def read_message(self, bag, position):
00707         with self._bag_lock:
00708             return bag._read_message(position)
00709 
00710     ### Views / listeners
00711 
00712     def add_view(self, topic, view):
00713         self._views.append(view)
00714         self.add_listener(topic, view)
00715 
00716     def remove_view(self, topic, view):
00717         self.remove_listener(topic, view)
00718         self._views.remove(view)
00719 
00720         wx.CallAfter(self.Refresh)
00721         
00722     def has_listeners(self, topic): return topic in self._listeners
00723 
00724     def add_listener(self, topic, listener):
00725         self._listeners.setdefault(topic, []).append(listener)
00726         
00727         self._message_listener_threads[(topic, listener)] = MessageListenerThread(self, topic, listener)
00728 
00729         # Notify the message listeners
00730         self._message_loaders[topic].reset()
00731         with self._playhead_positions_cvs[topic]:
00732             self._playhead_positions_cvs[topic].notify_all()
00733 
00734         wx.CallAfter(self.Refresh)
00735 
00736     def remove_listener(self, topic, listener):
00737         topic_listeners = self._listeners.get(topic)
00738         if topic_listeners is not None and listener in topic_listeners:
00739             topic_listeners.remove(listener)
00740 
00741             if len(topic_listeners) == 0:
00742                 del self._listeners[topic]
00743 
00744             # Stop the message listener thread
00745             if (topic, listener) in self._message_listener_threads:
00746                 self._message_listener_threads[(topic, listener)].stop()
00747                 del self._message_listener_threads[(topic, listener)]
00748 
00749             wx.CallAfter(self.Refresh)
00750 
00751     ### Plugins
00752 
00753     def get_viewer_types(self, datatype):
00754         return [RawView] + self._viewer_types.get('*', []) + self._viewer_types.get(datatype, [])
00755     
00756     def load_plugins(self):
00757         for view, timeline_renderer, msg_types in plugins.load_plugins():
00758             for msg_type in msg_types:
00759                 self._viewer_types.setdefault(msg_type, []).append(view)
00760                 if timeline_renderer:
00761                     self._timeline_renderers[msg_type] = timeline_renderer(self)
00762 
00763     ### Timeline renderers
00764 
00765     def get_renderers(self):
00766         renderers = []
00767 
00768         for topic in self.topics:
00769             datatype = self.get_datatype(topic)
00770             renderer = self._timeline_renderers.get(datatype)
00771             if renderer is not None:
00772                 renderers.append((topic, renderer))
00773                 
00774         return renderers
00775 
00776     def is_renderer_active(self, topic):
00777         return topic in self._rendered_topics
00778 
00779     def toggle_renderers(self):
00780         idle_renderers = len(self._rendered_topics) < len(self.topics)
00781         
00782         self.set_renderers_active(idle_renderers)
00783 
00784     def set_renderers_active(self, active):
00785         if active:
00786             for topic in self.topics:
00787                 self._rendered_topics.add(topic)
00788         else:
00789             self._rendered_topics.clear()
00790 
00791         wx.CallAfter(self.frame.ToolBar._setup)
00792         wx.CallAfter(self.Refresh)
00793 
00794     def set_renderer_active(self, topic, active):
00795         if active:
00796             if topic in self._rendered_topics:
00797                 return
00798             self._rendered_topics.add(topic)
00799         else:
00800             if not topic in self._rendered_topics:
00801                 return
00802             self._rendered_topics.remove(topic)
00803 
00804         wx.CallAfter(self.frame.ToolBar._setup)
00805         wx.CallAfter(self.Refresh)
00806 
00807     ### Playhead
00808 
00809     # property: play_speed
00810 
00811     def _get_play_speed(self):
00812         if self._paused:
00813             return 0.0
00814         return self._play_speed
00815 
00816     def _set_play_speed(self, play_speed):
00817         if play_speed == self._play_speed:
00818             return
00819 
00820         if play_speed > 0.0:
00821             self._play_speed = min( self._max_play_speed, max( self._min_play_speed, play_speed))
00822         elif play_speed < 0.0:
00823             self._play_speed = max(-self._max_play_speed, min(-self._min_play_speed, play_speed))
00824         else:
00825             self._play_speed = play_speed
00826 
00827         if self._play_speed < 1.0:
00828             self.stick_to_end = False
00829 
00830         wx.CallAfter(self.frame.ToolBar._setup)
00831 
00832         wx.PostEvent(self.frame, PlayheadChangedEvent())
00833 
00834     play_speed = property(_get_play_speed, _set_play_speed)
00835 
00836     def toggle_play(self):
00837         if self._play_speed != 0.0:
00838             self.play_speed = 0.0
00839         else:
00840             self.play_speed = 1.0
00841 
00842     def navigate_play(self): self.play_speed = 1.0
00843     def navigate_stop(self): self.play_speed = 0.0
00844 
00845     def navigate_rewind(self):
00846         if self._play_speed < 0.0:
00847             new_play_speed = self._play_speed * 2.0
00848         elif self._play_speed == 0.0:
00849             new_play_speed = -1.0
00850         else:
00851             new_play_speed = self._play_speed * 0.5
00852 
00853         self.play_speed = new_play_speed
00854         
00855     def navigate_fastforward(self):
00856         if self._play_speed > 0.0:
00857             new_play_speed = self._play_speed * 2.0
00858         elif self._play_speed == 0.0:
00859             new_play_speed = 2.0
00860         else:
00861             new_play_speed = self._play_speed * 0.5
00862 
00863         self.play_speed = new_play_speed
00864 
00865     def navigate_start(self): self.playhead = self.play_region[0]
00866     def navigate_end(self):   self.playhead = self.play_region[1]
00867 
00868     ### View port
00869 
00870     def reset_timeline(self):
00871         self.reset_zoom()
00872 
00873         self._selected_left  = None
00874         self._selected_right = None
00875 
00876         if self._stamp_left is not None:
00877             self.playhead = rospy.Time.from_sec(self._stamp_left)
00878 
00879     def set_timeline_view(self, stamp_left, stamp_right):
00880         self._stamp_left  = stamp_left
00881         self._stamp_right = stamp_right
00882 
00883         wx.CallAfter(self.frame.ToolBar._setup)
00884         wx.CallAfter(self.Refresh)
00885 
00886     def translate_timeline(self, dstamp):
00887         self.set_timeline_view(self._stamp_left + dstamp, self._stamp_right + dstamp)
00888 
00889     def reset_zoom(self):
00890         start_stamp, end_stamp = self.start_stamp, self.end_stamp
00891         if start_stamp is None:
00892             return
00893         
00894         if (end_stamp - start_stamp) < rospy.Duration.from_sec(5.0):
00895             end_stamp = start_stamp + rospy.Duration.from_sec(5.0)
00896 
00897         self.set_timeline_view(start_stamp.to_sec(), end_stamp.to_sec())
00898 
00899     def zoom_in(self):  self.zoom_timeline(0.5)
00900     def zoom_out(self): self.zoom_timeline(2.0)
00901 
00902     def can_zoom_in(self):  return self.can_zoom(0.5)
00903     def can_zoom_out(self): return self.can_zoom(2.0)
00904 
00905     def can_zoom(self, desired_zoom):
00906         if not self._stamp_left or not self._playhead:
00907             return False
00908 
00909         new_interval = self.get_zoom_interval(desired_zoom)
00910         
00911         new_range   = new_interval[1] - new_interval[0]
00912         curr_range  = self._stamp_right - self._stamp_left
00913         actual_zoom = new_range / curr_range
00914 
00915         if desired_zoom < 1.0:
00916             return actual_zoom < 0.95
00917         else:
00918             return actual_zoom > 1.05
00919 
00920     def zoom_timeline(self, zoom):
00921         interval = self.get_zoom_interval(zoom)
00922         if not interval:
00923             return
00924 
00925         self._stamp_left, self._stamp_right = interval
00926 
00927         self._layout()
00928 
00929         wx.CallAfter(self.frame.ToolBar._setup)
00930         wx.CallAfter(self.Refresh)
00931 
00932     def get_zoom_interval(self, zoom):
00933         if self._stamp_left is None:
00934             return None
00935         
00936         stamp_interval     = self._stamp_right - self._stamp_left
00937         playhead_fraction  = (self._playhead.to_sec() - self._stamp_left) / stamp_interval
00938         
00939         new_stamp_interval = zoom * stamp_interval
00940         
00941         # Enforce zoom limits
00942         px_per_sec = self._history_width / new_stamp_interval
00943         if px_per_sec < self._min_zoom:
00944             new_stamp_interval = self._history_width / self._min_zoom
00945         elif px_per_sec > self._max_zoom:
00946             new_stamp_interval = self._history_width / self._max_zoom
00947 
00948         left  = self._playhead.to_sec() - playhead_fraction * new_stamp_interval
00949         right = left + new_stamp_interval
00950 
00951         return (left, right)
00952 
00953     # property: playhead
00954 
00955     def _get_playhead(self): return self._playhead
00956 
00957     def _set_playhead(self, playhead):
00958         with self._playhead_lock:
00959             if playhead == self._playhead:
00960                 return
00961 
00962             self._playhead = playhead
00963 
00964             if self._playhead != self.end_stamp:
00965                 self.stick_to_end = False
00966 
00967             playhead_secs = playhead.to_sec()
00968 
00969             if playhead_secs > self._stamp_right:
00970                 dstamp = playhead_secs - self._stamp_right + (self._stamp_right - self._stamp_left) * 0.75
00971                 if dstamp > self.end_stamp.to_sec() - self._stamp_right:
00972                     dstamp = self.end_stamp.to_sec() - self._stamp_right
00973                 self.translate_timeline(dstamp)
00974                 
00975             elif playhead_secs < self._stamp_left:
00976                 dstamp = self._stamp_left - playhead_secs + (self._stamp_right - self._stamp_left) * 0.75
00977                 if dstamp > self._stamp_left - self.start_stamp.to_sec():
00978                     dstamp = self._stamp_left - self.start_stamp.to_sec()
00979                 self.translate_timeline(-dstamp)
00980 
00981             # Update the playhead positions
00982             for topic in self.topics:
00983                 bag, entry = self.get_entry(self._playhead, topic)
00984                 if entry:
00985                     if topic in self._playhead_positions and self._playhead_positions[topic] == (bag, entry.position):
00986                         continue
00987                     new_playhead_position = (bag, entry.position)
00988                 else:
00989                     new_playhead_position = (None, None)
00990 
00991                 with self._playhead_positions_cvs[topic]:
00992                     self._playhead_positions[topic] = new_playhead_position
00993                     self._playhead_positions_cvs[topic].notify_all()           # notify all message loaders that a new message needs to be loaded
00994 
00995             wx.PostEvent(self.frame, PlayheadChangedEvent())
00996             
00997             wx.CallAfter(self.Refresh)
00998 
00999     playhead = property(_get_playhead, _set_playhead)
01000 
01001     ### Rendering
01002 
01003     def _update_title(self):
01004         title = 'rxbag'
01005 
01006         if self._recorder:
01007             if self._recorder.paused:
01008                 title += ' - %s [recording paused]' % self._bags[0].filename
01009             else:
01010                 title += ' - %s [recording]' % self._bags[0].filename
01011 
01012         elif len(self.bags) > 0:
01013             if len(self.bags) == 1:
01014                 title += ' - ' + self._bags[0].filename
01015             else:
01016                 title += ' - [%d bags]' % len(self._bags)
01017 
01018         if self._loading_filename is not None:
01019             title += ' - Loading %s...' % self._loading_filename
01020         
01021         self.frame.Title = title
01022 
01023     def on_close(self, event):
01024         if self.background_task is not None:
01025             dialog = wx.MessageDialog(None, 'Background operation running:\n\n%s\n\nQuit anyway?' % self.background_task, 'Question', wx.YES_NO | wx.NO_DEFAULT | wx.ICON_QUESTION)
01026             result = dialog.ShowModal()
01027             dialog.Destroy()
01028             if result == wx.ID_NO:
01029                 event.Veto()
01030                 return
01031 
01032         self._close()
01033 
01034         event.Skip()
01035 
01036     def on_idle(self, event):
01037         if self.play_speed != 0.0:
01038             self._step_playhead()
01039             event.RequestMore()
01040 
01041     def on_size(self, event):
01042         self.Position = (0, 0)
01043         self.Size = (self.Parent.ClientSize[0], max(self.Parent.ClientSize[1], self._history_bottom + self._playhead_pointer_size[1] + self._margin_bottom))
01044         self.Refresh()
01045 
01046     def on_paint(self, event):
01047         pdc = wx.PaintDC(self)
01048         pdc.Background = wx.WHITE_BRUSH
01049         pdc.Clear()
01050 
01051         if len(self.bags) == 0 or len(self.topics) == 0:
01052             return
01053 
01054         dc = wx.lib.wxcairo.ContextFromDC(pdc)
01055         dc.set_antialias(cairo.ANTIALIAS_NONE)
01056 
01057         self._calc_font_sizes(dc)
01058         self._layout()
01059 
01060         self._draw_topic_dividers(dc)
01061         self._draw_selected_region(dc)
01062         self._draw_time_indicators(dc)
01063         self._draw_topic_histories(dc)
01064         self._draw_bag_ends(dc)
01065         self._draw_topic_names(dc)
01066         self._draw_history_border(dc)
01067         self._draw_playhead(dc)
01068 
01069     def _calc_font_sizes(self, dc):
01070         dc.set_font_size(self._time_font_size)
01071         self._time_font_height = dc.font_extents()[2]
01072 
01073         dc.set_font_size(self._topic_font_size)
01074         self._topic_name_sizes = dict([(topic, dc.text_extents(topic)[2:4]) for topic in self.topics])
01075 
01076     def _layout(self):
01077         self._topic_font_height = max([h for (w, h) in self._topic_name_sizes.values()])
01078 
01079         # Calculate history left and history width
01080         max_topic_name_width    = max([w for (w, h) in self._topic_name_sizes.values()])
01081         new_history_left  = self._margin_left + max_topic_name_width + self._topic_name_spacing
01082         new_history_width = self.Size[0] - new_history_left - self._margin_right
01083         updated_history = (new_history_left != self._history_left or new_history_width != self._history_width)
01084         if updated_history:
01085             self._history_left  = new_history_left
01086             self._history_width = new_history_width
01087             
01088             wx.CallAfter(self.frame.ToolBar._setup)    # zoom enabled may have changed
01089 
01090         # Calculate the bounds for each topic
01091         self._history_bounds = {}
01092         y = self._history_top
01093         for topic in self.topics:
01094             datatype = self.get_datatype(topic)
01095             
01096             topic_height = None
01097             if topic in self._rendered_topics:
01098                 renderer = self._timeline_renderers.get(datatype)
01099                 if renderer:
01100                     topic_height = renderer.get_segment_height(topic)
01101             if not topic_height:
01102                 topic_height = self._topic_font_height + self._topic_vertical_padding
01103 
01104             self._history_bounds[topic] = (self._history_left, y, self._history_width, topic_height)
01105 
01106             y += topic_height
01107 
01108         new_history_bottom = max([y + h for (x, y, w, h) in self._history_bounds.values()]) - 1
01109         if new_history_bottom != self._history_bottom:
01110             self._history_bottom = new_history_bottom 
01111 
01112             # Resize the scroll bars
01113             scroll_window = self.Parent
01114             visible_height = int(self._history_bottom) + self._playhead_pointer_size[1] + self._margin_bottom
01115             scroll_window.SetScrollbars(0, 1, 0, visible_height, 0, scroll_window.Position[1])
01116 
01117             # Resize the frame to fit
01118             bar_height = 0
01119             if self.frame.ToolBar:
01120                 bar_height += self.frame.ToolBar.Size[1]
01121             if self.frame.StatusBar:
01122                 bar_height += self.frame.StatusBar.Size[1]
01123 
01124             frame = scroll_window.Parent
01125             frame.Size = (frame.Size[0], visible_height + bar_height)
01126 
01127     def _draw_topic_dividers(self, dc):
01128         clip_left  = self._history_left
01129         clip_right = self._history_left + self._history_width
01130 
01131         dc.set_line_width(1)
01132         row = 0
01133         for topic in self.topics:
01134             (x, y, w, h) = self._history_bounds[topic]
01135             
01136             left = max(clip_left, x)
01137             rect = (left, y, min(clip_right - left, w), h)
01138             if row % 2 == 0:
01139                 dc.set_source_rgba(*self._history_background_color_alternate)
01140                 dc.rectangle(*rect)
01141                 dc.fill()
01142             dc.set_source_rgba(*self._history_background_color)
01143             dc.rectangle(*rect)
01144             dc.stroke()
01145             row += 1
01146 
01147     def _draw_selected_region(self, dc):
01148         if self._selected_left is None:
01149             return
01150         
01151         x_left  = self.map_stamp_to_x(self._selected_left)
01152         if self._selected_right is not None:
01153             x_right = self.map_stamp_to_x(self._selected_right)
01154         else:
01155             x_right = self.map_stamp_to_x(self._playhead.to_sec())
01156 
01157         left   = x_left
01158         top    = self._history_top - self._playhead_pointer_size[1] - 5 - self._time_font_size - 4
01159         width  = x_right - x_left
01160         height = self._history_top - top
01161 
01162         dc.set_source_rgba(*self._selected_region_color)
01163         dc.rectangle(left, top, width, height)
01164         dc.fill()
01165 
01166         dc.set_source_rgba(*self._selected_region_outline_ends_color)
01167         dc.set_line_width(2.0)
01168         dc.move_to(left, top)
01169         dc.line_to(left, top + height)
01170         dc.move_to(left + width, top)
01171         dc.line_to(left + width, top + height)
01172         dc.stroke()
01173         
01174         dc.set_source_rgba(*self._selected_region_outline_top_color)
01175         dc.set_line_width(1.0)
01176         dc.move_to(left,         top)
01177         dc.line_to(left + width, top)
01178         dc.stroke()
01179         dc.set_line_width(2.0)
01180         dc.move_to(left, self._history_top)
01181         dc.line_to(left, self._history_bottom)
01182         dc.move_to(left + width, self._history_top)
01183         dc.line_to(left + width, self._history_bottom)
01184         dc.stroke()
01185 
01186     def _draw_time_indicators(self, dc):
01187         """
01188         Draw vertical grid-lines showing major and minor time divisions.
01189         """
01190         x_per_sec = self.map_dstamp_to_dx(1.0)
01191 
01192         major_divisions = [s for s in self._sec_divisions if x_per_sec * s >= self._major_spacing]
01193         if len(major_divisions) == 0:
01194             major_division = max(self._sec_divisions)
01195         else:
01196             major_division = min(major_divisions)
01197 
01198         minor_divisions = [s for s in self._sec_divisions if x_per_sec * s >= self._minor_spacing and major_division % s == 0]
01199         if len(minor_divisions) > 0:
01200             minor_division = min(minor_divisions)
01201         else:
01202             minor_division = None
01203 
01204         start_stamp = self.start_stamp.to_sec()
01205 
01206         major_stamps = list(self._get_stamps(start_stamp, major_division))
01207         self._draw_major_divisions(dc, major_stamps, start_stamp, major_division)
01208         if minor_division:
01209             minor_stamps = [s for s in self._get_stamps(start_stamp, minor_division) if s not in major_stamps]
01210             self._draw_minor_divisions(dc, minor_stamps, start_stamp, minor_division)
01211 
01212     def _draw_major_divisions(self, dc, stamps, start_stamp, division):
01213         dc.set_line_width(1.0)
01214         dc.set_font_size(self._time_font_size)
01215 
01216         label_y = self._history_top - self._playhead_pointer_size[1] - 5
01217 
01218         for stamp in stamps:
01219             x = self.map_stamp_to_x(stamp, False)
01220 
01221             label        = self._get_label(division, stamp - start_stamp)
01222             label_x      = x + self._major_divisions_label_indent
01223             label_extent = dc.text_extents(label)
01224             if label_x + label_extent[2] < self.Size[0] - 1:  # don't display label if it doesn't fit in the control
01225                 dc.set_source_rgb(*self._major_divisions_label_color)
01226                 dc.move_to(label_x, label_y)
01227                 dc.show_text(label)
01228 
01229             dc.set_source_rgba(*self._major_divisions_color)
01230             dc.set_dash(self._major_divisions_dash)
01231             dc.move_to(x, label_y - label_extent[3])
01232             dc.line_to(x, self._history_bottom)
01233             dc.stroke()
01234             dc.set_dash([])
01235 
01236     def _draw_minor_divisions(self, dc, stamps, start_stamp, division):
01237         xs = [self.map_stamp_to_x(stamp) for stamp in stamps]
01238 
01239         dc.set_source_rgba(*self._minor_divisions_color_tick)
01240         for x in xs:
01241             dc.move_to(x, self._history_top - self._time_tick_height)
01242             dc.line_to(x, self._history_top)
01243         dc.stroke()
01244 
01245         dc.set_dash(self._minor_divisions_dash)
01246         dc.set_source_rgba(*self._minor_divisions_color)
01247         for x in xs:
01248             dc.move_to(x, self._history_top)
01249             dc.line_to(x, self._history_bottom)
01250         dc.stroke()
01251         dc.set_dash([])
01252 
01253     def _get_stamps(self, start_stamp, stamp_step):
01254         """
01255         Generate visible stamps every stamp_step
01256         """
01257         if start_stamp >= self._stamp_left:
01258             stamp = start_stamp
01259         else:
01260             stamp = start_stamp + int((self._stamp_left - start_stamp) / stamp_step) * stamp_step + stamp_step
01261 
01262         while stamp < self._stamp_right:
01263             yield stamp
01264             stamp += stamp_step
01265 
01266     def _get_label(self, division, elapsed):
01267         secs  = int(elapsed) % 60
01268 
01269         mins  = int(elapsed) / 60
01270         hrs   = mins / 60
01271         days  = hrs / 24
01272         weeks = days / 7
01273         
01274         if division >= 7 * 24 * 60 * 60:    # >1wk divisions: show weeks
01275             return '%dw' % weeks
01276         elif division >= 24 * 60 * 60:      # >24h divisions: show days
01277             return '%dd' % days
01278         elif division >= 60 * 60:           # >1h divisions: show hours 
01279             return '%dh' % hrs
01280         elif division >= 5 * 60:            # >5m divisions: show minutes
01281             return '%dm' % mins
01282         elif division >= 1:                 # >1s divisions: show minutes:seconds
01283             return '%d:%02d' % (mins, secs)
01284         elif division >= 0.1:               # >0.1s divisions: show seconds.0
01285             return '%d.%s' % (secs, str(int(10.0 * (elapsed - int(elapsed)))))
01286         elif division >= 0.01:              # >0.1s divisions: show seconds.0
01287             return '%d.%02d' % (secs, int(100.0 * (elapsed - int(elapsed))))
01288         else:                               # show seconds.00
01289             return '%d.%03d' % (secs, int(1000.0 * (elapsed - int(elapsed))))
01290 
01291     def _draw_topic_histories(self, dc):
01292         for topic in sorted(self._history_bounds.keys()):
01293             self._draw_topic_history(dc, topic)
01294 
01295     def _update_index_cache(self, topic):
01296         """
01297         Updates the cache of message timestamps for the given topic.
01298 
01299         @return: number of messages added to the index cache
01300         """
01301         if self.start_stamp is None or self.end_stamp is None:
01302             return 0
01303         
01304         if topic not in self.index_cache:
01305             # Don't have any cache of messages in this topic
01306             start_time = self.start_stamp
01307             topic_cache = []
01308             self.index_cache[topic] = topic_cache
01309         else:
01310             topic_cache = self.index_cache[topic]               
01311 
01312             # Check if the cache has been invalidated
01313             if topic not in self.invalidated_caches:
01314                 return 0
01315 
01316             if len(topic_cache) == 0:
01317                 start_time = self.start_stamp
01318             else:
01319                 start_time = rospy.Time.from_sec(max(0.0, topic_cache[-1]))
01320 
01321         end_time = self.end_stamp
01322 
01323         topic_cache_len = len(topic_cache)
01324 
01325         for entry in self.get_entries(topic, start_time, end_time):
01326             topic_cache.append(entry.time.to_sec())
01327 
01328         if topic in self.invalidated_caches:
01329             self.invalidated_caches.remove(topic)
01330 
01331         return len(topic_cache) - topic_cache_len
01332 
01333     def _draw_topic_history(self, dc, topic):
01334         """
01335         Draw boxes to show message regions on timelines.
01336         """
01337         
01338         x, y, w, h = self._history_bounds[topic]
01339         
01340         msg_y      = y + 1
01341         msg_height = h - 1
01342 
01343         datatype = self.get_datatype(topic)
01344 
01345         # Get the renderer and the message combine interval
01346         renderer = None
01347         msg_combine_interval = None
01348         if topic in self._rendered_topics:
01349             renderer = self._timeline_renderers.get(datatype)
01350             if not renderer is None:
01351                 msg_combine_interval = self.map_dx_to_dstamp(renderer.msg_combine_px)
01352         if msg_combine_interval is None:
01353             msg_combine_interval = self.map_dx_to_dstamp(self._default_msg_combine_px)
01354 
01355         # Get the cache
01356         if topic not in self.index_cache:
01357             return
01358         all_stamps = self.index_cache[topic]
01359 
01360         start_index = bisect.bisect_left(all_stamps, self._stamp_left)
01361         end_index   = bisect.bisect_left(all_stamps, self._stamp_right)
01362 
01363         # Set pen based on datatype
01364         datatype_color = self._datatype_colors.get(datatype, self._default_datatype_color)
01365 
01366         # Iterate through regions of connected messages
01367         width_interval = self._history_width / (self._stamp_right - self._stamp_left)
01368 
01369         # Clip to bounds
01370         dc.save()
01371         dc.rectangle(self._history_left, self._history_top, self._history_width, self._history_bottom - self._history_top)
01372         dc.clip()
01373 
01374         # Draw stamps
01375         dc.set_line_width(1)
01376         dc.set_source_rgba(*datatype_color)
01377 
01378         for (stamp_start, stamp_end) in self._find_regions(all_stamps[:end_index], self.map_dx_to_dstamp(self._default_msg_combine_px)):
01379             if stamp_end < self._stamp_left:
01380                 continue
01381             
01382             region_x_start = self._history_left + (stamp_start - self._stamp_left) * width_interval
01383             region_x_end   = self._history_left + (stamp_end   - self._stamp_left) * width_interval
01384             region_width   = max(1, region_x_end - region_x_start)
01385 
01386             dc.rectangle(region_x_start, msg_y, region_width, msg_height)
01387 
01388         dc.fill()
01389 
01390         # Draw active message
01391         if topic in self._listeners:
01392             dc.set_line_width(self._active_message_line_width)
01393             playhead_stamp = None
01394             playhead_index = bisect.bisect_right(all_stamps, self._playhead.to_sec()) - 1
01395             if playhead_index >= 0:
01396                 playhead_stamp = all_stamps[playhead_index]
01397                 if playhead_stamp > self._stamp_left and playhead_stamp < self._stamp_right:
01398                     playhead_x = self._history_left + (all_stamps[playhead_index] - self._stamp_left) * width_interval
01399                     dc.move_to(playhead_x, msg_y)
01400                     dc.line_to(playhead_x, msg_y + msg_height)
01401                     dc.stroke()
01402 
01403         # Custom renderer
01404         if renderer:
01405             # Iterate through regions of connected messages
01406             for (stamp_start, stamp_end) in self._find_regions(all_stamps[:end_index], msg_combine_interval):
01407                 if stamp_end < self._stamp_left:
01408                     continue
01409 
01410                 region_x_start = self._history_left + (stamp_start - self._stamp_left) * width_interval
01411                 region_x_end   = self._history_left + (stamp_end   - self._stamp_left) * width_interval
01412                 region_width   = max(1, region_x_end - region_x_start)
01413 
01414                 renderer.draw_timeline_segment(dc, topic, stamp_start, stamp_end, region_x_start, msg_y, region_width, msg_height)
01415 
01416         dc.restore()
01417 
01418     def _find_regions(self, stamps, max_interval):
01419         """
01420         Group timestamps into regions connected by timestamps less than max_interval secs apart
01421         """
01422         region_start, prev_stamp = None, None
01423         for stamp in stamps:
01424             if prev_stamp:
01425                 if stamp - prev_stamp > max_interval:
01426                     region_end = prev_stamp
01427                     yield (region_start, region_end)
01428                     region_start = stamp
01429             else:
01430                 region_start = stamp
01431 
01432             prev_stamp = stamp
01433 
01434         if region_start and prev_stamp:
01435             yield (region_start, prev_stamp)
01436 
01437     def _draw_topic_names(self, dc):
01438         """
01439         Draw topic names.
01440         """
01441         topics = self._history_bounds.keys()
01442         coords = [(self._margin_left, y + (h / 2) + (self._topic_font_height / 2)) for (x, y, w, h) in self._history_bounds.values()]
01443         
01444         dc.set_font_size(self._topic_font_size)
01445         dc.set_source_rgb(*self._topic_font_color)
01446         for text, coords in zip([t.lstrip('/') for t in topics], coords):
01447             dc.move_to(*coords)
01448             dc.show_text(text)
01449 
01450     def _draw_bag_ends(self, dc):
01451         """
01452         Draw markers to indicate the extent of the bag file.
01453         """
01454         x_start, x_end = self.map_stamp_to_x(self.start_stamp.to_sec()), self.map_stamp_to_x(self.end_stamp.to_sec())
01455         dc.set_source_rgba(*self._bag_end_color)
01456         dc.rectangle(self._history_left, self._history_top, x_start - self._history_left,                    self._history_bottom - self._history_top)
01457         dc.rectangle(x_end,             self._history_top, self._history_left + self._history_width - x_end, self._history_bottom - self._history_top)
01458         dc.fill()
01459 
01460     def _draw_history_border(self, dc):
01461         bounds_width = min(self._history_width, self.Size[0])
01462 
01463         x, y, w, h = self._history_left, self._history_top, bounds_width, self._history_bottom - self._history_top
01464 
01465         dc.set_source_rgb(0.1, 0.1, 0.1)
01466         dc.set_line_width(1)
01467         dc.rectangle(x, y, w, h)
01468         dc.stroke()
01469 
01470         dc.set_source_rgba(0.6, 0.6, 0.6, 0.3)
01471         dc.move_to(x + 2,     y + h + 1)
01472         dc.line_to(x + w + 1, y + h + 1)
01473         dc.line_to(x + w + 1, y + 2)
01474         dc.stroke()
01475 
01476     def _draw_playhead(self, dc):
01477         px = self.map_stamp_to_x(self.playhead.to_sec())
01478         pw, ph = self._playhead_pointer_size
01479 
01480         # Line
01481         dc.set_line_width(self._playhead_line_width)
01482         dc.set_source_rgba(*self._playhead_color)
01483         dc.move_to(px, self._history_top - 1)
01484         dc.line_to(px, self._history_bottom + 2)
01485         dc.stroke()
01486 
01487         # Upper triangle
01488         py = self._history_top - ph
01489         dc.move_to(px,      py + ph)
01490         dc.line_to(px + pw, py)
01491         dc.line_to(px - pw, py)
01492         dc.line_to(px ,     py + ph)
01493         dc.fill()
01494 
01495         # Lower triangle
01496         py = self._history_bottom + 1
01497         dc.move_to(px,      py)
01498         dc.line_to(px + pw, py + ph)
01499         dc.line_to(px - pw, py + ph)
01500         dc.line_to(px,      py)
01501         dc.fill()
01502 
01503     ### Pixel location <-> time
01504 
01505     def map_x_to_stamp(self, x, clamp_to_visible=True):
01506         fraction = float(x - self._history_left) / self._history_width
01507 
01508         if clamp_to_visible:
01509             if fraction <= 0.0:
01510                 return self._stamp_left
01511             elif fraction >= 1.0:
01512                 return self._stamp_right
01513 
01514         return self._stamp_left + fraction * (self._stamp_right - self._stamp_left)
01515 
01516     def map_dx_to_dstamp(self, dx):
01517         return float(dx) * (self._stamp_right - self._stamp_left) / self._history_width
01518 
01519     def map_stamp_to_x(self, stamp, clamp_to_visible=True):
01520         fraction = (stamp - self._stamp_left) / (self._stamp_right - self._stamp_left)
01521 
01522         if clamp_to_visible:
01523             fraction = min(1.0, max(0.0, fraction))
01524 
01525         return self._history_left + fraction * self._history_width
01526 
01527     def map_dstamp_to_dx(self, dstamp):
01528         return (float(dstamp) * self._history_width) / (self._stamp_right - self._stamp_left)
01529 
01530     ### Keyboard
01531 
01532     def on_key_down(self, event):
01533         key_code = event.KeyCode
01534         
01535         if   key_code == wx.WXK_SPACE:           self.toggle_play()
01536         elif key_code == wx.WXK_NUMPAD_ADD:      self.navigate_fastforward()
01537         elif key_code == wx.WXK_NUMPAD_SUBTRACT: self.navigate_rewind()
01538         elif key_code == wx.WXK_HOME:            self.navigate_start()
01539         elif key_code == wx.WXK_END:             self.navigate_end()
01540         elif key_code == wx.WXK_PAGEUP:          self.zoom_in()
01541         elif key_code == wx.WXK_PAGEDOWN:        self.zoom_out()
01542         elif key_code == wx.WXK_LEFT:            self.translate_timeline((self._stamp_right - self._stamp_left) * -0.05)
01543         elif key_code == wx.WXK_RIGHT:           self.translate_timeline((self._stamp_right - self._stamp_left) *  0.05)
01544         elif key_code == wx.WXK_RETURN:          self.toggle_selecting()
01545         elif key_code == wx.WXK_PAUSE:           self.toggle_recording()
01546 
01547     ### Playing
01548 
01549     def _step_playhead(self):
01550         # Reset on switch of playing mode
01551         if self.playhead != self.last_playhead:
01552             self.last_frame       = None
01553             self.last_playhead    = None
01554             self.desired_playhead = None
01555 
01556         if self._play_all:
01557             self.step_next_message()
01558         else:
01559             self.step_fixed()
01560 
01561     def step_fixed(self):
01562         if self.play_speed == 0.0 or not self.playhead:
01563             self.last_frame    = None
01564             self.last_playhead = None
01565             return
01566 
01567         now = rospy.Time.from_sec(time.time())
01568         if self.last_frame:
01569             # Get new playhead
01570             if self.stick_to_end:
01571                 new_playhead = self.end_stamp
01572             else:
01573                 new_playhead = self.playhead + rospy.Duration.from_sec((now - self.last_frame).to_sec() * self.play_speed)
01574     
01575                 start_stamp, end_stamp = self.play_region
01576 
01577                 if new_playhead > end_stamp:
01578                     if self.wrap:
01579                         if self.play_speed > 0.0:
01580                             new_playhead = start_stamp
01581                         else:
01582                             new_playhead = end_stamp
01583                     else:
01584                         new_playhead = end_stamp
01585 
01586                         if self.play_speed > 0.0:
01587                             self.stick_to_end = True
01588 
01589                 elif new_playhead < start_stamp:
01590                     if self.wrap:
01591                         if self.play_speed < 0.0:
01592                             new_playhead = end_stamp
01593                         else:
01594                             new_playhead = start_stamp
01595                     else:
01596                         new_playhead = start_stamp
01597 
01598             # Update the playhead
01599             self.playhead = new_playhead
01600 
01601         self.last_frame    = now
01602         self.last_playhead = self.playhead
01603 
01604     def step_next_message(self):
01605         if self.play_speed <= 0.0 or not self.playhead:
01606             self.last_frame    = None
01607             self.last_playhead = None
01608             return
01609 
01610         if self.last_frame:
01611             if not self.desired_playhead:
01612                 self.desired_playhead = self.playhead
01613             else:
01614                 delta = rospy.Time.from_sec(time.time()) - self.last_frame
01615                 if delta > rospy.Duration.from_sec(0.1):
01616                     delta = rospy.Duration.from_sec(0.1)
01617                 self.desired_playhead += delta
01618 
01619             # Get the occurrence of the next message
01620             next_message_time = self.get_next_message_time()
01621 
01622             if next_message_time < self.desired_playhead:
01623                 self.playhead = next_message_time
01624             else:
01625                 self.playhead = self.desired_playhead
01626 
01627         self.last_frame    = rospy.Time.from_sec(time.time())
01628         self.last_playhead = self.playhead
01629 
01630     ### Mouse events
01631 
01632     def on_left_down(self, event):
01633         self.SetFocus()
01634         self._clicked_pos = self._dragged_pos = event.Position
01635 
01636         self._paused = True
01637 
01638         if event.ShiftDown():
01639             return
01640 
01641         x, y = self._clicked_pos
01642 
01643         if x >= self._history_left and x <= self.history_right:
01644             if y >= self._history_top and y <= self._history_bottom:
01645                 # Clicked within timeline - set playhead
01646                 playhead_secs = self.map_x_to_stamp(x)
01647                 
01648                 if playhead_secs <= 0.0:
01649                     self.playhead = rospy.Time(0, 1)
01650                 else:
01651                     self.playhead = rospy.Time.from_sec(playhead_secs)
01652 
01653                 #self._selecting_mode = _SelectionMode.MARKED
01654                 
01655                 self.Refresh()
01656                     
01657             elif y <= self._history_top:
01658                 # Clicked above timeline
01659                 
01660                 if self._selecting_mode == _SelectionMode.NONE:
01661                     self._selected_left  = None
01662                     self._selected_right = None
01663                     self.selecting_mode = _SelectionMode.LEFT_MARKED
01664 
01665                     self.Refresh()
01666                 
01667                 elif self._selecting_mode == _SelectionMode.MARKED:
01668                     left_x  = self.map_stamp_to_x(self._selected_left)
01669                     right_x = self.map_stamp_to_x(self._selected_right)
01670                     
01671                     if x < left_x - self._selection_handle_width or x > right_x + self._selection_handle_width:
01672                         self._selected_left  = None
01673                         self._selected_right = None
01674                         self.selecting_mode = _SelectionMode.LEFT_MARKED
01675                         self.Refresh()
01676 
01677     def on_middle_down(self, event):
01678         self.SetFocus()
01679         self._clicked_pos = self._dragged_pos = event.Position
01680         
01681         self._paused = True
01682 
01683     def on_right_down(self, event):
01684         self.SetFocus()
01685         self._clicked_pos = self._dragged_pos = event.Position
01686 
01687         self.PopupMenu(TimelinePopupMenu(self), self._clicked_pos)
01688 
01689     def on_left_up  (self, event): self._on_mouse_up(event)
01690     def on_middle_up(self, event): self._on_mouse_up(event)
01691     def on_right_up (self, event): pass
01692 
01693     def _on_mouse_up(self, event):
01694         self._paused = False
01695         
01696         if self._selecting_mode in [_SelectionMode.LEFT_MARKED, _SelectionMode.MOVE_LEFT, _SelectionMode.MOVE_RIGHT, _SelectionMode.SHIFTING]:
01697             if self._selected_left is None:
01698                 self.selecting_mode = _SelectionMode.NONE
01699             else:
01700                 self.selecting_mode = _SelectionMode.MARKED
01701         
01702         self.Cursor = wx.StockCursor(wx.CURSOR_ARROW)
01703         
01704         self.Refresh()
01705 
01706     def on_mousewheel(self, event):
01707         dz = event.WheelRotation / event.WheelDelta
01708         self.zoom_timeline(1.0 - dz * 0.2)
01709 
01710     def on_mouse_move(self, event):
01711         if not self._history_left:  # @todo: need a better notion of initialized
01712             return
01713 
01714         x, y = event.Position
01715 
01716         if not event.Dragging():
01717             # Mouse moving
01718 
01719             if self._selecting_mode in [_SelectionMode.MARKED, _SelectionMode.MOVE_LEFT, _SelectionMode.MOVE_RIGHT, _SelectionMode.SHIFTING]:
01720                 if y <= self.history_top:
01721                     left_x  = self.map_stamp_to_x(self._selected_left)
01722                     right_x = self.map_stamp_to_x(self._selected_right)
01723 
01724                     if abs(x - left_x) <= self._selection_handle_width:
01725                         self.selecting_mode = _SelectionMode.MOVE_LEFT
01726                         self.Cursor = wx.StockCursor(wx.CURSOR_SIZEWE)
01727                         return
01728                     elif abs(x - right_x) <= self._selection_handle_width:
01729                         self.selecting_mode = _SelectionMode.MOVE_RIGHT
01730                         self.Cursor = wx.StockCursor(wx.CURSOR_SIZEWE)
01731                         return
01732                     elif x > left_x and x < right_x:
01733                         self.selecting_mode = _SelectionMode.SHIFTING
01734                         self.Cursor = wx.StockCursor(wx.CURSOR_SIZING)
01735                         return
01736                     else:
01737                         self.selecting_mode = _SelectionMode.MARKED
01738 
01739             self.Cursor = wx.StockCursor(wx.CURSOR_ARROW)
01740     
01741         else:
01742             # Mouse dragging
01743 
01744             if event.MiddleIsDown() or event.ShiftDown():
01745                 # Middle or shift: zoom
01746                 
01747                 dx_click, dy_click = x - self._clicked_pos[0], y - self._clicked_pos[1]
01748                 dx_drag,  dy_drag  = x - self._dragged_pos[0], y - self._dragged_pos[1]
01749                 
01750                 if dx_drag != 0:
01751                     self.translate_timeline(-self.map_dx_to_dstamp(dx_drag))
01752                 if (dx_drag == 0 and abs(dy_drag) > 0) or (dx_drag != 0 and abs(float(dy_drag) / dx_drag) > 0.2 and abs(dy_drag) > 1):
01753                     zoom = min(self._max_zoom_speed, max(self._min_zoom_speed, 1.0 + self._zoom_sensitivity * dy_drag))
01754                     self.zoom_timeline(zoom)
01755     
01756                 self.Cursor = wx.StockCursor(wx.CURSOR_HAND)
01757     
01758             elif event.LeftIsDown():
01759                 clicked_x, clicked_y = self._clicked_pos
01760     
01761                 x_stamp = self.map_x_to_stamp(x)
01762 
01763                 if y <= self.history_top:
01764                         
01765                     if self._selecting_mode == _SelectionMode.LEFT_MARKED:
01766                         # Left and selecting: change selection region
01767     
01768                         clicked_x_stamp = self.map_x_to_stamp(clicked_x)
01769                         
01770                         self._selected_left  = min(clicked_x_stamp, x_stamp)
01771                         self._selected_right = max(clicked_x_stamp, x_stamp)
01772         
01773                         self.Refresh()
01774                         
01775                     elif self._selecting_mode == _SelectionMode.MOVE_LEFT:
01776                         self._selected_left = x_stamp
01777                         self.Refresh()
01778                         
01779                     elif self._selecting_mode == _SelectionMode.MOVE_RIGHT:
01780                         self._selected_right = x_stamp
01781                         self.Refresh()
01782     
01783                     elif self._selecting_mode == _SelectionMode.SHIFTING:
01784                         dx_drag = x - self._dragged_pos[0]
01785                         dstamp = self.map_dx_to_dstamp(dx_drag)
01786     
01787                         self._selected_left  = max(self._start_stamp.to_sec(), min(self._end_stamp.to_sec(), self._selected_left  + dstamp))
01788                         self._selected_right = max(self._start_stamp.to_sec(), min(self._end_stamp.to_sec(), self._selected_right + dstamp))
01789                         self.Refresh()
01790                 
01791                 elif clicked_x >= self._history_left and clicked_x <= self.history_right and clicked_y >= self._history_top and clicked_y <= self._history_bottom:
01792                     # Left and clicked within timeline: change playhead
01793                     
01794                     if x_stamp <= 0.0:
01795                         self.playhead = rospy.Time(0, 1)
01796                     else:
01797                         self.playhead = rospy.Time.from_sec(x_stamp)
01798                         
01799                     self.Refresh()
01800     
01801             self._dragged_pos = event.Position
01802 
01803     def toggle_selecting(self):
01804         """
01805         Transitions selection mode from NONE -> LEFT_MARKED -> MARKED -> NONE
01806         """
01807         if self._selecting_mode == _SelectionMode.NONE:
01808             self._selected_left  = self._playhead.to_sec()
01809             self._selected_right = None
01810             
01811             self.selecting_mode = _SelectionMode.LEFT_MARKED
01812 
01813         elif self._selecting_mode == _SelectionMode.LEFT_MARKED:
01814             current_mark = self._selected_left
01815             self._selected_left  = min(current_mark, self._playhead.to_sec())
01816             self._selected_right = max(current_mark, self._playhead.to_sec())
01817 
01818             self.selecting_mode = _SelectionMode.MARKED
01819 
01820         elif self._selecting_mode == _SelectionMode.MARKED:
01821             self._selected_left  = None
01822             self._selected_right = None
01823             
01824             self.selecting_mode = _SelectionMode.NONE
01825 
01826         self.Refresh()
01827 
01828 class IndexCacheThread(threading.Thread):
01829     """
01830     Updates invalid caches.
01831     
01832     One thread per timeline.
01833     """
01834     def __init__(self, timeline):
01835         threading.Thread.__init__(self)
01836 
01837         self.timeline  = timeline
01838 
01839         self._stop_flag = False
01840 
01841         self.setDaemon(True)
01842         self.start()
01843 
01844     def run(self):
01845         last_updated_topic = None
01846         
01847         while not self._stop_flag:
01848             with self.timeline.index_cache_cv:
01849                 # Wait until the cache is dirty
01850                 while len(self.timeline.invalidated_caches) == 0:
01851                     self.timeline.index_cache_cv.wait()
01852                     if self._stop_flag:
01853                         return
01854 
01855                 # Update the index for one topic
01856                 updated = False
01857                 for topic in self.timeline.topics:
01858                     if topic in self.timeline.invalidated_caches:# and topic != last_updated_topic:
01859                         updated = (self.timeline._update_index_cache(topic) > 0)
01860                         #if updated:
01861                         #    last_updated_topic = topic
01862                         #    break
01863 
01864             if updated:
01865                 wx.CallAfter(self.timeline.Refresh)
01866 
01867                 # Give the GUI some time to update
01868                 time.sleep(1.0)
01869 
01870     def stop(self):
01871         self._stop_flag = True
01872         cv = self.timeline.index_cache_cv
01873         with cv:
01874             cv.notify()
01875 
01876 class MessageLoader(threading.Thread):
01877     """
01878     Waits for a new playhead position on the given topic, then loads the message at that position and notifies the view threads.
01879 
01880     One thread per topic.  Maintains a cache of recently loaded messages.
01881     """
01882     def __init__(self, timeline, topic):
01883         threading.Thread.__init__(self)
01884 
01885         self.timeline = timeline
01886         self.topic    = topic
01887         
01888         self.bag_playhead_position = None
01889 
01890         self._message_cache_capacity = 50
01891         self._message_cache          = {}
01892         self._message_cache_keys     = []
01893         
01894         self._stop_flag = False
01895         
01896         self.setDaemon(True)
01897         self.start()
01898 
01899     def reset(self):
01900         self.bag_playhead_position = None
01901 
01902     def run(self):
01903         while not self._stop_flag:
01904             # Wait for a new entry
01905             cv = self.timeline._playhead_positions_cvs[self.topic]
01906             with cv:
01907                 while (self.topic not in self.timeline._playhead_positions) or (self.bag_playhead_position == self.timeline._playhead_positions[self.topic]):
01908                     cv.wait()
01909                     if self._stop_flag:
01910                         return
01911                 bag, playhead_position = self.timeline._playhead_positions[self.topic]
01912 
01913             self.bag_playhead_position = (bag, playhead_position)
01914 
01915             # Don't bother loading the message if there are no listeners
01916             if not self.timeline.has_listeners(self.topic):
01917                 continue
01918 
01919             # Load the message
01920             if playhead_position is None:
01921                 msg_data = None
01922             else:
01923                 msg_data = self._get_message(bag, playhead_position)
01924 
01925             # Inform the views
01926             messages_cv = self.timeline._messages_cvs[self.topic]
01927             with messages_cv:
01928                 self.timeline._messages[self.topic] = (bag, msg_data)
01929                 messages_cv.notify_all()      # notify all views that a message is loaded
01930 
01931     def _get_message(self, bag, position):
01932         key = '%s%s' % (bag.filename, str(position))
01933         if key in self._message_cache:
01934             return self._message_cache[key]
01935 
01936         msg_data = self.timeline.read_message(bag, position)
01937 
01938         self._message_cache[key] = msg_data
01939         self._message_cache_keys.append(key)
01940 
01941         if len(self._message_cache) > self._message_cache_capacity:
01942             oldest_key = self._message_cache_keys[0]
01943             del self._message_cache[oldest_key]
01944             self._message_cache_keys.remove(oldest_key)
01945 
01946         return msg_data
01947 
01948     def stop(self):
01949         self._stop_flag = True
01950         cv = self.timeline._playhead_positions_cvs[self.topic]
01951         with cv:
01952             cv.notify_all()
01953 
01954 class MessageListenerThread(threading.Thread):
01955     """
01956     Waits for new messages loaded on the given topic, then calls the message listener.
01957     
01958     One thread per listener, topic pair.
01959     """
01960     def __init__(self, timeline, topic, listener):
01961         threading.Thread.__init__(self)
01962 
01963         self.timeline = timeline
01964         self.topic    = topic
01965         self.listener = listener
01966 
01967         self.bag_msg_data = None
01968 
01969         self._stop_flag = False
01970 
01971         self.setDaemon(True)
01972         self.start()
01973 
01974     def run(self):
01975         while not self._stop_flag:
01976             # Wait for a new message
01977             cv = self.timeline._messages_cvs[self.topic]
01978             with cv:
01979                 while (self.topic not in self.timeline._messages) or (self.bag_msg_data == self.timeline._messages[self.topic]):
01980                     cv.wait()
01981                     if self._stop_flag:
01982                         return
01983                 bag_msg_data = self.timeline._messages[self.topic]
01984 
01985             # View the message
01986             self.bag_msg_data = bag_msg_data
01987             try:
01988                 bag, msg_data = bag_msg_data
01989                 if msg_data:
01990                     self.listener.message_viewed(bag, msg_data)
01991                 else:
01992                     self.listener.message_cleared()
01993             except wx.PyDeadObjectError:
01994                 self.timeline.remove_listener(self.topic, self.listener)
01995             except Exception, ex:
01996                 print >> sys.stderr, 'Error notifying listener %s: %s' % (type(self.listener), str(ex))
01997 
01998     def stop(self):
01999         self._stop_flag = True
02000         cv = self.timeline._messages_cvs[self.topic]
02001         with cv:
02002             cv.notify_all()


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