39 from python_qt_binding.QtCore
import Qt, QTimer, qWarning, Signal
40 from python_qt_binding.QtWidgets
import QGraphicsScene, QMessageBox
42 from rqt_bag
import bag_helper
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
55 BagTimeline contains bag files, all information required to display the bag data visualization 56 on the screen Also handles events 58 status_bar_changed_signal = Signal()
59 selected_region_changed = Signal(rospy.Time, rospy.Time)
64 plugin context hook to enable adding rqt_bag plugin widgets as ROS_GUI snapin panes, 95 self._play_timer.timeout.connect(self.
on_idle)
96 self._play_timer.setInterval(3)
108 self.setBackgroundBrush(Qt.white)
110 self._timeline_frame.setPos(0, 0)
118 :returns: the ROS_GUI context, 'PluginContext' 124 Cleans up the timeline, bag and any threads 130 self._play_timer.stop()
137 self._recorder.stop()
140 self._timeline_frame.handle_close()
141 for bag
in self.
_bags:
145 self._context.remove_widget(frame)
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'' 154 self._bags.append(bag)
156 bag_topics = bag_helper.get_topics(bag)
158 new_topics = set(bag_topics) - set(self._timeline_frame.topics)
160 for topic
in new_topics:
170 if self._timeline_frame._stamp_left
is None:
171 self._timeline_frame.reset_timeline()
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]
180 self._timeline_frame.index_cache_cv.notify()
184 return sum(b.size
for b
in self.
_bags)
189 :return: first stamp in the bags, ''rospy.Time'' 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
202 :return: last stamp in the bags, ''rospy.Time'' 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
214 :return: sorted list of topic names, ''list(str)'' 218 for bag
in self.
_bags:
219 for topic
in bag_helper.get_topics(bag):
221 return sorted(topics)
225 :return: dict of list of topics for each datatype, ''dict(datatype:list(topic))'' 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
236 :return: datatype associated with a topic, ''str'' 237 :raises: if there are multiple datatypes assigned to a single topic, ''Exception'' 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))
247 datatype = bag_datatype
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'' 259 from rosbag
import bag
262 bag_start_time = bag_helper.get_start_stamp(b)
263 if bag_start_time
is not None and bag_start_time > end_stamp:
266 bag_end_time = bag_helper.get_end_stamp(b)
267 if bag_end_time
is not None and bag_end_time < start_stamp:
270 connections = list(b._get_connections(topics))
271 bag_entries.append(b._get_entries(connections, start_stamp, end_stamp))
273 for entry, _
in bag._mergesort(bag_entries, key=
lambda entry: entry.time):
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)'' 285 from rosbag
import bag
290 bag_start_time = bag_helper.get_start_stamp(b)
291 if bag_start_time
is not None and bag_start_time > end_stamp:
294 bag_end_time = bag_helper.get_end_stamp(b)
295 if bag_end_time
is not None and bag_end_time < start_stamp:
298 connections = list(b._get_connections(topic))
299 it = iter(b._get_entries(connections, start_stamp, end_stamp))
301 bag_entries.append(it)
303 for entry, it
in bag._mergesort(bag_entries, key=
lambda entry: entry.time):
304 yield bag_by_iter[it], 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)'' 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
320 return entry_bag, entry
325 :param t: time, ''rospy.Time'' 326 :return: tuple of (bag, entry) corresponding to time t, ''(rosbag.bag, msg)'' 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
335 return entry_bag, entry
340 :param t: time, ''rospy.Time'' 341 :return: tuple of (bag, entry) corisponding to time t, ''(rosbag.bag, msg)'' 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
350 return entry_bag, entry
354 :return: time of the next message after the current playhead position,''rospy.Time'' 356 if self._timeline_frame.playhead
is None:
361 return self._timeline_frame._start_stamp
367 :return: time of the next message before the current playhead position,''rospy.Time'' 369 if self._timeline_frame.playhead
is None:
374 return self._timeline_frame._end_stamp
380 self._player.resume()
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'' 391 QMessageBox.Warning,
'Exclamation',
'Background operation already running:\n\n%s' %
403 if len(self.
_bags) > 0:
405 self._timeline_frame.play_region[0],
406 self._timeline_frame.play_region[1])
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'' 425 total_messages = len(bag_entries)
428 if total_messages == 0:
429 QMessageBox(QMessageBox.Warning,
'rqt_bag',
'No messages found', QMessageBox.Ok).exec_()
437 QMessageBox(QMessageBox.Warning,
'rqt_bag',
438 'Error opening bag file [%s] for writing' % path, QMessageBox.Ok).exec_()
445 args=(export_bag, topics, start_stamp, end_stamp, bag_entries))
446 self._export_thread.start()
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'' 456 total_messages = len(bag_entries)
457 update_step = max(1, total_messages / 100)
461 for bag, entry
in bag_entries:
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)))
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
480 self.status_bar_changed_signal.emit()
487 self.status_bar_changed_signal.emit()
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_()
496 return bag._read_message(position)
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)
509 self._timeline_frame.on_mouse_up(event)
512 self._timeline_frame.on_mouse_move(event)
515 self._timeline_frame.on_mousewheel(event)
520 self._timeline_frame.zoom_in()
523 self._timeline_frame.zoom_out()
526 self._timeline_frame.reset_zoom()
529 self._timeline_frame.translate_timeline_left()
532 self._timeline_frame.translate_timeline_right()
536 return self.
_player and self._player.is_publishing(topic)
542 self._player.start_publishing(topic)
549 self._player.stop_publishing(topic)
557 self._player.start_clock_publishing()
558 except Exception
as ex:
559 qWarning(
'Error starting player; aborting publish: %s' % str(ex))
566 for topic
in self._timeline_frame.topics:
570 for topic
in self._timeline_frame.topics:
587 play_all = property(_get_play_all, _set_play_all)
598 moves the playhead to the next position based on the desired position 613 Moves the playhead a fixed distance into the future based on the current play speed 615 if self.
play_speed == 0.0
or not self._timeline_frame.playhead:
620 now = rospy.Time.from_sec(time.time())
624 new_playhead = self.end_stamp
626 new_playhead = self._timeline_frame.playhead + \
629 start_stamp, end_stamp = self._timeline_frame.play_region
631 if new_playhead > end_stamp:
634 new_playhead = start_stamp
636 new_playhead = end_stamp
638 new_playhead = end_stamp
643 elif new_playhead < start_stamp:
646 new_playhead = end_stamp
648 new_playhead = start_stamp
650 new_playhead = start_stamp
653 self._timeline_frame.playhead = new_playhead
660 Move the playhead to the next message 662 if self.
play_speed <= 0.0
or not self._timeline_frame.playhead:
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)
680 self._timeline_frame.playhead = next_message_time
684 self.
last_frame = rospy.Time.from_sec(time.time())
689 def record_bag(self, filename, all=True, topics=[], regex=False, limit=0):
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)))
699 self.
add_bag(self._recorder.bag)
701 self._recorder.start()
704 self._timeline_frame._index_cache_thread.period = 0.1
710 self._recorder.toggle_paused()
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
721 if not self._timeline_frame.topics
or topic
not in self._timeline_frame.topics:
729 if self._timeline_frame._stamp_left
is None:
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)))
746 self._views.append(frame)
752 self._listeners.setdefault(topic, []).append(listener)
755 MessageListenerThread(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)
768 if len(topic_listeners) == 0:
781 if self._timeline_frame._paused:
791 elif play_speed < 0.0:
800 play_speed = property(_get_play_speed, _set_play_speed)
810 self.
last_frame = rospy.Time.from_sec(time.time())
812 self._play_timer.start()
816 self._play_timer.stop()
832 new_play_speed = -1.0
849 self._timeline_frame.playhead = self._timeline_frame.play_region[0]
852 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)