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


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