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