bag_widget.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 os
00034 import rospy
00035 import time
00036 
00037 from python_qt_binding import loadUi
00038 from python_qt_binding.QtCore import Qt
00039 from python_qt_binding.QtGui import QFileDialog, QGraphicsView, QIcon, QWidget
00040 
00041 import rosbag
00042 import bag_helper
00043 from .bag_timeline import BagTimeline
00044 
00045 
00046 class BagGraphicsView(QGraphicsView):
00047     def __init__(self, parent=None):
00048         super(BagGraphicsView, self).__init__()
00049 
00050 
00051 class BagWidget(QWidget):
00052     """
00053     Widget for use with Bag class to display and replay bag files
00054     Handles all widget callbacks and contains the instance of BagTimeline for storing visualizing bag data
00055     """
00056     def __init__(self, context):
00057         """
00058         :param context: plugin context hook to enable adding widgets as a ROS_GUI pane, ''PluginContext''
00059         """
00060         super(BagWidget, self).__init__()
00061         ui_file = os.path.join(os.path.dirname(os.path.realpath(__file__)), 'bag_widget.ui')
00062         loadUi(ui_file, self, {'BagGraphicsView': BagGraphicsView})
00063 
00064         self.setObjectName('BagWidget')
00065 
00066         self._timeline = BagTimeline(context)
00067         self.graphics_view.setScene(self._timeline)
00068 
00069         self.graphics_view.resizeEvent = self._resizeEvent
00070         self.graphics_view.setMouseTracking(True)
00071 
00072         self.play_icon = QIcon.fromTheme('media-playback-start')
00073         self.pause_icon = QIcon.fromTheme('media-playback-pause')
00074         self.play_button.setIcon(self.play_icon)
00075         self.begin_button.setIcon(QIcon.fromTheme('media-skip-backward'))
00076         self.end_button.setIcon(QIcon.fromTheme('media-skip-forward'))
00077         self.slower_button.setIcon(QIcon.fromTheme('media-seek-backward'))
00078         self.faster_button.setIcon(QIcon.fromTheme('media-seek-forward'))
00079         self.zoom_in_button.setIcon(QIcon.fromTheme('zoom-in'))
00080         self.zoom_out_button.setIcon(QIcon.fromTheme('zoom-out'))
00081         self.zoom_all_button.setIcon(QIcon.fromTheme('zoom-original'))
00082         self.thumbs_button.setIcon(QIcon.fromTheme('insert-image'))
00083         self.record_button.setIcon(QIcon.fromTheme('media-record'))
00084         self.load_button.setIcon(QIcon.fromTheme('document-open'))
00085         self.save_button.setIcon(QIcon.fromTheme('document-save'))
00086 
00087         self.play_button.clicked[bool].connect(self._handle_play_clicked)
00088         self.thumbs_button.clicked[bool].connect(self._handle_thumbs_clicked)
00089         self.zoom_in_button.clicked[bool].connect(self._handle_zoom_in_clicked)
00090         self.zoom_out_button.clicked[bool].connect(self._handle_zoom_out_clicked)
00091         self.zoom_all_button.clicked[bool].connect(self._handle_zoom_all_clicked)
00092         self.faster_button.clicked[bool].connect(self._handle_faster_clicked)
00093         self.slower_button.clicked[bool].connect(self._handle_slower_clicked)
00094         self.begin_button.clicked[bool].connect(self._handle_begin_clicked)
00095         self.end_button.clicked[bool].connect(self._handle_end_clicked)
00096         self.record_button.clicked[bool].connect(self._handle_record_clicked)
00097         self.load_button.clicked[bool].connect(self._handle_load_clicked)
00098         self.save_button.clicked[bool].connect(self._handle_save_clicked)
00099         self.graphics_view.mousePressEvent = self._timeline.on_mouse_down
00100         self.graphics_view.mouseReleaseEvent = self._timeline.on_mouse_up
00101         self.graphics_view.mouseMoveEvent = self._timeline.on_mouse_move
00102         self.graphics_view.wheelEvent = self._timeline.on_mousewheel
00103         self.closeEvent = self.handle_close
00104         self.keyPressEvent = self.on_key_press
00105         # TODO when the closeEvent is properly called by ROS_GUI implement that event instead of destroyed
00106         self.destroyed.connect(self.handle_destroy)
00107 
00108         self.graphics_view.keyPressEvent = self.graphics_view_on_key_press
00109         self.play_button.setEnabled(False)
00110         self.thumbs_button.setEnabled(False)
00111         self.zoom_in_button.setEnabled(False)
00112         self.zoom_out_button.setEnabled(False)
00113         self.zoom_all_button.setEnabled(False)
00114         self.faster_button.setEnabled(False)
00115         self.slower_button.setEnabled(False)
00116         self.begin_button.setEnabled(False)
00117         self.end_button.setEnabled(False)
00118         self.save_button.setEnabled(False)
00119 
00120         self._recording = False
00121 
00122         self._timeline.status_bar_changed_signal.connect(self._update_status_bar)
00123 
00124     def graphics_view_on_key_press(self, event):
00125         key = event.key()
00126         if key in (Qt.Key_Left, Qt.Key_Right, Qt.Key_Up, Qt.Key_Down, Qt.Key_PageUp, Qt.Key_PageDown):
00127             # This causes the graphics view to ignore these keys so they can be caught by the bag_widget keyPressEvent
00128             event.ignore()
00129         else:
00130             # Maintains functionality for all other keys QGraphicsView implements
00131             QGraphicsView.keyPressEvent(self.graphics_view, event)
00132 
00133     # callbacks for ui events
00134     def on_key_press(self, event):
00135         key = event.key()
00136         if key == Qt.Key_Space:
00137             self._timeline.toggle_play()
00138         elif key == Qt.Key_Home:
00139             self._timeline.navigate_start()
00140         elif key == Qt.Key_End:
00141             self._handle_end_clicked()
00142         elif key == Qt.Key_Plus or key == Qt.Key_Equal:
00143             self._handle_faster_clicked()
00144         elif key == Qt.Key_Minus:
00145             self._handle_slower_clicked()
00146         elif key == Qt.Key_Left:
00147             self._timeline.translate_timeline_left()
00148         elif key == Qt.Key_Right:
00149             self._timeline.translate_timeline_right()
00150         elif key == Qt.Key_Up or key == Qt.Key_PageUp:
00151             self._handle_zoom_in_clicked()
00152         elif key == Qt.Key_Down or key == Qt.Key_PageDown:
00153             self._handle_zoom_out_clicked()
00154 
00155     def handle_destroy(self, args):
00156         self._timeline.handle_close()
00157 
00158     def handle_close(self, event):
00159         self.shutdown_all()
00160 
00161         event.accept()
00162 
00163     def _resizeEvent(self, event):
00164         # TODO The -2 allows a buffer zone to make sure the scroll bars do not appear when not needed. On some systems (Lucid) this doesn't function properly
00165         # need to look at a method to determine the maximum size of the scene that will maintain a proper no scrollbar fit in the view.
00166         self.graphics_view.scene().setSceneRect(0, 0, self.graphics_view.width() - 2, max(self.graphics_view.height() - 2, self._timeline._timeline_frame._history_bottom))
00167 
00168     def _handle_publish_clicked(self, checked):
00169         self._timeline.set_publishing_state(checked)
00170 
00171     def _handle_play_clicked(self, checked):
00172         if checked:
00173             self.play_button.setIcon(self.pause_icon)
00174             self._timeline.navigate_play()
00175         else:
00176             self.play_button.setIcon(self.play_icon)
00177             self._timeline.navigate_stop()
00178 
00179     def _handle_faster_clicked(self):
00180         self._timeline.navigate_fastforward()
00181 
00182     def _handle_slower_clicked(self):
00183         self._timeline.navigate_rewind()
00184 
00185     def _handle_begin_clicked(self):
00186         self._timeline.navigate_start()
00187 
00188     def _handle_end_clicked(self):
00189         self._timeline.navigate_end()
00190 
00191     def _handle_thumbs_clicked(self, checked):
00192         self._timeline._timeline_frame.toggle_renderers()
00193 
00194     def _handle_zoom_all_clicked(self):
00195         self._timeline.reset_zoom()
00196 
00197     def _handle_zoom_out_clicked(self):
00198         self._timeline.zoom_out()
00199 
00200     def _handle_zoom_in_clicked(self):
00201         self._timeline.zoom_in()
00202 
00203     def _handle_record_clicked(self):
00204         if self._recording:
00205             self._timeline.toggle_recording()
00206             return
00207         # TODO verify master is still running
00208         filename = QFileDialog.getSaveFileName(self, self.tr('Select prefix for new Bag File'), '.', self.tr('Bag files {.bag} (*.bag)'))
00209         if filename[0] != '':
00210             prefix = filename[0].strip()
00211 
00212             # Get filename to record to
00213             record_filename = time.strftime('%Y-%m-%d-%H-%M-%S.bag', time.localtime(time.time()))
00214             if prefix.endswith('.bag'):
00215                 prefix = prefix[:-len('.bag')]
00216             if prefix:
00217                 record_filename = '%s_%s' % (prefix, record_filename)
00218 
00219             rospy.loginfo('Recording to %s.' % record_filename)
00220 
00221             #TODO Implement recording of topic subsets, regex limiting and by number of messages per topic
00222             self.load_button.setEnabled(False)
00223             self._recording = True
00224             self._timeline.record_bag(record_filename)
00225 
00226     def _handle_load_clicked(self):
00227         filename = QFileDialog.getOpenFileName(self, self.tr('Load from File'), '.', self.tr('Bag files {.bag} (*.bag)'))
00228         if filename[0] != '':
00229             bag = rosbag.Bag(filename[0])
00230             self.play_button.setEnabled(True)
00231             self.thumbs_button.setEnabled(True)
00232             self.zoom_in_button.setEnabled(True)
00233             self.zoom_out_button.setEnabled(True)
00234             self.zoom_all_button.setEnabled(True)
00235             self.faster_button.setEnabled(True)
00236             self.slower_button.setEnabled(True)
00237             self.begin_button.setEnabled(True)
00238             self.end_button.setEnabled(True)
00239             self.save_button.setEnabled(True)
00240             self.record_button.setEnabled(False)
00241             self._timeline.add_bag(bag)
00242 
00243     def _handle_save_clicked(self):
00244         filename = QFileDialog.getSaveFileName(self, self.tr('Save selected region to file...'), '.', self.tr('Bag files {.bag} (*.bag)'))
00245         if filename[0] != '':
00246             self._timeline.copy_region_to_bag(filename[0])
00247 
00248     def _update_status_bar(self):
00249         if self._timeline._timeline_frame.playhead is None or self._timeline._timeline_frame.start_stamp is None:
00250             return
00251         # TODO Figure out why this function is causing a "RuntimeError: wrapped C/C++ object of %S has been deleted" on close if the playhead is moving
00252         try:
00253             # Background Process Status
00254             self.progress_bar.setValue(self._timeline.background_progress)
00255 
00256             # Raw timestamp
00257             self.stamp_label.setText('%d.%s' % (self._timeline._timeline_frame.playhead.secs, str(self._timeline._timeline_frame.playhead.nsecs)[:3]))
00258 
00259             # Human-readable time
00260             self.date_label.setText(bag_helper.stamp_to_str(self._timeline._timeline_frame.playhead))
00261 
00262             # Elapsed time (in seconds)
00263             self.seconds_label.setText('%.3fs' % (self._timeline._timeline_frame.playhead - self._timeline._timeline_frame.start_stamp).to_sec())
00264 
00265             # Play speed
00266             spd = self._timeline.play_speed
00267             if spd != 0.0:
00268                 if spd > 1.0:
00269                     spd_str = '>> %.0fx' % spd
00270                 elif spd == 1.0:
00271                     spd_str = '>'
00272                 elif spd > 0.0:
00273                     spd_str = '> 1/%.0fx' % (1.0 / spd)
00274                 elif spd > -1.0:
00275                     spd_str = '< 1/%.0fx' % (1.0 / -spd)
00276                 elif spd == 1.0:
00277                     spd_str = '<'
00278                 else:
00279                     spd_str = '<< %.0fx' % -spd
00280                 self.playspeed_label.setText(spd_str)
00281             else:
00282                 self.playspeed_label.setText('')
00283         except:
00284             return
00285     # Shutdown all members
00286 
00287     def shutdown_all(self):
00288         self._timeline.handle_close()


rqt_bag
Author(s): Aaron Blasdel
autogenerated on Fri Jan 3 2014 11:55:06