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


rqt_bag
Author(s): Aaron Blasdel, Tim Field
autogenerated on Thu Jun 6 2019 18:52:48