bag_timeline.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2012, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 
33 import rospy
34 import rosbag
35 import time
36 import threading
37 
38 
39 from python_qt_binding.QtCore import Qt, QTimer, qWarning, Signal
40 from python_qt_binding.QtWidgets import QGraphicsScene, QMessageBox
41 
42 from rqt_bag import bag_helper
43 
44 from .timeline_frame import TimelineFrame
45 from .message_listener_thread import MessageListenerThread
46 from .message_loader_thread import MessageLoaderThread
47 from .player import Player
48 from .recorder import Recorder
49 from .timeline_menu import TimelinePopupMenu
50 
51 
52 class BagTimeline(QGraphicsScene):
53 
54  """
55  BagTimeline contains bag files, all information required to display the bag data visualization
56  on the screen Also handles events
57  """
58  status_bar_changed_signal = Signal()
59  selected_region_changed = Signal(rospy.Time, rospy.Time)
60 
61  def __init__(self, context, publish_clock):
62  """
63  :param context:
64  plugin context hook to enable adding rqt_bag plugin widgets as ROS_GUI snapin panes,
65  ''PluginContext''
66  """
67  super(BagTimeline, self).__init__()
68  self._bags = []
69  self._bag_lock = threading.RLock()
70 
71  self.background_task = None # Display string
73 
74  # Playing / Recording
75  self._playhead_lock = threading.RLock()
76  self._max_play_speed = 1024.0 # fastest X play speed
77  self._min_play_speed = 1.0 / 1024.0 # slowest X play speed
78  self._play_speed = 0.0
79  self._play_all = False
81  self._playhead_positions = {} # topic -> (bag, position)
82  self._message_loaders = {}
83  self._messages_cvs = {}
84  self._messages = {} # topic -> (bag, msg_data)
85  self._message_listener_threads = {} # listener -> MessageListenerThread
86  self._player = False
87  self._publish_clock = publish_clock
88  self._recorder = None
89  self.last_frame = None
90  self.last_playhead = None
91  self.desired_playhead = None
92  self.wrap = True # should the playhead wrap when it reaches the end?
93  self.stick_to_end = False # should the playhead stick to the end?
94  self._play_timer = QTimer()
95  self._play_timer.timeout.connect(self.on_idle)
96  self._play_timer.setInterval(3)
97 
98  # Plugin popup management
99  self._context = context
100  self.popups = {}
101  self._views = []
102  self._listeners = {}
103 
104  # Initialize scene
105  # the timeline renderer fixes use of black pens and fills, so ensure we fix white here for
106  # contrast. Otherwise a dark qt theme will default it to black and the frame render
107  # pen will be unreadable
108  self.setBackgroundBrush(Qt.white)
109  self._timeline_frame = TimelineFrame(self)
110  self._timeline_frame.setPos(0, 0)
111  self.addItem(self._timeline_frame)
112 
114  self.__closed = False
115 
116  def get_context(self):
117  """
118  :returns: the ROS_GUI context, 'PluginContext'
119  """
120  return self._context
121 
122  def handle_close(self):
123  """
124  Cleans up the timeline, bag and any threads
125  """
126  if self.__closed:
127  return
128  else:
129  self.__closed = True
130  self._play_timer.stop()
131  for topic in self._get_topics():
132  self.stop_publishing(topic)
133  self._message_loaders[topic].stop()
134  if self._player:
135  self._player.stop()
136  if self._recorder:
137  self._recorder.stop()
138  if self.background_task is not None:
139  self.background_task_cancel = True
140  self._timeline_frame.handle_close()
141  for bag in self._bags:
142  bag.close()
143  for frame in self._views:
144  if frame.parent():
145  self._context.remove_widget(frame)
146 
147  # Bag Management and access
148  def add_bag(self, bag):
149  """
150  creates an indexing thread for each new topic in the bag
151  fixes the boarders and notifies the indexing thread to index the new items bags
152  :param bag: ros bag file, ''rosbag.bag''
153  """
154  self._bags.append(bag)
155 
156  bag_topics = bag_helper.get_topics(bag)
157 
158  new_topics = set(bag_topics) - set(self._timeline_frame.topics)
159 
160  for topic in new_topics:
161  self._playhead_positions_cvs[topic] = threading.Condition()
162  self._messages_cvs[topic] = threading.Condition()
163  self._message_loaders[topic] = MessageLoaderThread(self, topic)
164 
165  self._timeline_frame._start_stamp = self._get_start_stamp()
166  self._timeline_frame._end_stamp = self._get_end_stamp()
167  self._timeline_frame.topics = self._get_topics()
168  self._timeline_frame._topics_by_datatype = self._get_topics_by_datatype()
169  # If this is the first bag, reset the timeline
170  if self._timeline_frame._stamp_left is None:
171  self._timeline_frame.reset_timeline()
172 
173  # Invalidate entire index cache for all topics in this bag
174  with self._timeline_frame.index_cache_cv:
175  for topic in bag_topics:
176  self._timeline_frame.invalidated_caches.add(topic)
177  if topic in self._timeline_frame.index_cache:
178  del self._timeline_frame.index_cache[topic]
179 
180  self._timeline_frame.index_cache_cv.notify()
181 
182  def file_size(self):
183  with self._bag_lock:
184  return sum(b.size for b in self._bags)
185 
186  # TODO Rethink API and if these need to be visible
187  def _get_start_stamp(self):
188  """
189  :return: first stamp in the bags, ''rospy.Time''
190  """
191  with self._bag_lock:
192  start_stamp = None
193  for bag in self._bags:
194  bag_start_stamp = bag_helper.get_start_stamp(bag)
195  if bag_start_stamp is not None and \
196  (start_stamp is None or bag_start_stamp < start_stamp):
197  start_stamp = bag_start_stamp
198  return start_stamp
199 
200  def _get_end_stamp(self):
201  """
202  :return: last stamp in the bags, ''rospy.Time''
203  """
204  with self._bag_lock:
205  end_stamp = None
206  for bag in self._bags:
207  bag_end_stamp = bag_helper.get_end_stamp(bag)
208  if bag_end_stamp is not None and (end_stamp is None or bag_end_stamp > end_stamp):
209  end_stamp = bag_end_stamp
210  return end_stamp
211 
212  def _get_topics(self):
213  """
214  :return: sorted list of topic names, ''list(str)''
215  """
216  with self._bag_lock:
217  topics = set()
218  for bag in self._bags:
219  for topic in bag_helper.get_topics(bag):
220  topics.add(topic)
221  return sorted(topics)
222 
224  """
225  :return: dict of list of topics for each datatype, ''dict(datatype:list(topic))''
226  """
227  with self._bag_lock:
228  topics_by_datatype = {}
229  for bag in self._bags:
230  for datatype, topics in bag_helper.get_topics_by_datatype(bag).items():
231  topics_by_datatype.setdefault(datatype, []).extend(topics)
232  return topics_by_datatype
233 
234  def get_datatype(self, topic):
235  """
236  :return: datatype associated with a topic, ''str''
237  :raises: if there are multiple datatypes assigned to a single topic, ''Exception''
238  """
239  with self._bag_lock:
240  datatype = None
241  for bag in self._bags:
242  bag_datatype = bag_helper.get_datatype(bag, topic)
243  if datatype and bag_datatype and (bag_datatype != datatype):
244  raise Exception('topic %s has multiple datatypes: %s and %s' %
245  (topic, datatype, bag_datatype))
246  if bag_datatype:
247  datatype = bag_datatype
248  return datatype
249 
250  def get_entries(self, topics, start_stamp, end_stamp):
251  """
252  generator function for bag entries
253  :param topics: list of topics to query, ''list(str)''
254  :param start_stamp: stamp to start at, ''rospy.Time''
255  :param end_stamp: stamp to end at, ''rospy,Time''
256  :returns: entries the bag file, ''msg''
257  """
258  with self._bag_lock:
259  from rosbag import bag # for _mergesort
260  bag_entries = []
261  for b in self._bags:
262  bag_start_time = bag_helper.get_start_stamp(b)
263  if bag_start_time is not None and bag_start_time > end_stamp:
264  continue
265 
266  bag_end_time = bag_helper.get_end_stamp(b)
267  if bag_end_time is not None and bag_end_time < start_stamp:
268  continue
269 
270  connections = list(b._get_connections(topics))
271  bag_entries.append(b._get_entries(connections, start_stamp, end_stamp))
272 
273  for entry, _ in bag._mergesort(bag_entries, key=lambda entry: entry.time):
274  yield entry
275 
276  def get_entries_with_bags(self, topic, start_stamp, end_stamp):
277  """
278  generator function for bag entries
279  :param topics: list of topics to query, ''list(str)''
280  :param start_stamp: stamp to start at, ''rospy.Time''
281  :param end_stamp: stamp to end at, ''rospy,Time''
282  :returns: tuple of (bag, entry) for the entries in the bag file, ''(rosbag.bag, msg)''
283  """
284  with self._bag_lock:
285  from rosbag import bag # for _mergesort
286 
287  bag_entries = []
288  bag_by_iter = {}
289  for b in self._bags:
290  bag_start_time = bag_helper.get_start_stamp(b)
291  if bag_start_time is not None and bag_start_time > end_stamp:
292  continue
293 
294  bag_end_time = bag_helper.get_end_stamp(b)
295  if bag_end_time is not None and bag_end_time < start_stamp:
296  continue
297 
298  connections = list(b._get_connections(topic))
299  it = iter(b._get_entries(connections, start_stamp, end_stamp))
300  bag_by_iter[it] = b
301  bag_entries.append(it)
302 
303  for entry, it in bag._mergesort(bag_entries, key=lambda entry: entry.time):
304  yield bag_by_iter[it], entry
305 
306  def get_entry(self, t, topic):
307  """
308  Access a bag entry
309  :param t: time, ''rospy.Time''
310  :param topic: the topic to be accessed, ''str''
311  :return: tuple of (bag, entry) corisponding to time t and topic, ''(rosbag.bag, msg)''
312  """
313  with self._bag_lock:
314  entry_bag, entry = None, None
315  for bag in self._bags:
316  bag_entry = bag._get_entry(t, bag._get_connections(topic))
317  if bag_entry and (not entry or bag_entry.time > entry.time):
318  entry_bag, entry = bag, bag_entry
319 
320  return entry_bag, entry
321 
322  def get_entry_before(self, t):
323  """
324  Access a bag entry
325  :param t: time, ''rospy.Time''
326  :return: tuple of (bag, entry) corresponding to time t, ''(rosbag.bag, msg)''
327  """
328  with self._bag_lock:
329  entry_bag, entry = None, None
330  for bag in self._bags:
331  bag_entry = bag._get_entry(t - rospy.Duration(0, 1), bag._get_connections())
332  if bag_entry and (not entry or bag_entry.time < entry.time):
333  entry_bag, entry = bag, bag_entry
334 
335  return entry_bag, entry
336 
337  def get_entry_after(self, t):
338  """
339  Access a bag entry
340  :param t: time, ''rospy.Time''
341  :return: tuple of (bag, entry) corisponding to time t, ''(rosbag.bag, msg)''
342  """
343  with self._bag_lock:
344  entry_bag, entry = None, None
345  for bag in self._bags:
346  bag_entry = bag._get_entry_after(t, bag._get_connections())
347  if bag_entry and (not entry or bag_entry.time < entry.time):
348  entry_bag, entry = bag, bag_entry
349 
350  return entry_bag, entry
351 
353  """
354  :return: time of the next message after the current playhead position,''rospy.Time''
355  """
356  if self._timeline_frame.playhead is None:
357  return None
358 
359  _, entry = self.get_entry_after(self._timeline_frame.playhead)
360  if entry is None:
361  return self._timeline_frame._start_stamp
362 
363  return entry.time
364 
366  """
367  :return: time of the next message before the current playhead position,''rospy.Time''
368  """
369  if self._timeline_frame.playhead is None:
370  return None
371 
372  _, entry = self.get_entry_before(self._timeline_frame.playhead)
373  if entry is None:
374  return self._timeline_frame._end_stamp
375 
376  return entry.time
377 
378  def resume(self):
379  if (self._player):
380  self._player.resume()
381 
382  # Copy messages to...
383 
384  def start_background_task(self, background_task):
385  """
386  Verify that a background task is not currently running before starting a new one
387  :param background_task: name of the background task, ''str''
388  """
389  if self.background_task is not None:
390  QMessageBox(
391  QMessageBox.Warning, 'Exclamation', 'Background operation already running:\n\n%s' %
392  self.background_task, QMessageBox.Ok).exec_()
393  return False
394 
395  self.background_task = background_task
396  self.background_task_cancel = False
397  return True
398 
400  self.background_task = None
401 
402  def copy_region_to_bag(self, filename):
403  if len(self._bags) > 0:
404  self._export_region(filename, self._timeline_frame.topics,
405  self._timeline_frame.play_region[0],
406  self._timeline_frame.play_region[1])
407 
408  def _export_region(self, path, topics, start_stamp, end_stamp):
409  """
410  Starts a thread to save the current selection to a new bag file
411  :param path: filesystem path to write to, ''str''
412  :param topics: topics to write to the file, ''list(str)''
413  :param start_stamp: start of area to save, ''rospy.Time''
414  :param end_stamp: end of area to save, ''rospy.Time''
415  """
416  if not self.start_background_task('Copying messages to "%s"' % path):
417  return
418  # TODO implement a status bar area with information on the current save status
419  bag_entries = list(self.get_entries_with_bags(topics, start_stamp, end_stamp))
420 
421  if self.background_task_cancel:
422  return
423 
424  # Get the total number of messages to copy
425  total_messages = len(bag_entries)
426 
427  # If no messages, prompt the user and return
428  if total_messages == 0:
429  QMessageBox(QMessageBox.Warning, 'rqt_bag', 'No messages found', QMessageBox.Ok).exec_()
430  self.stop_background_task()
431  return
432 
433  # Open the path for writing
434  try:
435  export_bag = rosbag.Bag(path, 'w')
436  except Exception:
437  QMessageBox(QMessageBox.Warning, 'rqt_bag',
438  'Error opening bag file [%s] for writing' % path, QMessageBox.Ok).exec_()
439  self.stop_background_task()
440  return
441 
442  # Run copying in a background thread
443  self._export_thread = threading.Thread(
444  target=self._run_export_region,
445  args=(export_bag, topics, start_stamp, end_stamp, bag_entries))
446  self._export_thread.start()
447 
448  def _run_export_region(self, export_bag, topics, start_stamp, end_stamp, bag_entries):
449  """
450  Threaded function that saves the current selection to a new bag file
451  :param export_bag: bagfile to write to, ''rosbag.bag''
452  :param topics: topics to write to the file, ''list(str)''
453  :param start_stamp: start of area to save, ''rospy.Time''
454  :param end_stamp: end of area to save, ''rospy.Time''
455  """
456  total_messages = len(bag_entries)
457  update_step = max(1, total_messages / 100)
458  message_num = 1
459  progress = 0
460  # Write out the messages
461  for bag, entry in bag_entries:
462  if self.background_task_cancel:
463  break
464  try:
465  topic, msg, t = self.read_message(bag, entry.position)
466  export_bag.write(topic, msg, t)
467  except Exception as ex:
468  qWarning('Error exporting message at position %s: %s' %
469  (str(entry.position), str(ex)))
470  export_bag.close()
471  self.stop_background_task()
472  return
473 
474  if message_num % update_step == 0 or message_num == total_messages:
475  new_progress = int(100.0 * (float(message_num) / total_messages))
476  if new_progress != progress:
477  progress = new_progress
478  if not self.background_task_cancel:
479  self.background_progress = progress
480  self.status_bar_changed_signal.emit()
481 
482  message_num += 1
483 
484  # Close the bag
485  try:
486  self.background_progress = 0
487  self.status_bar_changed_signal.emit()
488  export_bag.close()
489  except Exception as ex:
490  QMessageBox(QMessageBox.Warning, 'rqt_bag', 'Error closing bag file [%s]: %s' % (
491  export_bag.filename, str(ex)), QMessageBox.Ok).exec_()
492  self.stop_background_task()
493 
494  def read_message(self, bag, position):
495  with self._bag_lock:
496  return bag._read_message(position)
497 
498  # Mouse events
499  def on_mouse_down(self, event):
500  if event.buttons() == Qt.LeftButton:
501  self._timeline_frame.on_left_down(event)
502  elif event.buttons() == Qt.MidButton:
503  self._timeline_frame.on_middle_down(event)
504  elif event.buttons() == Qt.RightButton:
505  topic = self._timeline_frame.map_y_to_topic(self.views()[0].mapToScene(event.pos()).y())
506  TimelinePopupMenu(self, event, topic)
507 
508  def on_mouse_up(self, event):
509  self._timeline_frame.on_mouse_up(event)
510 
511  def on_mouse_move(self, event):
512  self._timeline_frame.on_mouse_move(event)
513 
514  def on_mousewheel(self, event):
515  self._timeline_frame.on_mousewheel(event)
516 
517  # Zooming
518 
519  def zoom_in(self):
520  self._timeline_frame.zoom_in()
521 
522  def zoom_out(self):
523  self._timeline_frame.zoom_out()
524 
525  def reset_zoom(self):
526  self._timeline_frame.reset_zoom()
527 
529  self._timeline_frame.translate_timeline_left()
530 
532  self._timeline_frame.translate_timeline_right()
533 
534  # Publishing
535  def is_publishing(self, topic):
536  return self._player and self._player.is_publishing(topic)
537 
538  def start_publishing(self, topic):
539  if not self._player and not self._create_player():
540  return False
541 
542  self._player.start_publishing(topic)
543  return True
544 
545  def stop_publishing(self, topic):
546  if not self._player:
547  return False
548 
549  self._player.stop_publishing(topic)
550  return True
551 
552  def _create_player(self):
553  if not self._player:
554  try:
555  self._player = Player(self)
556  if self._publish_clock:
557  self._player.start_clock_publishing()
558  except Exception as ex:
559  qWarning('Error starting player; aborting publish: %s' % str(ex))
560  return False
561 
562  return True
563 
564  def set_publishing_state(self, start_publishing):
565  if start_publishing:
566  for topic in self._timeline_frame.topics:
567  if not self.start_publishing(topic):
568  break
569  else:
570  for topic in self._timeline_frame.topics:
571  self.stop_publishing(topic)
572 
573  # property: play_all
574  def _get_play_all(self):
575  return self._play_all
576 
577  def _set_play_all(self, play_all):
578  if play_all == self._play_all:
579  return
580 
581  self._play_all = not self._play_all
582 
583  self.last_frame = None
584  self.last_playhead = None
585  self.desired_playhead = None
586 
587  play_all = property(_get_play_all, _set_play_all)
588 
589  def toggle_play_all(self):
590  self.play_all = not self.play_all
591 
592  # Playing
593  def on_idle(self):
594  self._step_playhead()
595 
596  def _step_playhead(self):
597  """
598  moves the playhead to the next position based on the desired position
599  """
600  # Reset when the playing mode switchs
601  if self._timeline_frame.playhead != self.last_playhead:
602  self.last_frame = None
603  self.last_playhead = None
604  self.desired_playhead = None
605 
606  if self._play_all:
607  self.step_next_message()
608  else:
609  self.step_fixed()
610 
611  def step_fixed(self):
612  """
613  Moves the playhead a fixed distance into the future based on the current play speed
614  """
615  if self.play_speed == 0.0 or not self._timeline_frame.playhead:
616  self.last_frame = None
617  self.last_playhead = None
618  return
619 
620  now = rospy.Time.from_sec(time.time())
621  if self.last_frame:
622  # Get new playhead
623  if self.stick_to_end:
624  new_playhead = self.end_stamp
625  else:
626  new_playhead = self._timeline_frame.playhead + \
627  rospy.Duration.from_sec((now - self.last_frame).to_sec() * self.play_speed)
628 
629  start_stamp, end_stamp = self._timeline_frame.play_region
630 
631  if new_playhead > end_stamp:
632  if self.wrap:
633  if self.play_speed > 0.0:
634  new_playhead = start_stamp
635  else:
636  new_playhead = end_stamp
637  else:
638  new_playhead = end_stamp
639 
640  if self.play_speed > 0.0:
641  self.stick_to_end = True
642 
643  elif new_playhead < start_stamp:
644  if self.wrap:
645  if self.play_speed < 0.0:
646  new_playhead = end_stamp
647  else:
648  new_playhead = start_stamp
649  else:
650  new_playhead = start_stamp
651 
652  # Update the playhead
653  self._timeline_frame.playhead = new_playhead
654 
655  self.last_frame = now
656  self.last_playhead = self._timeline_frame.playhead
657 
658  def step_next_message(self):
659  """
660  Move the playhead to the next message
661  """
662  if self.play_speed <= 0.0 or not self._timeline_frame.playhead:
663  self.last_frame = None
664  self.last_playhead = None
665  return
666 
667  if self.last_frame:
668  if not self.desired_playhead:
669  self.desired_playhead = self._timeline_frame.playhead
670  else:
671  delta = rospy.Time.from_sec(time.time()) - self.last_frame
672  if delta > rospy.Duration.from_sec(0.1):
673  delta = rospy.Duration.from_sec(0.1)
674  self.desired_playhead += delta
675 
676  # Get the occurrence of the next message
677  next_message_time = self.get_next_message_time()
678 
679  if next_message_time < self.desired_playhead:
680  self._timeline_frame.playhead = next_message_time
681  else:
682  self._timeline_frame.playhead = self.desired_playhead
683 
684  self.last_frame = rospy.Time.from_sec(time.time())
685  self.last_playhead = self._timeline_frame.playhead
686 
687  # Recording
688 
689  def record_bag(self, filename, all=True, topics=[], regex=False, limit=0):
690  try:
691  self._recorder = Recorder(
692  filename, bag_lock=self._bag_lock, all=all, topics=topics, regex=regex, limit=limit)
693  except Exception as ex:
694  qWarning('Error opening bag for recording [%s]: %s' % (filename, str(ex)))
695  return
696 
697  self._recorder.add_listener(self._message_recorded)
698 
699  self.add_bag(self._recorder.bag)
700 
701  self._recorder.start()
702 
703  self.wrap = False
704  self._timeline_frame._index_cache_thread.period = 0.1
705 
706  self.update()
707 
708  def toggle_recording(self):
709  if self._recorder:
710  self._recorder.toggle_paused()
711  self.update()
712 
713  def _message_recorded(self, topic, msg, t):
714  if self._timeline_frame._start_stamp is None:
715  self._timeline_frame._start_stamp = t
716  self._timeline_frame._end_stamp = t
717  self._timeline_frame._playhead = t
718  elif self._timeline_frame._end_stamp is None or t > self._timeline_frame._end_stamp:
719  self._timeline_frame._end_stamp = t
720 
721  if not self._timeline_frame.topics or topic not in self._timeline_frame.topics:
722  self._timeline_frame.topics = self._get_topics()
723  self._timeline_frame._topics_by_datatype = self._get_topics_by_datatype()
724 
725  self._playhead_positions_cvs[topic] = threading.Condition()
726  self._messages_cvs[topic] = threading.Condition()
727  self._message_loaders[topic] = MessageLoaderThread(self, topic)
728 
729  if self._timeline_frame._stamp_left is None:
730  self.reset_zoom()
731 
732  # Notify the index caching thread that it has work to do
733  with self._timeline_frame.index_cache_cv:
734  self._timeline_frame.invalidated_caches.add(topic)
735  self._timeline_frame.index_cache_cv.notify()
736 
737  if topic in self._listeners:
738  for listener in self._listeners[topic]:
739  try:
740  listener.timeline_changed()
741  except Exception as ex:
742  qWarning('Error calling timeline_changed on %s: %s' % (type(listener), str(ex)))
743 
744  # Views / listeners
745  def add_view(self, topic, frame):
746  self._views.append(frame)
747 
748  def has_listeners(self, topic):
749  return topic in self._listeners
750 
751  def add_listener(self, topic, listener):
752  self._listeners.setdefault(topic, []).append(listener)
753 
754  self._message_listener_threads[(topic, listener)] = \
755  MessageListenerThread(self, topic, listener)
756  # Notify the message listeners
757  self._message_loaders[topic].reset()
758  with self._playhead_positions_cvs[topic]:
759  self._playhead_positions_cvs[topic].notify_all()
760 
761  self.update()
762 
763  def remove_listener(self, topic, listener):
764  topic_listeners = self._listeners.get(topic)
765  if topic_listeners is not None and listener in topic_listeners:
766  topic_listeners.remove(listener)
767 
768  if len(topic_listeners) == 0:
769  del self._listeners[topic]
770 
771  # Stop the message listener thread
772  if (topic, listener) in self._message_listener_threads:
773  self._message_listener_threads[(topic, listener)].stop()
774  del self._message_listener_threads[(topic, listener)]
775  self.update()
776 
777  # Playhead
778 
779  # property: play_speed
780  def _get_play_speed(self):
781  if self._timeline_frame._paused:
782  return 0.0
783  return self._play_speed
784 
785  def _set_play_speed(self, play_speed):
786  if play_speed == self._play_speed:
787  return
788 
789  if play_speed > 0.0:
790  self._play_speed = min(self._max_play_speed, max(self._min_play_speed, play_speed))
791  elif play_speed < 0.0:
792  self._play_speed = max(-self._max_play_speed, min(-self._min_play_speed, play_speed))
793  else:
794  self._play_speed = play_speed
795 
796  if self._play_speed < 1.0:
797  self.stick_to_end = False
798 
799  self.update()
800  play_speed = property(_get_play_speed, _set_play_speed)
801 
802  def toggle_play(self):
803  if self._play_speed != 0.0:
804  self.play_speed = 0.0
805  else:
806  self.play_speed = 1.0
807 
808  def navigate_play(self):
809  self.play_speed = 1.0
810  self.last_frame = rospy.Time.from_sec(time.time())
811  self.last_playhead = self._timeline_frame.playhead
812  self._play_timer.start()
813 
814  def navigate_stop(self):
815  self.play_speed = 0.0
816  self._play_timer.stop()
817 
818  def navigate_previous(self):
819  self.navigate_stop()
820  self._timeline_frame.playhead = self.get_previous_message_time()
821  self.last_playhead = self._timeline_frame.playhead
822 
823  def navigate_next(self):
824  self.navigate_stop()
825  self._timeline_frame.playhead = self.get_next_message_time()
826  self.last_playhead = self._timeline_frame.playhead
827 
828  def navigate_rewind(self):
829  if self._play_speed < 0.0:
830  new_play_speed = self._play_speed * 2.0
831  elif self._play_speed == 0.0:
832  new_play_speed = -1.0
833  else:
834  new_play_speed = self._play_speed * 0.5
835 
836  self.play_speed = new_play_speed
837 
839  if self._play_speed > 0.0:
840  new_play_speed = self._play_speed * 2.0
841  elif self._play_speed == 0.0:
842  new_play_speed = 2.0
843  else:
844  new_play_speed = self._play_speed * 0.5
845 
846  self.play_speed = new_play_speed
847 
848  def navigate_start(self):
849  self._timeline_frame.playhead = self._timeline_frame.play_region[0]
850 
851  def navigate_end(self):
852  self._timeline_frame.playhead = self._timeline_frame.play_region[1]
def add_listener(self, topic, listener)
def copy_region_to_bag(self, filename)
def record_bag(self, filename, all=True, topics=[], regex=False, limit=0)
def _set_play_speed(self, play_speed)
def start_background_task(self, background_task)
def __init__(self, context, publish_clock)
Definition: bag_timeline.py:61
def _run_export_region(self, export_bag, topics, start_stamp, end_stamp, bag_entries)
def read_message(self, bag, position)
def get_entry(self, t, topic)
def get_entries(self, topics, start_stamp, end_stamp)
def _message_recorded(self, topic, msg, t)
def set_publishing_state(self, start_publishing)
def _export_region(self, path, topics, start_stamp, end_stamp)
def _set_play_all(self, play_all)
def remove_listener(self, topic, listener)
def add_view(self, topic, frame)
def get_entries_with_bags(self, topic, start_stamp, end_stamp)


rqt_bag
Author(s): Aaron Blasdel, Tim Field
autogenerated on Fri Jun 7 2019 22:05:54