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


rqt_bag
Author(s): Aaron Blasdel, Tim Field
autogenerated on Thu Aug 17 2017 02:19:26