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