41 from python_qt_binding.QtCore
import Qt, QTimer, qWarning, Signal
42 from python_qt_binding.QtWidgets
import QGraphicsScene, QMessageBox
44 from rqt_bag
import bag_helper
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
57 BagTimeline contains bag files, all information required to display the bag data visualization 58 on the screen Also handles events 60 status_bar_changed_signal = Signal()
61 selected_region_changed = Signal(rospy.Time, rospy.Time)
66 plugin context hook to enable adding rqt_bag plugin widgets as ROS_GUI snapin panes, 97 self._play_timer.timeout.connect(self.
on_idle)
98 self._play_timer.setInterval(3)
110 self.setBackgroundBrush(Qt.white)
112 self._timeline_frame.setPos(0, 0)
120 :returns: the ROS_GUI context, 'PluginContext' 126 Cleans up the timeline, bag and any threads 132 self._play_timer.stop()
139 self._recorder.stop()
142 self._timeline_frame.handle_close()
143 for bag
in self.
_bags:
147 self._context.remove_widget(frame)
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'' 156 self._bags.append(bag)
158 bag_topics = bag_helper.get_topics(bag)
160 new_topics = set(bag_topics) - set(self._timeline_frame.topics)
162 for topic
in new_topics:
172 if self._timeline_frame._stamp_left
is None:
173 self._timeline_frame.reset_timeline()
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]
182 self._timeline_frame.index_cache_cv.notify()
186 return sum(b.size
for b
in self.
_bags)
191 :return: first stamp in the bags, ''rospy.Time'' 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
204 :return: last stamp in the bags, ''rospy.Time'' 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
216 :return: sorted list of topic names, ''list(str)'' 220 for bag
in self.
_bags:
221 for topic
in bag_helper.get_topics(bag):
223 return sorted(topics)
227 :return: dict of list of topics for each datatype, ''dict(datatype:list(topic))'' 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
238 :return: datatype associated with a topic, ''str'' 239 :raises: if there are multiple datatypes assigned to a single topic, ''Exception'' 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))
249 datatype = bag_datatype
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'' 263 bag_start_time = bag_helper.get_start_stamp(b)
264 if bag_start_time
is not None and bag_start_time > end_stamp:
267 bag_end_time = bag_helper.get_end_stamp(b)
268 if bag_end_time
is not None and bag_end_time < start_stamp:
271 connections = list(b._get_connections(topics))
274 bag_entries.append(sorted(b._get_entries(connections, start_stamp, end_stamp)))
276 for entry
in heapq.merge(*bag_entries):
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)'' 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:
294 bag_end_time = bag_helper.get_end_stamp(bag)
295 if bag_end_time
is not None and bag_end_time < start_stamp:
298 connections = list(bag._get_connections(topic))
301 bag_entries.append([(bag, entry)
for entry
in sorted(
302 bag._get_entries(connections, start_stamp, end_stamp))])
306 for bag_entry
in sorted(itertools.chain(*bag_entries), key=
lambda bag_entry: bag_entry[1].time):
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)'' 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
323 return entry_bag, entry
328 :param t: time, ''rospy.Time'' 329 :return: tuple of (bag, entry) corresponding to time t, ''(rosbag.bag, msg)'' 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
338 return entry_bag, entry
343 :param t: time, ''rospy.Time'' 344 :return: tuple of (bag, entry) corisponding to time t, ''(rosbag.bag, msg)'' 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
353 return entry_bag, entry
357 :return: time of the next message after the current playhead position,''rospy.Time'' 359 if self._timeline_frame.playhead
is None:
364 return self._timeline_frame._start_stamp
370 :return: time of the next message before the current playhead position,''rospy.Time'' 372 if self._timeline_frame.playhead
is None:
377 return self._timeline_frame._end_stamp
383 self._player.resume()
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'' 394 QMessageBox.Warning,
'Exclamation',
'Background operation already running:\n\n%s' %
406 if len(self.
_bags) > 0:
408 self._timeline_frame.play_region[0],
409 self._timeline_frame.play_region[1])
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'' 428 total_messages = len(bag_entries)
431 if total_messages == 0:
432 QMessageBox(QMessageBox.Warning,
'rqt_bag',
'No messages found', QMessageBox.Ok).exec_()
440 QMessageBox(QMessageBox.Warning,
'rqt_bag',
441 'Error opening bag file [%s] for writing' % path, QMessageBox.Ok).exec_()
448 args=(export_bag, topics, start_stamp, end_stamp, bag_entries))
449 self._export_thread.start()
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'' 459 total_messages = len(bag_entries)
460 update_step = max(1, total_messages / 100)
464 for bag, entry
in bag_entries:
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)))
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
483 self.status_bar_changed_signal.emit()
490 self.status_bar_changed_signal.emit()
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_()
499 return bag._read_message(position)
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)
512 self._timeline_frame.on_mouse_up(event)
515 self._timeline_frame.on_mouse_move(event)
518 self._timeline_frame.on_mousewheel(event)
523 self._timeline_frame.zoom_in()
526 self._timeline_frame.zoom_out()
529 self._timeline_frame.reset_zoom()
532 self._timeline_frame.translate_timeline_left()
535 self._timeline_frame.translate_timeline_right()
539 return self.
_player and self._player.is_publishing(topic)
545 self._player.start_publishing(topic)
552 self._player.stop_publishing(topic)
560 self._player.start_clock_publishing()
561 except Exception
as ex:
562 qWarning(
'Error starting player; aborting publish: %s' % str(ex))
569 for topic
in self._timeline_frame.topics:
573 for topic
in self._timeline_frame.topics:
590 play_all = property(_get_play_all, _set_play_all)
601 moves the playhead to the next position based on the desired position 616 Moves the playhead a fixed distance into the future based on the current play speed 618 if self.
play_speed == 0.0
or not self._timeline_frame.playhead:
623 now = rospy.Time.from_sec(time.time())
627 new_playhead = self.end_stamp
629 new_playhead = self._timeline_frame.playhead + \
632 start_stamp, end_stamp = self._timeline_frame.play_region
634 if new_playhead > end_stamp:
637 new_playhead = start_stamp
639 new_playhead = end_stamp
641 new_playhead = end_stamp
646 elif new_playhead < start_stamp:
649 new_playhead = end_stamp
651 new_playhead = start_stamp
653 new_playhead = start_stamp
656 self._timeline_frame.playhead = new_playhead
663 Move the playhead to the next message 665 if self.
play_speed <= 0.0
or not self._timeline_frame.playhead:
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)
683 self._timeline_frame.playhead = next_message_time
687 self.
last_frame = rospy.Time.from_sec(time.time())
692 def record_bag(self, filename, all=True, topics=[], regex=False, limit=0):
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)))
702 self.
add_bag(self._recorder.bag)
704 self._recorder.start()
707 self._timeline_frame._index_cache_thread.period = 0.1
713 self._recorder.toggle_paused()
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
724 if not self._timeline_frame.topics
or topic
not in self._timeline_frame.topics:
733 with self._timeline_frame.index_cache_cv:
734 self._timeline_frame.invalidated_caches.add(topic)
735 self._timeline_frame.index_cache_cv.notify()
740 listener.timeline_changed()
741 except Exception
as ex:
742 qWarning(
'Error calling timeline_changed on %s: %s' % (type(listener), str(ex)))
750 self._views.append(frame)
756 self._listeners.setdefault(topic, []).append(listener)
759 MessageListenerThread(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)
772 if len(topic_listeners) == 0:
785 if self._timeline_frame._paused:
795 elif play_speed < 0.0:
804 play_speed = property(_get_play_speed, _set_play_speed)
814 self.
last_frame = rospy.Time.from_sec(time.time())
816 self._play_timer.start()
820 self._play_timer.stop()
836 new_play_speed = -1.0
853 self._timeline_frame.playhead = self._timeline_frame.play_region[0]
856 self._timeline_frame.playhead = self._timeline_frame.play_region[1]
def toggle_play_all(self)
def navigate_fastforward(self)
def translate_timeline_right(self)
def _get_start_stamp(self)
def step_next_message(self)
def toggle_recording(self)
def get_previous_message_time(self)
def add_listener(self, topic, listener)
def get_next_message_time(self)
def copy_region_to_bag(self, filename)
def record_bag(self, filename, all=True, topics=[], regex=False, limit=0)
def get_entry_after(self, t)
def navigate_previous(self)
def _set_play_speed(self, play_speed)
def on_mousewheel(self, event)
def _get_play_speed(self)
def is_publishing(self, topic)
def navigate_rewind(self)
def get_datatype(self, topic)
def stop_publishing(self, topic)
def start_background_task(self, background_task)
def __init__(self, context, publish_clock)
def has_listeners(self, topic)
def on_mouse_down(self, event)
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_topics_by_datatype(self)
def get_entries(self, topics, start_stamp, end_stamp)
def start_publishing(self, topic)
def on_mouse_move(self, event)
def _message_recorded(self, topic, msg, t)
_message_listener_threads
def translate_timeline_left(self)
def set_publishing_state(self, start_publishing)
def on_mouse_up(self, event)
def stop_background_task(self)
def _export_region(self, path, topics, start_stamp, end_stamp)
def get_entry_before(self, t)
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)