bag_timeline.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2012, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions
00008 # are met:
00009 #
00010 #  * Redistributions of source code must retain the above copyright
00011 #    notice, this list of conditions and the following disclaimer.
00012 #  * Redistributions in binary form must reproduce the above
00013 #    copyright notice, this list of conditions and the following
00014 #    disclaimer in the documentation and/or other materials provided
00015 #    with the distribution.
00016 #  * Neither the name of Willow Garage, Inc. nor the names of its
00017 #    contributors may be used to endorse or promote products derived
00018 #    from this software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 # POSSIBILITY OF SUCH DAMAGE.
00032 
00033 import rospy
00034 import rosbag
00035 import time
00036 import threading
00037 
00038 
00039 from python_qt_binding.QtCore import Qt, QTimer, qWarning, Signal
00040 from python_qt_binding.QtWidgets import QGraphicsScene, QMessageBox
00041 
00042 from rqt_bag import bag_helper
00043 
00044 from .timeline_frame import TimelineFrame
00045 from .message_listener_thread import MessageListenerThread
00046 from .message_loader_thread import MessageLoaderThread
00047 from .player import Player
00048 from .recorder import Recorder
00049 from .timeline_menu import TimelinePopupMenu
00050 
00051 
00052 class BagTimeline(QGraphicsScene):
00053 
00054     """
00055     BagTimeline contains bag files, all information required to display the bag data visualization
00056     on the screen Also handles events
00057     """
00058     status_bar_changed_signal = Signal()
00059     selected_region_changed = Signal(rospy.Time, rospy.Time)
00060 
00061     def __init__(self, context, publish_clock):
00062         """
00063         :param context:
00064             plugin context hook to enable adding rqt_bag plugin widgets as ROS_GUI snapin panes,
00065             ''PluginContext''
00066         """
00067         super(BagTimeline, self).__init__()
00068         self._bags = []
00069         self._bag_lock = threading.RLock()
00070 
00071         self.background_task = None  # Display string
00072         self.background_task_cancel = False
00073 
00074         # Playing / Recording
00075         self._playhead_lock = threading.RLock()
00076         self._max_play_speed = 1024.0  # fastest X play speed
00077         self._min_play_speed = 1.0 / 1024.0  # slowest X play speed
00078         self._play_speed = 0.0
00079         self._play_all = False
00080         self._playhead_positions_cvs = {}
00081         self._playhead_positions = {}  # topic -> (bag, position)
00082         self._message_loaders = {}
00083         self._messages_cvs = {}
00084         self._messages = {}  # topic -> (bag, msg_data)
00085         self._message_listener_threads = {}  # listener -> MessageListenerThread
00086         self._player = False
00087         self._publish_clock = publish_clock
00088         self._recorder = None
00089         self.last_frame = None
00090         self.last_playhead = None
00091         self.desired_playhead = None
00092         self.wrap = True  # should the playhead wrap when it reaches the end?
00093         self.stick_to_end = False  # should the playhead stick to the end?
00094         self._play_timer = QTimer()
00095         self._play_timer.timeout.connect(self.on_idle)
00096         self._play_timer.setInterval(3)
00097 
00098         # Plugin popup management
00099         self._context = context
00100         self.popups = {}
00101         self._views = []
00102         self._listeners = {}
00103 
00104         # Initialize scene
00105         # the timeline renderer fixes use of black pens and fills, so ensure we fix white here for
00106         # contrast. Otherwise a dark qt theme will default it to black and the frame render
00107         # pen will be unreadable
00108         self.setBackgroundBrush(Qt.white)
00109         self._timeline_frame = TimelineFrame(self)
00110         self._timeline_frame.setPos(0, 0)
00111         self.addItem(self._timeline_frame)
00112 
00113         self.background_progress = 0
00114         self.__closed = False
00115 
00116     def get_context(self):
00117         """
00118         :returns: the ROS_GUI context, 'PluginContext'
00119         """
00120         return self._context
00121 
00122     def handle_close(self):
00123         """
00124         Cleans up the timeline, bag and any threads
00125         """
00126         if self.__closed:
00127             return
00128         else:
00129             self.__closed = True
00130         self._play_timer.stop()
00131         for topic in self._get_topics():
00132             self.stop_publishing(topic)
00133             self._message_loaders[topic].stop()
00134         if self._player:
00135             self._player.stop()
00136         if self._recorder:
00137             self._recorder.stop()
00138         if self.background_task is not None:
00139             self.background_task_cancel = True
00140         self._timeline_frame.handle_close()
00141         for bag in self._bags:
00142             bag.close()
00143         for frame in self._views:
00144             if frame.parent():
00145                 self._context.remove_widget(frame)
00146 
00147     # Bag Management and access
00148     def add_bag(self, bag):
00149         """
00150         creates an indexing thread for each new topic in the bag
00151         fixes the boarders and notifies the indexing thread to index the new items bags
00152         :param bag: ros bag file, ''rosbag.bag''
00153         """
00154         self._bags.append(bag)
00155 
00156         bag_topics = bag_helper.get_topics(bag)
00157 
00158         new_topics = set(bag_topics) - set(self._timeline_frame.topics)
00159 
00160         for topic in new_topics:
00161             self._playhead_positions_cvs[topic] = threading.Condition()
00162             self._messages_cvs[topic] = threading.Condition()
00163             self._message_loaders[topic] = MessageLoaderThread(self, topic)
00164 
00165         self._timeline_frame._start_stamp = self._get_start_stamp()
00166         self._timeline_frame._end_stamp = self._get_end_stamp()
00167         self._timeline_frame.topics = self._get_topics()
00168         self._timeline_frame._topics_by_datatype = self._get_topics_by_datatype()
00169         # If this is the first bag, reset the timeline
00170         if self._timeline_frame._stamp_left is None:
00171             self._timeline_frame.reset_timeline()
00172 
00173         # Invalidate entire index cache for all topics in this bag
00174         with self._timeline_frame.index_cache_cv:
00175             for topic in bag_topics:
00176                 self._timeline_frame.invalidated_caches.add(topic)
00177                 if topic in self._timeline_frame.index_cache:
00178                     del self._timeline_frame.index_cache[topic]
00179 
00180             self._timeline_frame.index_cache_cv.notify()
00181 
00182     def file_size(self):
00183         with self._bag_lock:
00184             return sum(b.size for b in self._bags)
00185 
00186     # TODO Rethink API and if these need to be visible
00187     def _get_start_stamp(self):
00188         """
00189         :return: first stamp in the bags, ''rospy.Time''
00190         """
00191         with self._bag_lock:
00192             start_stamp = None
00193             for bag in self._bags:
00194                 bag_start_stamp = bag_helper.get_start_stamp(bag)
00195                 if bag_start_stamp is not None and \
00196                         (start_stamp is None or bag_start_stamp < start_stamp):
00197                     start_stamp = bag_start_stamp
00198             return start_stamp
00199 
00200     def _get_end_stamp(self):
00201         """
00202         :return: last stamp in the bags, ''rospy.Time''
00203         """
00204         with self._bag_lock:
00205             end_stamp = None
00206             for bag in self._bags:
00207                 bag_end_stamp = bag_helper.get_end_stamp(bag)
00208                 if bag_end_stamp is not None and (end_stamp is None or bag_end_stamp > end_stamp):
00209                     end_stamp = bag_end_stamp
00210             return end_stamp
00211 
00212     def _get_topics(self):
00213         """
00214         :return: sorted list of topic names, ''list(str)''
00215         """
00216         with self._bag_lock:
00217             topics = set()
00218             for bag in self._bags:
00219                 for topic in bag_helper.get_topics(bag):
00220                     topics.add(topic)
00221             return sorted(topics)
00222 
00223     def _get_topics_by_datatype(self):
00224         """
00225         :return: dict of list of topics for each datatype, ''dict(datatype:list(topic))''
00226         """
00227         with self._bag_lock:
00228             topics_by_datatype = {}
00229             for bag in self._bags:
00230                 for datatype, topics in bag_helper.get_topics_by_datatype(bag).items():
00231                     topics_by_datatype.setdefault(datatype, []).extend(topics)
00232             return topics_by_datatype
00233 
00234     def get_datatype(self, topic):
00235         """
00236         :return: datatype associated with a topic, ''str''
00237         :raises: if there are multiple datatypes assigned to a single topic, ''Exception''
00238         """
00239         with self._bag_lock:
00240             datatype = None
00241             for bag in self._bags:
00242                 bag_datatype = bag_helper.get_datatype(bag, topic)
00243                 if datatype and bag_datatype and (bag_datatype != datatype):
00244                     raise Exception('topic %s has multiple datatypes: %s and %s' %
00245                                     (topic, datatype, bag_datatype))
00246                 if bag_datatype:
00247                     datatype = bag_datatype
00248             return datatype
00249 
00250     def get_entries(self, topics, start_stamp, end_stamp):
00251         """
00252         generator function for bag entries
00253         :param topics: list of topics to query, ''list(str)''
00254         :param start_stamp: stamp to start at, ''rospy.Time''
00255         :param end_stamp: stamp to end at, ''rospy,Time''
00256         :returns: entries the bag file, ''msg''
00257         """
00258         with self._bag_lock:
00259             from rosbag import bag  # for _mergesort
00260             bag_entries = []
00261             for b in self._bags:
00262                 bag_start_time = bag_helper.get_start_stamp(b)
00263                 if bag_start_time is not None and bag_start_time > end_stamp:
00264                     continue
00265 
00266                 bag_end_time = bag_helper.get_end_stamp(b)
00267                 if bag_end_time is not None and bag_end_time < start_stamp:
00268                     continue
00269 
00270                 connections = list(b._get_connections(topics))
00271                 bag_entries.append(b._get_entries(connections, start_stamp, end_stamp))
00272 
00273             for entry, _ in bag._mergesort(bag_entries, key=lambda entry: entry.time):
00274                 yield entry
00275 
00276     def get_entries_with_bags(self, topic, start_stamp, end_stamp):
00277         """
00278         generator function for bag entries
00279         :param topics: list of topics to query, ''list(str)''
00280         :param start_stamp: stamp to start at, ''rospy.Time''
00281         :param end_stamp: stamp to end at, ''rospy,Time''
00282         :returns: tuple of (bag, entry) for the entries in the bag file, ''(rosbag.bag, msg)''
00283         """
00284         with self._bag_lock:
00285             from rosbag import bag  # for _mergesort
00286 
00287             bag_entries = []
00288             bag_by_iter = {}
00289             for b in self._bags:
00290                 bag_start_time = bag_helper.get_start_stamp(b)
00291                 if bag_start_time is not None and bag_start_time > end_stamp:
00292                     continue
00293 
00294                 bag_end_time = bag_helper.get_end_stamp(b)
00295                 if bag_end_time is not None and bag_end_time < start_stamp:
00296                     continue
00297 
00298                 connections = list(b._get_connections(topic))
00299                 it = iter(b._get_entries(connections, start_stamp, end_stamp))
00300                 bag_by_iter[it] = b
00301                 bag_entries.append(it)
00302 
00303             for entry, it in bag._mergesort(bag_entries, key=lambda entry: entry.time):
00304                 yield bag_by_iter[it], entry
00305 
00306     def get_entry(self, t, topic):
00307         """
00308         Access a bag entry
00309         :param t: time, ''rospy.Time''
00310         :param topic: the topic to be accessed, ''str''
00311         :return: tuple of (bag, entry) corisponding to time t and topic, ''(rosbag.bag, msg)''
00312         """
00313         with self._bag_lock:
00314             entry_bag, entry = None, None
00315             for bag in self._bags:
00316                 bag_entry = bag._get_entry(t, bag._get_connections(topic))
00317                 if bag_entry and (not entry or bag_entry.time > entry.time):
00318                     entry_bag, entry = bag, bag_entry
00319 
00320             return entry_bag, entry
00321 
00322     def get_entry_before(self, t):
00323         """
00324         Access a bag entry
00325         :param t: time, ''rospy.Time''
00326         :return: tuple of (bag, entry) corresponding to time t, ''(rosbag.bag, msg)''
00327         """
00328         with self._bag_lock:
00329             entry_bag, entry = None, None
00330             for bag in self._bags:
00331                 bag_entry = bag._get_entry(t - rospy.Duration(0, 1), bag._get_connections())
00332                 if bag_entry and (not entry or bag_entry.time < entry.time):
00333                     entry_bag, entry = bag, bag_entry
00334 
00335             return entry_bag, entry
00336 
00337     def get_entry_after(self, t):
00338         """
00339         Access a bag entry
00340         :param t: time, ''rospy.Time''
00341         :return: tuple of (bag, entry) corisponding to time t, ''(rosbag.bag, msg)''
00342         """
00343         with self._bag_lock:
00344             entry_bag, entry = None, None
00345             for bag in self._bags:
00346                 bag_entry = bag._get_entry_after(t, bag._get_connections())
00347                 if bag_entry and (not entry or bag_entry.time < entry.time):
00348                     entry_bag, entry = bag, bag_entry
00349 
00350             return entry_bag, entry
00351 
00352     def get_next_message_time(self):
00353         """
00354         :return: time of the next message after the current playhead position,''rospy.Time''
00355         """
00356         if self._timeline_frame.playhead is None:
00357             return None
00358 
00359         _, entry = self.get_entry_after(self._timeline_frame.playhead)
00360         if entry is None:
00361             return self._timeline_frame._start_stamp
00362 
00363         return entry.time
00364 
00365     def get_previous_message_time(self):
00366         """
00367         :return: time of the next message before the current playhead position,''rospy.Time''
00368         """
00369         if self._timeline_frame.playhead is None:
00370             return None
00371 
00372         _, entry = self.get_entry_before(self._timeline_frame.playhead)
00373         if entry is None:
00374             return self._timeline_frame._end_stamp
00375 
00376         return entry.time
00377 
00378     def resume(self):
00379         if (self._player):
00380             self._player.resume()
00381 
00382     # Copy messages to...
00383 
00384     def start_background_task(self, background_task):
00385         """
00386         Verify that a background task is not currently running before starting a new one
00387         :param background_task: name of the background task, ''str''
00388         """
00389         if self.background_task is not None:
00390             QMessageBox(
00391                 QMessageBox.Warning, 'Exclamation', 'Background operation already running:\n\n%s' %
00392                 self.background_task, QMessageBox.Ok).exec_()
00393             return False
00394 
00395         self.background_task = background_task
00396         self.background_task_cancel = False
00397         return True
00398 
00399     def stop_background_task(self):
00400         self.background_task = None
00401 
00402     def copy_region_to_bag(self, filename):
00403         if len(self._bags) > 0:
00404             self._export_region(filename, self._timeline_frame.topics,
00405                                 self._timeline_frame.play_region[0],
00406                                 self._timeline_frame.play_region[1])
00407 
00408     def _export_region(self, path, topics, start_stamp, end_stamp):
00409         """
00410         Starts a thread to save the current selection to a new bag file
00411         :param path: filesystem path to write to, ''str''
00412         :param topics: topics to write to the file, ''list(str)''
00413         :param start_stamp: start of area to save, ''rospy.Time''
00414         :param end_stamp: end of area to save, ''rospy.Time''
00415         """
00416         if not self.start_background_task('Copying messages to "%s"' % path):
00417             return
00418         # TODO implement a status bar area with information on the current save status
00419         bag_entries = list(self.get_entries_with_bags(topics, start_stamp, end_stamp))
00420 
00421         if self.background_task_cancel:
00422             return
00423 
00424         # Get the total number of messages to copy
00425         total_messages = len(bag_entries)
00426 
00427         # If no messages, prompt the user and return
00428         if total_messages == 0:
00429             QMessageBox(QMessageBox.Warning, 'rqt_bag', 'No messages found', QMessageBox.Ok).exec_()
00430             self.stop_background_task()
00431             return
00432 
00433         # Open the path for writing
00434         try:
00435             export_bag = rosbag.Bag(path, 'w')
00436         except Exception:
00437             QMessageBox(QMessageBox.Warning, 'rqt_bag',
00438                         'Error opening bag file [%s] for writing' % path, QMessageBox.Ok).exec_()
00439             self.stop_background_task()
00440             return
00441 
00442         # Run copying in a background thread
00443         self._export_thread = threading.Thread(
00444             target=self._run_export_region,
00445             args=(export_bag, topics, start_stamp, end_stamp, bag_entries))
00446         self._export_thread.start()
00447 
00448     def _run_export_region(self, export_bag, topics, start_stamp, end_stamp, bag_entries):
00449         """
00450         Threaded function that saves the current selection to a new bag file
00451         :param export_bag: bagfile to write to, ''rosbag.bag''
00452         :param topics: topics to write to the file, ''list(str)''
00453         :param start_stamp: start of area to save, ''rospy.Time''
00454         :param end_stamp: end of area to save, ''rospy.Time''
00455         """
00456         total_messages = len(bag_entries)
00457         update_step = max(1, total_messages / 100)
00458         message_num = 1
00459         progress = 0
00460         # Write out the messages
00461         for bag, entry in bag_entries:
00462             if self.background_task_cancel:
00463                 break
00464             try:
00465                 topic, msg, t = self.read_message(bag, entry.position)
00466                 export_bag.write(topic, msg, t)
00467             except Exception as ex:
00468                 qWarning('Error exporting message at position %s: %s' %
00469                          (str(entry.position), str(ex)))
00470                 export_bag.close()
00471                 self.stop_background_task()
00472                 return
00473 
00474             if message_num % update_step == 0 or message_num == total_messages:
00475                 new_progress = int(100.0 * (float(message_num) / total_messages))
00476                 if new_progress != progress:
00477                     progress = new_progress
00478                     if not self.background_task_cancel:
00479                         self.background_progress = progress
00480                         self.status_bar_changed_signal.emit()
00481 
00482             message_num += 1
00483 
00484         # Close the bag
00485         try:
00486             self.background_progress = 0
00487             self.status_bar_changed_signal.emit()
00488             export_bag.close()
00489         except Exception as ex:
00490             QMessageBox(QMessageBox.Warning, 'rqt_bag', 'Error closing bag file [%s]: %s' % (
00491                 export_bag.filename, str(ex)), QMessageBox.Ok).exec_()
00492         self.stop_background_task()
00493 
00494     def read_message(self, bag, position):
00495         with self._bag_lock:
00496             return bag._read_message(position)
00497 
00498     # Mouse events
00499     def on_mouse_down(self, event):
00500         if event.buttons() == Qt.LeftButton:
00501             self._timeline_frame.on_left_down(event)
00502         elif event.buttons() == Qt.MidButton:
00503             self._timeline_frame.on_middle_down(event)
00504         elif event.buttons() == Qt.RightButton:
00505             topic = self._timeline_frame.map_y_to_topic(self.views()[0].mapToScene(event.pos()).y())
00506             TimelinePopupMenu(self, event, topic)
00507 
00508     def on_mouse_up(self, event):
00509         self._timeline_frame.on_mouse_up(event)
00510 
00511     def on_mouse_move(self, event):
00512         self._timeline_frame.on_mouse_move(event)
00513 
00514     def on_mousewheel(self, event):
00515         self._timeline_frame.on_mousewheel(event)
00516 
00517     # Zooming
00518 
00519     def zoom_in(self):
00520         self._timeline_frame.zoom_in()
00521 
00522     def zoom_out(self):
00523         self._timeline_frame.zoom_out()
00524 
00525     def reset_zoom(self):
00526         self._timeline_frame.reset_zoom()
00527 
00528     def translate_timeline_left(self):
00529         self._timeline_frame.translate_timeline_left()
00530 
00531     def translate_timeline_right(self):
00532         self._timeline_frame.translate_timeline_right()
00533 
00534     # Publishing
00535     def is_publishing(self, topic):
00536         return self._player and self._player.is_publishing(topic)
00537 
00538     def start_publishing(self, topic):
00539         if not self._player and not self._create_player():
00540             return False
00541 
00542         self._player.start_publishing(topic)
00543         return True
00544 
00545     def stop_publishing(self, topic):
00546         if not self._player:
00547             return False
00548 
00549         self._player.stop_publishing(topic)
00550         return True
00551 
00552     def _create_player(self):
00553         if not self._player:
00554             try:
00555                 self._player = Player(self)
00556                 if self._publish_clock:
00557                     self._player.start_clock_publishing()
00558             except Exception as ex:
00559                 qWarning('Error starting player; aborting publish: %s' % str(ex))
00560                 return False
00561 
00562         return True
00563 
00564     def set_publishing_state(self, start_publishing):
00565         if start_publishing:
00566             for topic in self._timeline_frame.topics:
00567                 if not self.start_publishing(topic):
00568                     break
00569         else:
00570             for topic in self._timeline_frame.topics:
00571                 self.stop_publishing(topic)
00572 
00573     # property: play_all
00574     def _get_play_all(self):
00575         return self._play_all
00576 
00577     def _set_play_all(self, play_all):
00578         if play_all == self._play_all:
00579             return
00580 
00581         self._play_all = not self._play_all
00582 
00583         self.last_frame = None
00584         self.last_playhead = None
00585         self.desired_playhead = None
00586 
00587     play_all = property(_get_play_all, _set_play_all)
00588 
00589     def toggle_play_all(self):
00590         self.play_all = not self.play_all
00591 
00592     # Playing
00593     def on_idle(self):
00594         self._step_playhead()
00595 
00596     def _step_playhead(self):
00597         """
00598         moves the playhead to the next position based on the desired position
00599         """
00600         # Reset when the playing mode switchs
00601         if self._timeline_frame.playhead != self.last_playhead:
00602             self.last_frame = None
00603             self.last_playhead = None
00604             self.desired_playhead = None
00605 
00606         if self._play_all:
00607             self.step_next_message()
00608         else:
00609             self.step_fixed()
00610 
00611     def step_fixed(self):
00612         """
00613         Moves the playhead a fixed distance into the future based on the current play speed
00614         """
00615         if self.play_speed == 0.0 or not self._timeline_frame.playhead:
00616             self.last_frame = None
00617             self.last_playhead = None
00618             return
00619 
00620         now = rospy.Time.from_sec(time.time())
00621         if self.last_frame:
00622             # Get new playhead
00623             if self.stick_to_end:
00624                 new_playhead = self.end_stamp
00625             else:
00626                 new_playhead = self._timeline_frame.playhead + \
00627                     rospy.Duration.from_sec((now - self.last_frame).to_sec() * self.play_speed)
00628 
00629                 start_stamp, end_stamp = self._timeline_frame.play_region
00630 
00631                 if new_playhead > end_stamp:
00632                     if self.wrap:
00633                         if self.play_speed > 0.0:
00634                             new_playhead = start_stamp
00635                         else:
00636                             new_playhead = end_stamp
00637                     else:
00638                         new_playhead = end_stamp
00639 
00640                         if self.play_speed > 0.0:
00641                             self.stick_to_end = True
00642 
00643                 elif new_playhead < start_stamp:
00644                     if self.wrap:
00645                         if self.play_speed < 0.0:
00646                             new_playhead = end_stamp
00647                         else:
00648                             new_playhead = start_stamp
00649                     else:
00650                         new_playhead = start_stamp
00651 
00652             # Update the playhead
00653             self._timeline_frame.playhead = new_playhead
00654 
00655         self.last_frame = now
00656         self.last_playhead = self._timeline_frame.playhead
00657 
00658     def step_next_message(self):
00659         """
00660         Move the playhead to the next message
00661         """
00662         if self.play_speed <= 0.0 or not self._timeline_frame.playhead:
00663             self.last_frame = None
00664             self.last_playhead = None
00665             return
00666 
00667         if self.last_frame:
00668             if not self.desired_playhead:
00669                 self.desired_playhead = self._timeline_frame.playhead
00670             else:
00671                 delta = rospy.Time.from_sec(time.time()) - self.last_frame
00672                 if delta > rospy.Duration.from_sec(0.1):
00673                     delta = rospy.Duration.from_sec(0.1)
00674                 self.desired_playhead += delta
00675 
00676             # Get the occurrence of the next message
00677             next_message_time = self.get_next_message_time()
00678 
00679             if next_message_time < self.desired_playhead:
00680                 self._timeline_frame.playhead = next_message_time
00681             else:
00682                 self._timeline_frame.playhead = self.desired_playhead
00683 
00684         self.last_frame = rospy.Time.from_sec(time.time())
00685         self.last_playhead = self._timeline_frame.playhead
00686 
00687     # Recording
00688 
00689     def record_bag(self, filename, all=True, topics=[], regex=False, limit=0):
00690         try:
00691             self._recorder = Recorder(
00692                 filename, bag_lock=self._bag_lock, all=all, topics=topics, regex=regex, limit=limit)
00693         except Exception as ex:
00694             qWarning('Error opening bag for recording [%s]: %s' % (filename, str(ex)))
00695             return
00696 
00697         self._recorder.add_listener(self._message_recorded)
00698 
00699         self.add_bag(self._recorder.bag)
00700 
00701         self._recorder.start()
00702 
00703         self.wrap = False
00704         self._timeline_frame._index_cache_thread.period = 0.1
00705 
00706         self.update()
00707 
00708     def toggle_recording(self):
00709         if self._recorder:
00710             self._recorder.toggle_paused()
00711             self.update()
00712 
00713     def _message_recorded(self, topic, msg, t):
00714         if self._timeline_frame._start_stamp is None:
00715             self._timeline_frame._start_stamp = t
00716             self._timeline_frame._end_stamp = t
00717             self._timeline_frame._playhead = t
00718         elif self._timeline_frame._end_stamp is None or t > self._timeline_frame._end_stamp:
00719             self._timeline_frame._end_stamp = t
00720 
00721         if not self._timeline_frame.topics or topic not in self._timeline_frame.topics:
00722             self._timeline_frame.topics = self._get_topics()
00723             self._timeline_frame._topics_by_datatype = self._get_topics_by_datatype()
00724 
00725             self._playhead_positions_cvs[topic] = threading.Condition()
00726             self._messages_cvs[topic] = threading.Condition()
00727             self._message_loaders[topic] = MessageLoaderThread(self, topic)
00728 
00729         if self._timeline_frame._stamp_left is None:
00730             self.reset_zoom()
00731 
00732         # Notify the index caching thread that it has work to do
00733         with self._timeline_frame.index_cache_cv:
00734             self._timeline_frame.invalidated_caches.add(topic)
00735             self._timeline_frame.index_cache_cv.notify()
00736 
00737         if topic in self._listeners:
00738             for listener in self._listeners[topic]:
00739                 try:
00740                     listener.timeline_changed()
00741                 except Exception as ex:
00742                     qWarning('Error calling timeline_changed on %s: %s' % (type(listener), str(ex)))
00743 
00744     # Views / listeners
00745     def add_view(self, topic, frame):
00746         self._views.append(frame)
00747 
00748     def has_listeners(self, topic):
00749         return topic in self._listeners
00750 
00751     def add_listener(self, topic, listener):
00752         self._listeners.setdefault(topic, []).append(listener)
00753 
00754         self._message_listener_threads[(topic, listener)] = \
00755             MessageListenerThread(self, topic, listener)
00756         # Notify the message listeners
00757         self._message_loaders[topic].reset()
00758         with self._playhead_positions_cvs[topic]:
00759             self._playhead_positions_cvs[topic].notify_all()
00760 
00761         self.update()
00762 
00763     def remove_listener(self, topic, listener):
00764         topic_listeners = self._listeners.get(topic)
00765         if topic_listeners is not None and listener in topic_listeners:
00766             topic_listeners.remove(listener)
00767 
00768             if len(topic_listeners) == 0:
00769                 del self._listeners[topic]
00770 
00771             # Stop the message listener thread
00772             if (topic, listener) in self._message_listener_threads:
00773                 self._message_listener_threads[(topic, listener)].stop()
00774                 del self._message_listener_threads[(topic, listener)]
00775             self.update()
00776 
00777     # Playhead
00778 
00779     # property: play_speed
00780     def _get_play_speed(self):
00781         if self._timeline_frame._paused:
00782             return 0.0
00783         return self._play_speed
00784 
00785     def _set_play_speed(self, play_speed):
00786         if play_speed == self._play_speed:
00787             return
00788 
00789         if play_speed > 0.0:
00790             self._play_speed = min(self._max_play_speed, max(self._min_play_speed, play_speed))
00791         elif play_speed < 0.0:
00792             self._play_speed = max(-self._max_play_speed, min(-self._min_play_speed, play_speed))
00793         else:
00794             self._play_speed = play_speed
00795 
00796         if self._play_speed < 1.0:
00797             self.stick_to_end = False
00798 
00799         self.update()
00800     play_speed = property(_get_play_speed, _set_play_speed)
00801 
00802     def toggle_play(self):
00803         if self._play_speed != 0.0:
00804             self.play_speed = 0.0
00805         else:
00806             self.play_speed = 1.0
00807 
00808     def navigate_play(self):
00809         self.play_speed = 1.0
00810         self.last_frame = rospy.Time.from_sec(time.time())
00811         self.last_playhead = self._timeline_frame.playhead
00812         self._play_timer.start()
00813 
00814     def navigate_stop(self):
00815         self.play_speed = 0.0
00816         self._play_timer.stop()
00817 
00818     def navigate_previous(self):
00819         self.navigate_stop()
00820         self._timeline_frame.playhead = self.get_previous_message_time()
00821         self.last_playhead = self._timeline_frame.playhead
00822 
00823     def navigate_next(self):
00824         self.navigate_stop()
00825         self._timeline_frame.playhead = self.get_next_message_time()
00826         self.last_playhead = self._timeline_frame.playhead
00827 
00828     def navigate_rewind(self):
00829         if self._play_speed < 0.0:
00830             new_play_speed = self._play_speed * 2.0
00831         elif self._play_speed == 0.0:
00832             new_play_speed = -1.0
00833         else:
00834             new_play_speed = self._play_speed * 0.5
00835 
00836         self.play_speed = new_play_speed
00837 
00838     def navigate_fastforward(self):
00839         if self._play_speed > 0.0:
00840             new_play_speed = self._play_speed * 2.0
00841         elif self._play_speed == 0.0:
00842             new_play_speed = 2.0
00843         else:
00844             new_play_speed = self._play_speed * 0.5
00845 
00846         self.play_speed = new_play_speed
00847 
00848     def navigate_start(self):
00849         self._timeline_frame.playhead = self._timeline_frame.play_region[0]
00850 
00851     def navigate_end(self):
00852         self._timeline_frame.playhead = self._timeline_frame.play_region[1]


rqt_bag
Author(s): Aaron Blasdel, Tim Field
autogenerated on Thu Jun 6 2019 18:52:48