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 time
00035 
00036 import rospy
00037 import rospkg
00038 
00039 from python_qt_binding import loadUi
00040 from python_qt_binding.QtCore import Qt, qWarning, Signal
00041 from python_qt_binding.QtGui import QFileDialog, QGraphicsView, QIcon, QWidget
00042 
00043 import rosbag
00044 import bag_helper
00045 from .bag_timeline import BagTimeline
00046 from .topic_selection import TopicSelection
00047 
00048 
00049 class BagGraphicsView(QGraphicsView):
00050     def __init__(self, parent=None):
00051         super(BagGraphicsView, self).__init__()
00052 
00053 
00054 class BagWidget(QWidget):
00055     """
00056     Widget for use with Bag class to display and replay bag files
00057     Handles all widget callbacks and contains the instance of BagTimeline for storing visualizing bag data
00058     """
00059 
00060     set_status_text = Signal(str)
00061 
00062     def __init__(self, context, publish_clock):
00063         """
00064         :param context: plugin context hook to enable adding widgets as a ROS_GUI pane, ''PluginContext''
00065         """
00066         super(BagWidget, self).__init__()
00067         rp = rospkg.RosPack()
00068         ui_file = os.path.join(rp.get_path('rqt_bag'), 'resource', 'bag_widget.ui')
00069         loadUi(ui_file, self, {'BagGraphicsView': BagGraphicsView})
00070 
00071         self.setObjectName('BagWidget')
00072 
00073         self._timeline = BagTimeline(context, publish_clock)
00074         self.graphics_view.setScene(self._timeline)
00075 
00076         self.graphics_view.resizeEvent = self._resizeEvent
00077         self.graphics_view.setMouseTracking(True)
00078 
00079         self.play_icon = QIcon.fromTheme('media-playback-start')
00080         self.pause_icon = QIcon.fromTheme('media-playback-pause')
00081         self.play_button.setIcon(self.play_icon)
00082         self.begin_button.setIcon(QIcon.fromTheme('media-skip-backward'))
00083         self.end_button.setIcon(QIcon.fromTheme('media-skip-forward'))
00084         self.slower_button.setIcon(QIcon.fromTheme('media-seek-backward'))
00085         self.faster_button.setIcon(QIcon.fromTheme('media-seek-forward'))
00086         self.zoom_in_button.setIcon(QIcon.fromTheme('zoom-in'))
00087         self.zoom_out_button.setIcon(QIcon.fromTheme('zoom-out'))
00088         self.zoom_all_button.setIcon(QIcon.fromTheme('zoom-original'))
00089         self.thumbs_button.setIcon(QIcon.fromTheme('insert-image'))
00090         self.record_button.setIcon(QIcon.fromTheme('media-record'))
00091         self.load_button.setIcon(QIcon.fromTheme('document-open'))
00092         self.save_button.setIcon(QIcon.fromTheme('document-save'))
00093 
00094         self.play_button.clicked[bool].connect(self._handle_play_clicked)
00095         self.thumbs_button.clicked[bool].connect(self._handle_thumbs_clicked)
00096         self.zoom_in_button.clicked[bool].connect(self._handle_zoom_in_clicked)
00097         self.zoom_out_button.clicked[bool].connect(self._handle_zoom_out_clicked)
00098         self.zoom_all_button.clicked[bool].connect(self._handle_zoom_all_clicked)
00099         self.faster_button.clicked[bool].connect(self._handle_faster_clicked)
00100         self.slower_button.clicked[bool].connect(self._handle_slower_clicked)
00101         self.begin_button.clicked[bool].connect(self._handle_begin_clicked)
00102         self.end_button.clicked[bool].connect(self._handle_end_clicked)
00103         self.record_button.clicked[bool].connect(self._handle_record_clicked)
00104         self.load_button.clicked[bool].connect(self._handle_load_clicked)
00105         self.save_button.clicked[bool].connect(self._handle_save_clicked)
00106         self.graphics_view.mousePressEvent = self._timeline.on_mouse_down
00107         self.graphics_view.mouseReleaseEvent = self._timeline.on_mouse_up
00108         self.graphics_view.mouseMoveEvent = self._timeline.on_mouse_move
00109         self.graphics_view.wheelEvent = self._timeline.on_mousewheel
00110         self.closeEvent = self.handle_close
00111         self.keyPressEvent = self.on_key_press
00112         # TODO when the closeEvent is properly called by ROS_GUI implement that event instead of destroyed
00113         self.destroyed.connect(self.handle_destroy)
00114 
00115         self.graphics_view.keyPressEvent = self.graphics_view_on_key_press
00116         self.play_button.setEnabled(False)
00117         self.thumbs_button.setEnabled(False)
00118         self.zoom_in_button.setEnabled(False)
00119         self.zoom_out_button.setEnabled(False)
00120         self.zoom_all_button.setEnabled(False)
00121         self.faster_button.setEnabled(False)
00122         self.slower_button.setEnabled(False)
00123         self.begin_button.setEnabled(False)
00124         self.end_button.setEnabled(False)
00125         self.save_button.setEnabled(False)
00126 
00127         self._recording = False
00128 
00129         self._timeline.status_bar_changed_signal.connect(self._update_status_bar)
00130         self.set_status_text.connect(self._set_status_text)
00131 
00132     def graphics_view_on_key_press(self, event):
00133         key = event.key()
00134         if key in (Qt.Key_Left, Qt.Key_Right, Qt.Key_Up, Qt.Key_Down, Qt.Key_PageUp, Qt.Key_PageDown):
00135             # This causes the graphics view to ignore these keys so they can be caught by the bag_widget keyPressEvent
00136             event.ignore()
00137         else:
00138             # Maintains functionality for all other keys QGraphicsView implements
00139             QGraphicsView.keyPressEvent(self.graphics_view, event)
00140 
00141     # callbacks for ui events
00142     def on_key_press(self, event):
00143         key = event.key()
00144         if key == Qt.Key_Space:
00145             self._timeline.toggle_play()
00146         elif key == Qt.Key_Home:
00147             self._timeline.navigate_start()
00148         elif key == Qt.Key_End:
00149             self._handle_end_clicked()
00150         elif key == Qt.Key_Plus or key == Qt.Key_Equal:
00151             self._handle_faster_clicked()
00152         elif key == Qt.Key_Minus:
00153             self._handle_slower_clicked()
00154         elif key == Qt.Key_Left:
00155             self._timeline.translate_timeline_left()
00156         elif key == Qt.Key_Right:
00157             self._timeline.translate_timeline_right()
00158         elif key == Qt.Key_Up or key == Qt.Key_PageUp:
00159             self._handle_zoom_in_clicked()
00160         elif key == Qt.Key_Down or key == Qt.Key_PageDown:
00161             self._handle_zoom_out_clicked()
00162 
00163     def handle_destroy(self, args):
00164         self._timeline.handle_close()
00165 
00166     def handle_close(self, event):
00167         self.shutdown_all()
00168 
00169         event.accept()
00170 
00171     def _resizeEvent(self, event):
00172         # 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
00173         # 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.
00174         self.graphics_view.scene().setSceneRect(0, 0, self.graphics_view.width() - 2, max(self.graphics_view.height() - 2, self._timeline._timeline_frame._history_bottom))
00175 
00176     def _handle_publish_clicked(self, checked):
00177         self._timeline.set_publishing_state(checked)
00178 
00179     def _handle_play_clicked(self, checked):
00180         if checked:
00181             self.play_button.setIcon(self.pause_icon)
00182             self._timeline.navigate_play()
00183         else:
00184             self.play_button.setIcon(self.play_icon)
00185             self._timeline.navigate_stop()
00186 
00187     def _handle_faster_clicked(self):
00188         self._timeline.navigate_fastforward()
00189         self.play_button.setChecked(True)
00190         self.play_button.setIcon(self.pause_icon)
00191 
00192     def _handle_slower_clicked(self):
00193         self._timeline.navigate_rewind()
00194         self.play_button.setChecked(True)
00195         self.play_button.setIcon(self.pause_icon)
00196 
00197     def _handle_begin_clicked(self):
00198         self._timeline.navigate_start()
00199 
00200     def _handle_end_clicked(self):
00201         self._timeline.navigate_end()
00202 
00203     def _handle_thumbs_clicked(self, checked):
00204         self._timeline._timeline_frame.toggle_renderers()
00205 
00206     def _handle_zoom_all_clicked(self):
00207         self._timeline.reset_zoom()
00208 
00209     def _handle_zoom_out_clicked(self):
00210         self._timeline.zoom_out()
00211 
00212     def _handle_zoom_in_clicked(self):
00213         self._timeline.zoom_in()
00214 
00215     def _handle_record_clicked(self):
00216         if self._recording:
00217             self._timeline.toggle_recording()
00218             return
00219 
00220         #TODO Implement limiting by regex and by number of messages per topic
00221         self.topic_selection = TopicSelection()
00222         self.topic_selection.recordSettingsSelected.connect(self._on_record_settings_selected)
00223 
00224 
00225     def _on_record_settings_selected(self, all_topics, selected_topics):
00226         # TODO verify master is still running
00227         filename = QFileDialog.getSaveFileName(self, self.tr('Select prefix for new Bag File'), '.', self.tr('Bag files {.bag} (*.bag)'))
00228         if filename[0] != '':
00229             prefix = filename[0].strip()
00230 
00231             # Get filename to record to
00232             record_filename = time.strftime('%Y-%m-%d-%H-%M-%S.bag', time.localtime(time.time()))
00233             if prefix.endswith('.bag'):
00234                 prefix = prefix[:-len('.bag')]
00235             if prefix:
00236                 record_filename = '%s_%s' % (prefix, record_filename)
00237 
00238             rospy.loginfo('Recording to %s.' % record_filename)
00239 
00240             self.load_button.setEnabled(False)
00241             self._recording = True
00242             self._timeline.record_bag(record_filename, all_topics, selected_topics)
00243 
00244 
00245     def _handle_load_clicked(self):
00246         filename = QFileDialog.getOpenFileName(self, self.tr('Load from File'), '.', self.tr('Bag files {.bag} (*.bag)'))
00247         if filename[0] != '':
00248             self.load_bag(filename[0])
00249 
00250     def load_bag(self, filename):
00251         qWarning("Loading %s" % filename)
00252 
00253         # QProgressBar can EITHER: show text or show a bouncing loading bar,
00254         #  but apparently the text is hidden when the bounding loading bar is
00255         #  shown
00256         #self.progress_bar.setRange(0, 0)
00257         self.set_status_text.emit("Loading %s" % filename)
00258         #progress_format = self.progress_bar.format()
00259         #progress_text_visible = self.progress_bar.isTextVisible()
00260         #self.progress_bar.setFormat("Loading %s" % filename)
00261         #self.progress_bar.setTextVisible(True)
00262 
00263         bag = rosbag.Bag(filename)
00264         self.play_button.setEnabled(True)
00265         self.thumbs_button.setEnabled(True)
00266         self.zoom_in_button.setEnabled(True)
00267         self.zoom_out_button.setEnabled(True)
00268         self.zoom_all_button.setEnabled(True)
00269         self.faster_button.setEnabled(True)
00270         self.slower_button.setEnabled(True)
00271         self.begin_button.setEnabled(True)
00272         self.end_button.setEnabled(True)
00273         self.save_button.setEnabled(True)
00274         self.record_button.setEnabled(False)
00275         self._timeline.add_bag(bag)
00276         qWarning("Done loading %s" % filename )
00277         # put the progress bar back the way it was
00278         self.set_status_text.emit("")
00279         #self.progress_bar.setFormat(progress_format)
00280         #self.progress_bar.setTextVisible(progress_text_visible) # causes a segfault :(
00281         #self.progress_bar.setRange(0, 100)
00282         # self clear loading filename
00283 
00284     def _handle_save_clicked(self):
00285         filename = QFileDialog.getSaveFileName(self, self.tr('Save selected region to file...'), '.', self.tr('Bag files {.bag} (*.bag)'))
00286         if filename[0] != '':
00287             self._timeline.copy_region_to_bag(filename[0])
00288 
00289     def _set_status_text(self, text):
00290         if text:
00291             self.progress_bar.setFormat(text)
00292             self.progress_bar.setTextVisible(True)
00293         else:
00294             self.progress_bar.setTextVisible(False)
00295 
00296     def _update_status_bar(self):
00297         if self._timeline._timeline_frame.playhead is None or self._timeline._timeline_frame.start_stamp is None:
00298             return
00299         # 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
00300         try:
00301             # Background Process Status
00302             self.progress_bar.setValue(self._timeline.background_progress)
00303 
00304             # Raw timestamp
00305             self.stamp_label.setText('%.3fs' % self._timeline._timeline_frame.playhead.to_sec())
00306 
00307             # Human-readable time
00308             self.date_label.setText(bag_helper.stamp_to_str(self._timeline._timeline_frame.playhead))
00309 
00310             # Elapsed time (in seconds)
00311             self.seconds_label.setText('%.3fs' % (self._timeline._timeline_frame.playhead - self._timeline._timeline_frame.start_stamp).to_sec())
00312 
00313             # Play speed
00314             spd = self._timeline.play_speed
00315             if spd != 0.0:
00316                 if spd > 1.0:
00317                     spd_str = '>> %.0fx' % spd
00318                 elif spd == 1.0:
00319                     spd_str = '>'
00320                 elif spd > 0.0:
00321                     spd_str = '> 1/%.0fx' % (1.0 / spd)
00322                 elif spd > -1.0:
00323                     spd_str = '< 1/%.0fx' % (1.0 / -spd)
00324                 elif spd == 1.0:
00325                     spd_str = '<'
00326                 else:
00327                     spd_str = '<< %.0fx' % -spd
00328                 self.playspeed_label.setText(spd_str)
00329             else:
00330                 self.playspeed_label.setText('')
00331         except:
00332             return
00333     # Shutdown all members
00334 
00335     def shutdown_all(self):
00336         self._timeline.handle_close()


rqt_bag
Author(s): Aaron Blasdel, Tim Field
autogenerated on Mon Oct 6 2014 07:15:30