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


rqt_bag
Author(s): Aaron Blasdel, Tim Field
autogenerated on Wed Sep 16 2015 06:58:10