From 10b33b6adba44893626ac959a57998fbdf676f94 Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Thu, 26 Dec 2024 18:44:18 +0000 Subject: [PATCH 1/4] Add standard tests to rqt_bag. This ensures the package is up to our standards. Signed-off-by: Chris Lalancette --- rqt_bag/package.xml | 7 ++ rqt_bag/src/rqt_bag/__init__.py | 10 +- rqt_bag/src/rqt_bag/bag.py | 9 +- rqt_bag/src/rqt_bag/bag_helper.py | 3 +- rqt_bag/src/rqt_bag/bag_timeline.py | 94 ++++++++------ rqt_bag/src/rqt_bag/bag_widget.py | 35 +++--- rqt_bag/src/rqt_bag/index_cache_thread.py | 2 +- .../src/rqt_bag/message_listener_thread.py | 6 +- rqt_bag/src/rqt_bag/message_loader_thread.py | 3 +- rqt_bag/src/rqt_bag/node_selection.py | 17 +-- rqt_bag/src/rqt_bag/player.py | 24 ++-- rqt_bag/src/rqt_bag/plugins/message_view.py | 33 +++-- rqt_bag/src/rqt_bag/plugins/plugin.py | 7 +- rqt_bag/src/rqt_bag/plugins/raw_view.py | 32 ++--- .../src/rqt_bag/plugins/timeline_renderer.py | 5 +- .../src/rqt_bag/plugins/topic_message_view.py | 10 +- rqt_bag/src/rqt_bag/qos.py | 20 +-- rqt_bag/src/rqt_bag/recorder.py | 18 ++- rqt_bag/src/rqt_bag/rosbag2.py | 18 +-- rqt_bag/src/rqt_bag/timeline_cache.py | 28 +---- rqt_bag/src/rqt_bag/timeline_frame.py | 118 +++++++++++------- rqt_bag/src/rqt_bag/timeline_menu.py | 20 +-- rqt_bag/src/rqt_bag/topic_selection.py | 11 +- rqt_bag/test/test_copyright.py | 39 ++++-- rqt_bag/test/test_flake8.py | 41 ++++++ rqt_bag/test/test_pep257.py | 39 ++++++ rqt_bag/test/test_xmllint.py | 39 ++++++ 27 files changed, 428 insertions(+), 260 deletions(-) create mode 100644 rqt_bag/test/test_flake8.py create mode 100644 rqt_bag/test/test_pep257.py create mode 100644 rqt_bag/test/test_xmllint.py diff --git a/rqt_bag/package.xml b/rqt_bag/package.xml index 032b3ed..4f84789 100644 --- a/rqt_bag/package.xml +++ b/rqt_bag/package.xml @@ -16,13 +16,20 @@ Mabel Zhang Tim Field + ament_index_python + builtin_interfaces + python3-yaml python_qt_binding rclpy rosbag2_py + rosidl_runtime_py rqt_gui rqt_gui_py ament_copyright + ament_flake8 + ament_pep257 + ament_xmllint python3-pytest diff --git a/rqt_bag/src/rqt_bag/__init__.py b/rqt_bag/src/rqt_bag/__init__.py index fd2a20c..c9d6c53 100644 --- a/rqt_bag/src/rqt_bag/__init__.py +++ b/rqt_bag/src/rqt_bag/__init__.py @@ -26,8 +26,8 @@ # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -from rqt_bag import bag_helper -from rqt_bag.plugins.message_view import MessageView -from rqt_bag.plugins.topic_message_view import TopicMessageView -from rqt_bag.plugins.timeline_renderer import TimelineRenderer -from rqt_bag.timeline_cache import TimelineCache +from rqt_bag import bag_helper # noqa: F401 +from rqt_bag.plugins.message_view import MessageView # noqa: F401 +from rqt_bag.plugins.timeline_renderer import TimelineRenderer # noqa: F401 +from rqt_bag.plugins.topic_message_view import TopicMessageView # noqa: F401 +from rqt_bag.timeline_cache import TimelineCache # noqa: F401 diff --git a/rqt_bag/src/rqt_bag/bag.py b/rqt_bag/src/rqt_bag/bag.py index 64dc345..f8b0c5a 100644 --- a/rqt_bag/src/rqt_bag/bag.py +++ b/rqt_bag/src/rqt_bag/bag.py @@ -26,8 +26,8 @@ # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -import os import argparse +import os import threading from qt_gui.plugin import Plugin @@ -36,13 +36,12 @@ class Bag(Plugin): - - """ - Subclass of Plugin to provide interactive bag visualization, playing(publishing) and recording - """ + """Provide interactive bag visualization, playing(publishing) and recording.""" def __init__(self, context): """ + Construct a Bag object. + :param context: plugin context hook to enable adding widgets as a ROS_GUI pane, ''PluginContext'' """ diff --git a/rqt_bag/src/rqt_bag/bag_helper.py b/rqt_bag/src/rqt_bag/bag_helper.py index d094e23..4d5913d 100644 --- a/rqt_bag/src/rqt_bag/bag_helper.py +++ b/rqt_bag/src/rqt_bag/bag_helper.py @@ -32,7 +32,8 @@ def to_sec(t): - """Convert an rclpy.time.Time or rclpy.duration.Duration to a float representing seconds. + """ + Convert an rclpy.time.Time or rclpy.duration.Duration to a float representing seconds. @param t: @type t: rclpy.time.Time or rclpy.duration.Duration: diff --git a/rqt_bag/src/rqt_bag/bag_timeline.py b/rqt_bag/src/rqt_bag/bag_timeline.py index 07aabde..101775b 100644 --- a/rqt_bag/src/rqt_bag/bag_timeline.py +++ b/rqt_bag/src/rqt_bag/bag_timeline.py @@ -26,36 +26,40 @@ # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -import rosbag2_py -import time import threading - +import time from python_qt_binding.QtCore import qDebug, Qt, QTimer, qWarning, Signal from python_qt_binding.QtWidgets import QGraphicsScene, QMessageBox -from rqt_bag import bag_helper from rclpy.duration import Duration from rclpy.time import Time -from .timeline_frame import TimelineFrame +import rosbag2_py + +from rqt_bag import bag_helper + from .message_listener_thread import MessageListenerThread from .message_loader_thread import MessageLoaderThread from .player import Player from .recorder import Recorder +from .timeline_frame import TimelineFrame class BagTimeline(QGraphicsScene): - """ - BagTimeline contains bag files, all information required to display the bag data visualization - on the screen Also handles events + BagTimeline contains bag files, and all info required to display the bag data on the screen. + + It also handles related events. """ + status_bar_changed_signal = Signal() selected_region_changed = Signal(Time, Time) def __init__(self, context, publish_clock): """ + Construct a BagTimeline object. + :param context: plugin context hook to enable adding rqt_bag plugin widgets as ROS_GUI snapin panes, ''PluginContext'' @@ -115,6 +119,8 @@ def __init__(self, context, publish_clock): def get_context(self): """ + Get the gui context. + :returns: the ROS_GUI context, 'PluginContext' """ return self._context @@ -124,9 +130,7 @@ def stop_recorder(self): self._recorder.stop() def handle_close(self): - """ - Cleans up the timeline, bag and any threads - """ + """Clean up the timeline, bag and any threads.""" if self.__closed: return else: @@ -148,8 +152,9 @@ def handle_close(self): # Bag Management and access def add_bag(self, bag): """ - creates an indexing thread for each new topic in the bag - fixes the boarders and notifies the indexing thread to index the new items bags + Create an indexing thread for each new topic in the bag. + + Fixes the boarders and notifies the indexing thread to index the new items bags. :param bag: ros bag file, ''rosbag2.bag'' """ self._bags.append(bag) @@ -188,6 +193,8 @@ def file_size(self): # TODO Rethink API and if these need to be visible def _get_start_stamp(self): """ + Get the first stamp in the bags. + :return: first stamp in the bags, ''rclpy.time.Time'' """ with self._bag_lock: @@ -201,6 +208,8 @@ def _get_start_stamp(self): def _get_end_stamp(self): """ + Get the last stamp in the bags. + :return: last stamp in the bags, ''rclpy.time.Time'' """ with self._bag_lock: @@ -213,6 +222,8 @@ def _get_end_stamp(self): def _get_topics(self): """ + Get a sorted list of topic names. + :return: sorted list of topic names, ''list(str)'' """ with self._bag_lock: @@ -224,6 +235,8 @@ def _get_topics(self): def _get_topics_by_datatype(self): """ + Get a dict of topics by datatype. + :return: dict of list of topics for each datatype, ''dict(datatype:list(topic))'' """ with self._bag_lock: @@ -235,6 +248,8 @@ def _get_topics_by_datatype(self): def get_datatype(self, topic): """ + Get the datatype for a topic. + :return: datatype associated with a topic, ''str'' :raises: if there are multiple datatypes assigned to a single topic, ''Exception'' """ @@ -251,7 +266,8 @@ def get_datatype(self, topic): def get_entries(self, topics, start_stamp, end_stamp): """ - generator function for bag entries + Get a generator for bag entries. + :param topics: list of topics to query, ''list(str)'' :param start_stamp: stamp to start at, ''rclpy.time.Time'' :param end_stamp: stamp to end at, ''rclpy.time,Time'' @@ -280,7 +296,8 @@ def get_entries(self, topics, start_stamp, end_stamp): def get_entries_with_bags(self, topic, start_stamp, end_stamp): """ - generator function for bag entries + Get a generator of bag entries. + :param topics: list of topics to query, ''list(str)'' :param start_stamp: stamp to start at, ''rclpy.time.Time'' :param end_stamp: stamp to end at, ''rclpy.time,Time'' @@ -288,7 +305,6 @@ def get_entries_with_bags(self, topic, start_stamp, end_stamp): """ with self._bag_lock: bag_entries = [] - bag_by_iter = {} for b in self._bags: bag_start_time = b.get_earliest_timestamp() if bag_start_time is not None and bag_start_time > end_stamp: @@ -306,7 +322,8 @@ def get_entries_with_bags(self, topic, start_stamp, end_stamp): def get_entry(self, t, topic): """ - Access a bag entry + Access a bag entry. + :param t: time, ''rclpy.time.Time'' :param topic: the topic to be accessed, ''str'' :return: tuple of (bag, entry) corresponding to time t and topic, ''(rosbag2.bag, msg)'' @@ -322,7 +339,8 @@ def get_entry(self, t, topic): def get_entry_before(self, t): """ - Access a bag entry + Access a bag entry. + :param t: time, ''rclpy.time.Time'' :return: tuple of (bag, entry) corresponding to time t, ''(rosbag2.bag, msg)'' """ @@ -337,7 +355,8 @@ def get_entry_before(self, t): def get_entry_after(self, t, topic=None): """ - Access a bag entry + Access a bag entry. + :param t: time, ''rclpy.time.Time'' :return: tuple of (bag, entry) corresponding to time t, ''(rosbag2.bag, msg)'' """ @@ -352,6 +371,8 @@ def get_entry_after(self, t, topic=None): def get_next_message_time(self): """ + Get the time of the next message. + :return: time of the next message after the current playhead position,''rclpy.time.Time'' """ if self._timeline_frame.playhead is None: @@ -365,6 +386,8 @@ def get_next_message_time(self): def get_previous_message_time(self): """ + Get the time of the previous message. + :return: time of the next message before the current playhead position,''rclpy.time.Time'' """ if self._timeline_frame.playhead is None: @@ -384,7 +407,8 @@ def resume(self): def start_background_task(self, background_task): """ - Verify that a background task is not currently running before starting a new one + Verify that a background task is not currently running before starting a new one. + :param background_task: name of the background task, ''str'' """ if self.background_task is not None: @@ -408,7 +432,8 @@ def copy_region_to_bag(self, filename): def _export_region(self, path, topics, start_stamp, end_stamp): """ - Starts a thread to save the current selection to a new bag file + Start a thread to save the current selection to a new bag file. + :param path: filesystem path to write to, ''str'' :param topics: topics to write to the file, ''list(str)'' :param start_stamp: start of area to save, ''rclpy.time.Time'' @@ -427,7 +452,8 @@ def _export_region(self, path, topics, start_stamp, end_stamp): # If no messages, prompt the user and return if total_messages == 0: - QMessageBox(QMessageBox.Warning, 'rqt_bag', 'No messages found', QMessageBox.Ok).exec_() + QMessageBox(QMessageBox.Warning, 'rqt_bag', 'No messages found', + QMessageBox.Ok).exec_() self.stop_background_task() return @@ -450,12 +476,15 @@ def _export_region(self, path, topics, start_stamp, end_stamp): # Run copying in a background thread self._export_thread = threading.Thread( target=self._run_export_region, - args=(rosbag_writer, topics, start_stamp, end_stamp, bag_entries, path, self.serialization_format)) + args=(rosbag_writer, topics, start_stamp, end_stamp, bag_entries, path, + self.serialization_format)) self._export_thread.start() - def _run_export_region(self, rosbag_writer, topics, start_stamp, end_stamp, bag_entries, export_filename, serialization_format): + def _run_export_region(self, rosbag_writer, topics, start_stamp, end_stamp, bag_entries, + export_filename, serialization_format): """ - Threaded function that saves the current selection to a new bag file + Threaded function that saves the current selection to a new bag file. + :param export_bag: bagfile to write to, ''rosbag.bag'' :param topics: topics to write to the file, ''list(str)'' :param start_stamp: start of area to save, ''rclpy.time.Time'' @@ -589,9 +618,7 @@ def on_idle(self): self._step_playhead() def _step_playhead(self): - """ - moves the playhead to the next position based on the desired position - """ + """Move the playhead to the next position based on the desired position.""" # Reset when the playing mode switches. A rclpy.time.Time cannot be compared to a NoneType if self.last_playhead is None or self._timeline_frame.playhead != self.last_playhead: self.last_frame = None @@ -604,9 +631,7 @@ def _step_playhead(self): self.step_fixed() def step_fixed(self): - """ - Moves the playhead a fixed distance into the future based on the current play speed - """ + """Move the playhead a fixed distance into the future based on the current play speed.""" if self.play_speed == 0.0 or not self._timeline_frame.playhead: self.last_frame = None self.last_playhead = None @@ -651,9 +676,7 @@ def step_fixed(self): self.last_playhead = self._timeline_frame.playhead def step_next_message(self): - """ - Move the playhead to the next message - """ + """Move the playhead to the next message.""" if self.play_speed <= 0.0 or not self._timeline_frame.playhead: self.last_frame = None self.last_playhead = None @@ -729,7 +752,8 @@ def _message_recorded(self, topic, msg, t): try: listener.timeline_changed() except Exception as ex: - qWarning('Error calling timeline_changed on %s: %s' % (type(listener), str(ex))) + listen_type = type(listener) + qWarning('Error calling timeline_changed on %s: %s' % (listen_type, str(ex))) # Dynamically resize the timeline, if necessary, to make visible any new messages # that might otherwise have exceeded the bounds of the window diff --git a/rqt_bag/src/rqt_bag/bag_widget.py b/rqt_bag/src/rqt_bag/bag_widget.py index 71a3e5d..3115e33 100644 --- a/rqt_bag/src/rqt_bag/bag_widget.py +++ b/rqt_bag/src/rqt_bag/bag_widget.py @@ -26,23 +26,24 @@ # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. +import math import os import time -import math - from ament_index_python import get_resource -from rclpy import logging from python_qt_binding import loadUi from python_qt_binding.QtCore import qDebug, Qt, qWarning, Signal from python_qt_binding.QtGui import QIcon, QResizeEvent from python_qt_binding.QtWidgets import QFileDialog, QGraphicsView, QWidget +from rclpy import logging + from rqt_bag import bag_helper + from .bag_timeline import BagTimeline -from .topic_selection import TopicSelection from .rosbag2 import Rosbag2 +from .topic_selection import TopicSelection class BagGraphicsView(QGraphicsView): @@ -52,7 +53,6 @@ def __init__(self, parent=None): class BagWidget(QWidget): - """ Widget for use with Bag class to display and replay bag files. @@ -65,6 +65,8 @@ class BagWidget(QWidget): def __init__(self, context, publish_clock): """ + Construct a BagWidget object. + :param context: plugin context hook to enable adding widgets as a ROS_GUI pane, ''PluginContext'' """ @@ -251,7 +253,9 @@ def _handle_record_clicked(self): def _on_record_settings_selected(self, all_topics, selected_topics): # Get bag name to record to, prepopulating the dialog input with the current time proposed_filename = time.strftime('%Y-%m-%d-%H-%M-%S', time.localtime(time.time())) - filename = QFileDialog.getSaveFileName(self, self.tr('Select name for new rosbag'), proposed_filename) + filename = QFileDialog.getSaveFileName(self, + self.tr('Select name for new rosbag'), + proposed_filename) if filename[0] != '': record_filename = filename[0].strip() @@ -318,7 +322,7 @@ def load_bag(self, filename): self._timeline.add_bag(bag) qDebug("Done loading '%s'" % filename.encode(errors='replace')) # put the progress bar back the way it was - self.set_status_text.emit("") + self.set_status_text.emit('') # reset zoom to show entirety of all loaded bags self._timeline.reset_zoom() # After loading bag(s), force a resize event on the bag widget so that @@ -343,8 +347,9 @@ def _handle_save_clicked(self): # from loaded bags is available. # Get the bag name to save to, prepopulating the dialog input with the current time proposed_filename = time.strftime('%Y-%m-%d-%H-%M-%S', time.localtime(time.time())) - filename = \ - QFileDialog.getSaveFileName(self, self.tr('Save selected region...'), proposed_filename) + filename = QFileDialog.getSaveFileName(self, + self.tr('Save selected region...'), + proposed_filename) if filename[0] != '': self._timeline.copy_region_to_bag(filename[0]) @@ -365,7 +370,8 @@ def _filesize_to_str(self, size): return '0 B' def _stamp_to_str(self, t): - """Convert a rclpy.time.Time to a human-readable string. + """ + Convert a rclpy.time.Time to a human-readable string. @param t: time to convert @type t: rclpy.time.Time @@ -379,8 +385,8 @@ def _stamp_to_str(self, t): time.localtime(t_sec)) + '.%03d' % (t_nsec * 1e-9) def _update_status_bar(self): - if (self._timeline._timeline_frame.playhead is None or \ - self._timeline._timeline_frame.start_stamp is None): + if self._timeline._timeline_frame.playhead is None or \ + self._timeline._timeline_frame.start_stamp is None: return # 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 @@ -389,7 +395,8 @@ def _update_status_bar(self): self.progress_bar.setValue(self._timeline.background_progress) # Raw timestamp - self.stamp_label.setText('%.9fs' % bag_helper.to_sec(self._timeline._timeline_frame.playhead)) + playhead_sec = bag_helper.to_sec(self._timeline._timeline_frame.playhead) + self.stamp_label.setText('%.9fs' % playhead_sec) # Human-readable time self.date_label.setText( @@ -421,7 +428,7 @@ def _update_status_bar(self): self.playspeed_label.setText(spd_str) else: self.playspeed_label.setText('') - except Exception as e: + except Exception: return # Shutdown all members diff --git a/rqt_bag/src/rqt_bag/index_cache_thread.py b/rqt_bag/src/rqt_bag/index_cache_thread.py index da44d20..f349137 100644 --- a/rqt_bag/src/rqt_bag/index_cache_thread.py +++ b/rqt_bag/src/rqt_bag/index_cache_thread.py @@ -31,9 +31,9 @@ class IndexCacheThread(threading.Thread): - """ Updates invalid caches. + One thread per timeline. """ diff --git a/rqt_bag/src/rqt_bag/message_listener_thread.py b/rqt_bag/src/rqt_bag/message_listener_thread.py index 1d53522..17f9f4c 100644 --- a/rqt_bag/src/rqt_bag/message_listener_thread.py +++ b/rqt_bag/src/rqt_bag/message_listener_thread.py @@ -40,9 +40,9 @@ def __init__(self, data): class MessageListenerThread(threading.Thread): - """ Waits for new messages loaded on the given topic, then calls the message listener. + One thread per listener, topic pair. """ @@ -58,9 +58,7 @@ def __init__(self, timeline, topic, listener): self.start() def run(self): - """ - Thread body. loops and notifies the listener of new messages - """ + """Thread body. loops and notifies the listener of new messages.""" while not self._stop_flag: # Wait for a new message cv = self.timeline._messages_cvs[self.topic] diff --git a/rqt_bag/src/rqt_bag/message_loader_thread.py b/rqt_bag/src/rqt_bag/message_loader_thread.py index 434c50b..48efbe5 100644 --- a/rqt_bag/src/rqt_bag/message_loader_thread.py +++ b/rqt_bag/src/rqt_bag/message_loader_thread.py @@ -31,8 +31,7 @@ class MessageLoaderThread(threading.Thread): """ - Waits for a new playhead position on the given topic, then loads the message at that position - and notifies the view threads. + Waits for a playhead position on a topic, then loads that message and notifies view threads. One thread per topic. Maintains a cache of recently loaded messages. """ diff --git a/rqt_bag/src/rqt_bag/node_selection.py b/rqt_bag/src/rqt_bag/node_selection.py index e243790..de95ed1 100644 --- a/rqt_bag/src/rqt_bag/node_selection.py +++ b/rqt_bag/src/rqt_bag/node_selection.py @@ -27,7 +27,7 @@ # POSSIBILITY OF SUCH DAMAGE. from python_qt_binding.QtCore import Qt -from python_qt_binding.QtWidgets import QWidget, QVBoxLayout, QCheckBox, QScrollArea, QPushButton +from python_qt_binding.QtWidgets import QCheckBox, QPushButton, QScrollArea, QVBoxLayout, QWidget class NodeSelection(QWidget): @@ -37,11 +37,11 @@ def __init__(self, parent, node): self.parent_widget = parent self.node = node self.selected_nodes = [] - self.setWindowTitle("Select the nodes you want to record") + self.setWindowTitle('Select the nodes you want to record') self.resize(500, 700) self.area = QScrollArea(self) self.main_widget = QWidget(self.area) - self.ok_button = QPushButton("Done", self) + self.ok_button = QPushButton('Done', self) self.ok_button.clicked.connect(self.onButtonClicked) self.ok_button.setEnabled(False) self.main_vlayout = QVBoxLayout() @@ -59,7 +59,10 @@ def __init__(self, parent, node): def addCheckBox(self, node): node_name = node[0] node_namespace = node[1] - name = node_namespace + node_name if (node_namespace[-1] == '/') else node_namespace + '/' + node_name + if node_namespace[-1] == '/': + name = node_namespace + node_name + else: + name = node_namespace + '/' + node_name item = QCheckBox(name, self) item.stateChanged.connect(lambda x: self.updateNode(x, node)) self.selection_vlayout.addWidget(item) @@ -75,12 +78,12 @@ def updateNode(self, state, node): self.ok_button.setEnabled(False) def onButtonClicked(self): - # Get all of the topics for the selected nodes + # Get all of the topics for the selected nodes topics = set() for node in self.selected_nodes: - subscription_info_entries = self.node.get_publisher_names_and_types_by_node(node[0], node[1]) - for subscription_info in subscription_info_entries: + sub_info_entries = self.node.get_publisher_names_and_types_by_node(node[0], node[1]) + for subscription_info in sub_info_entries: topics.add(subscription_info[0]) # Select each of these in the (parent) topics dialog diff --git a/rqt_bag/src/rqt_bag/player.py b/rqt_bag/src/rqt_bag/player.py index 0ee3855..5d9b6d4 100644 --- a/rqt_bag/src/rqt_bag/player.py +++ b/rqt_bag/src/rqt_bag/player.py @@ -26,9 +26,7 @@ # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -""" -Player listens to messages from the timeline and publishes them to ROS. -""" +"""Player listens to messages from the timeline and publishes them to ROS.""" from builtin_interfaces.msg import Time @@ -36,14 +34,11 @@ from rclpy.qos import QoSProfile from rosbag2_py import convert_rclcpp_qos_to_rclpy_qos -CLOCK_TOPIC = "/clock" +CLOCK_TOPIC = '/clock' class Player(QObject): - - """ - This object handles publishing messages as the playhead passes over their position - """ + """Handles publishing messages as the playhead passes over their position.""" def __init__(self, node, timeline): super(Player, self).__init__() @@ -89,7 +84,7 @@ def start_clock_publishing(self): def stop_clock_publishing(self): self._publish_clock = False if CLOCK_TOPIC in self._publishers: - self._node.destroy_publisher(self._publishers[topic]) + self._node.destroy_publisher(self._publishers[CLOCK_TOPIC]) del self._publishers[CLOCK_TOPIC] def stop(self): @@ -101,7 +96,8 @@ def create_publisher(self, topic, ros_message, offered_qos_profile): ros_msg_type = type(ros_message) try: # Publish based on the original recorded QoS settings - self._publishers[topic] = self._node.create_publisher(ros_msg_type, topic, qos_profile=offered_qos_profile) + self._publishers[topic] = self._node.create_publisher(ros_msg_type, topic, + qos_profile=offered_qos_profile) return True except Exception as ex: # Any errors, stop listening/publishing to this topic @@ -114,7 +110,8 @@ def create_publisher(self, topic, ros_message, offered_qos_profile): def message_viewed(self, bag, entry): """ - When a message is viewed publish it + Publish a message when it is viewed. + :param bag: the bag the message is in, ''rosbag.bag'' :param entry: the bag entry """ @@ -145,8 +142,9 @@ def message_cleared(self): def event(self, event): """ - This function will be called to process events posted by post_event - it will call message_cleared or message_viewed with the relevant data + Process events posted by post_event. + + It will call message_cleared or message_viewed with the relevant data. """ bag, entry = event.data if entry: diff --git a/rqt_bag/src/rqt_bag/plugins/message_view.py b/rqt_bag/src/rqt_bag/plugins/message_view.py index 8a428b8..0fc955c 100644 --- a/rqt_bag/src/rqt_bag/plugins/message_view.py +++ b/rqt_bag/src/rqt_bag/plugins/message_view.py @@ -26,18 +26,16 @@ # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. - from python_qt_binding.QtCore import QObject -import rosbag2_py - class MessageView(QObject): - """ - A message details renderer. When registered with rqt_bag, a MessageView is called - whenever the timeline playhead moves. + A message details renderer. + + When registered with rqt_bag, a MessageView is called whenever the timeline playhead moves. """ + name = 'Untitled' def __init__(self, timeline, topic): @@ -63,34 +61,33 @@ def message_viewed(self, *, bag, entry, ros_message, msg_type_name, topic): pass def message_cleared(self): - """ - Clear the currently viewed message (if any). - """ + """Clear the currently viewed message (if any).""" pass def timeline_changed(self): """ - Called when the messages in a timeline change, e.g. if a new message is recorded, or - a bag file is added + Update the timeline when it is changed. + + This callback is called e.g. if a new message is recorded, or a bag file is added. """ pass def close(self): - """ - Close the message view, releasing any resources. - """ + """Close the message view, releasing any resources.""" pass -# NOTE: event function should not be changed in subclasses + # NOTE: event function should not be changed in subclasses def event(self, event): """ - This function will be called to process events posted by post_event - it will call message_cleared or message_viewed with the relevant data + Process events posted by post_event. + + It will call message_cleared or message_viewed with the relevant data. """ bag, entry = event.data if entry: (ros_message, msg_type_name) = bag.deserialize_entry(entry) - self.message_viewed(bag=bag, entry=entry, ros_message=ros_message, msg_type_name=msg_type_name, topic=entry.topic) + self.message_viewed(bag=bag, entry=entry, ros_message=ros_message, + msg_type_name=msg_type_name, topic=entry.topic) else: self.message_cleared() return True diff --git a/rqt_bag/src/rqt_bag/plugins/plugin.py b/rqt_bag/src/rqt_bag/plugins/plugin.py index 2246c2d..4f0db81 100644 --- a/rqt_bag/src/rqt_bag/plugins/plugin.py +++ b/rqt_bag/src/rqt_bag/plugins/plugin.py @@ -28,7 +28,6 @@ class Plugin(object): - """ Interface for rqt_bag plugins. @@ -40,19 +39,21 @@ def __init__(self): pass def get_view_class(self): - """Return a class which is a child of rqt_bag.plugin.topic_message_view.TopicMessageView.""" + """Return class which is a child of rqt_bag.plugin.topic_message_view.TopicMessageView.""" raise NotImplementedError() def get_renderer_class(self): """ Return a class which is a child of rqt_bag.plugin.timeline_renderer.TimelineRenderer. + To omit the renderer component simply return None. """ return None def get_message_types(self): """ - Return alist of message types which this plugin operates on. + Return a list of message types which this plugin operates on. + To allow your plugin to be run on all message types return ['*']. """ return [] diff --git a/rqt_bag/src/rqt_bag/plugins/raw_view.py b/rqt_bag/src/rqt_bag/plugins/raw_view.py index af7d98c..5472ab6 100644 --- a/rqt_bag/src/rqt_bag/plugins/raw_view.py +++ b/rqt_bag/src/rqt_bag/plugins/raw_view.py @@ -25,24 +25,20 @@ # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -""" -Defines a raw view: a TopicMessageView that displays the message contents in a tree. -""" + +"""Defines a raw view: a TopicMessageView that displays the message contents in a tree.""" + import codecs import math -from rclpy.time import Time - from python_qt_binding.QtCore import Qt from python_qt_binding.QtWidgets import \ - QApplication, QAbstractItemView, QSizePolicy, QTreeWidget, QTreeWidgetItem, QWidget + QAbstractItemView, QApplication, QSizePolicy, QTreeWidget, QTreeWidgetItem, QWidget + +from rclpy.time import Time + from .topic_message_view import TopicMessageView -# compatibility fix for python2/3 -try: - long -except NameError: - long = int class RawView(TopicMessageView): name = 'Raw' @@ -53,6 +49,8 @@ class RawView(TopicMessageView): def __init__(self, timeline, parent, topic): """ + Construct a RawView object. + :param timeline: timeline data object, ''BagTimeline'' :param parent: widget that will be added to the ros_gui context, ''QWidget'' """ @@ -63,7 +61,8 @@ def __init__(self, timeline, parent, topic): parent.layout().addWidget(self.message_tree) def message_viewed(self, *, entry, ros_message, msg_type_name, **kwargs): - super(RawView, self).message_viewed(entry=entry, ros_message=ros_message, msg_type_name=msg_type_name) + super(RawView, self).message_viewed(entry=entry, + ros_message=ros_message, msg_type_name=msg_type_name) if ros_message is None: self.message_cleared() else: @@ -93,7 +92,8 @@ def msg(self): def set_message(self, msg, msg_type_name): """ - Clears the tree view and displays the new message + Clear the tree view and displays the new message. + :param msg: message object to display in the treeview, ''msg'' """ # Remember whether items were expanded or not before deleting @@ -191,8 +191,8 @@ def _add_msg_object(self, parent, path, name, obj, obj_type): else: subobjs = [] - if type(obj) in [int, long, float]: - if type(obj) == float: + if type(obj) in (int, float): + if type(obj) is float: obj_repr = '%.6f' % obj else: obj_repr = str(obj) @@ -202,7 +202,7 @@ def _add_msg_object(self, parent, path, name, obj, obj_type): else: label += ': %s' % obj_repr - elif type(obj) in [str, bool, int, long, float, complex, Time]: + elif type(obj) in (str, bool, int, float, complex, Time): # Ignore any binary data obj_repr = codecs.utf_8_decode(str(obj).encode(), 'ignore')[0] diff --git a/rqt_bag/src/rqt_bag/plugins/timeline_renderer.py b/rqt_bag/src/rqt_bag/plugins/timeline_renderer.py index 069b231..0551df6 100644 --- a/rqt_bag/src/rqt_bag/plugins/timeline_renderer.py +++ b/rqt_bag/src/rqt_bag/plugins/timeline_renderer.py @@ -30,7 +30,6 @@ class TimelineRenderer(QObject): - """ A custom renderer for interval of time of a topic on the timeline. @@ -73,7 +72,5 @@ def draw_timeline_segment(self, painter, topic, stamp_start, stamp_end, x, y, wi return False def close(self): - """ - Close the renderer, releasing any resources. - """ + """Close the renderer, releasing any resources.""" pass diff --git a/rqt_bag/src/rqt_bag/plugins/topic_message_view.py b/rqt_bag/src/rqt_bag/plugins/topic_message_view.py index e82040f..1d7ce92 100644 --- a/rqt_bag/src/rqt_bag/plugins/topic_message_view.py +++ b/rqt_bag/src/rqt_bag/plugins/topic_message_view.py @@ -26,18 +26,16 @@ # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -from .message_view import MessageView - from python_qt_binding.QtGui import QIcon from python_qt_binding.QtWidgets import QAction, QToolBar + from rclpy.time import Time +from .message_view import MessageView -class TopicMessageView(MessageView): - """ - A message view with a toolbar for navigating messages in a single topic. - """ +class TopicMessageView(MessageView): + """A message view with a toolbar for navigating messages in a single topic.""" def __init__(self, timeline, parent, topic): MessageView.__init__(self, timeline, topic) diff --git a/rqt_bag/src/rqt_bag/qos.py b/rqt_bag/src/rqt_bag/qos.py index 3dfa4f2..6653e9e 100644 --- a/rqt_bag/src/rqt_bag/qos.py +++ b/rqt_bag/src/rqt_bag/qos.py @@ -30,18 +30,15 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -""" -QoS-related utility functions -""" +"""QoS-related utility functions.""" -import yaml -import math +from rclpy.duration import Duration import rclpy.qos - from rclpy.qos import QoSProfile -from rclpy.duration import Duration from rclpy.time import Time +import yaml + def duration_to_node(duration): t = Time(nanoseconds=duration.nanoseconds) @@ -73,8 +70,11 @@ def qos_profiles_to_yaml(qos_profiles): def gen_subscriber_qos_profile(qos_profiles): - """Generate a single QoS profile for a subscriber from a set of QoS profiles (typically - acquired from an active set of publishers for a particular topic).""" + """ + Generate a single QoS profile for a subscriber from a set of QoS profiles. + + These are typically acquired from an active set of publishers for a particular topic. + """ if not qos_profiles: return QoSProfile(depth=10) @@ -90,7 +90,7 @@ def gen_subscriber_qos_profile(qos_profiles): def get_qos_profiles_for_topic(node, topic): - """Get the QoS profiles used by current publishers on a specific topic""" + """Get the QoS profiles used by current publishers on a specific topic.""" publishers_info = node.get_publishers_info_by_topic(topic) if publishers_info: # Get the QoS info for each of the current publishers on this topic diff --git a/rqt_bag/src/rqt_bag/recorder.py b/rqt_bag/src/rqt_bag/recorder.py index 5cefd54..2320a6e 100644 --- a/rqt_bag/src/rqt_bag/recorder.py +++ b/rqt_bag/src/rqt_bag/recorder.py @@ -28,30 +28,25 @@ """Recorder subscribes to ROS messages and writes them to a bag file.""" -try: - from queue import Queue - from queue import Empty -except ImportError: - from Queue import Queue - from Queue import Empty +from queue import Empty +from queue import Queue import re - import sys import threading import time from rclpy.clock import Clock, ClockType -from rclpy.duration import Duration from rclpy.serialization import serialize_message from rclpy.topic_or_service_is_hidden import topic_or_service_is_hidden + import rosbag2_py +from rosbag2_py import get_default_storage_id, to_rclcpp_qos_vector + from rosidl_runtime_py.utilities import get_message from .qos import gen_subscriber_qos_profile, get_qos_profiles_for_topic, qos_profiles_to_yaml from .rosbag2 import Rosbag2 -from rosbag2_py import get_default_storage_id, to_rclcpp_qos_vector - class Recorder(object): @@ -130,7 +125,8 @@ def _create_initial_rosbag(self, filename, topics): return Rosbag2(filename, recording=True, topics=topic_type_map) def add_listener(self, listener): - """Add a listener which gets called whenever a message is recorded. + """ + Add a listener which gets called whenever a message is recorded. @param listener: function to call @type listener: function taking (topic, message, time) diff --git a/rqt_bag/src/rqt_bag/rosbag2.py b/rqt_bag/src/rqt_bag/rosbag2.py index 49fc6e8..f43aae0 100644 --- a/rqt_bag/src/rqt_bag/rosbag2.py +++ b/rqt_bag/src/rqt_bag/rosbag2.py @@ -32,16 +32,17 @@ from collections import namedtuple import os +from rclpy import logging from rclpy.clock import Clock, ClockType from rclpy.duration import Duration -from rclpy import logging from rclpy.serialization import deserialize_message -import rosbag2_py -from rosidl_runtime_py.utilities import get_message +import rosbag2_py from rosbag2_py import get_default_storage_id, StorageFilter -WRITE_ONLY_MSG = "open for writing only, returning None" +from rosidl_runtime_py.utilities import get_message + +WRITE_ONLY_MSG = 'open for writing only, returning None' Entry = namedtuple('Entry', ['topic', 'data', 'timestamp']) @@ -112,12 +113,13 @@ def get_topics_by_type(self): return topics_by_type def get_entry(self, timestamp, topic=None): - """Get the (serialized) entry for a specific timestamp. + """ + Get the (serialized) entry for a specific timestamp. Returns the entry that is closest in time (<=) to the provided timestamp. """ if not self.reader: - self._logger.warn("get_entry - " + WRITE_ONLY_MSG) + self._logger.warn('get_entry - ' + WRITE_ONLY_MSG) return None self.reader.set_read_order(rosbag2_py.ReadOrder(reverse=True)) @@ -136,7 +138,7 @@ def get_entry(self, timestamp, topic=None): def get_entry_after(self, timestamp, topic=None): """Get the next entry after a given timestamp.""" if not self.reader: - self._logger.warn("get_entry_after - " + WRITE_ONLY_MSG) + self._logger.warn('get_entry_after - ' + WRITE_ONLY_MSG) return None self.reader.set_read_order(rosbag2_py.ReadOrder(reverse=False)) @@ -145,7 +147,7 @@ def get_entry_after(self, timestamp, topic=None): def get_entries_in_range(self, t_start, t_end, topic=None): if not self.reader: - self._logger.warn("get_entries_in_range - " + WRITE_ONLY_MSG) + self._logger.warn('get_entries_in_range - ' + WRITE_ONLY_MSG) return None self.reader.set_read_order(rosbag2_py.ReadOrder(reverse=False)) diff --git a/rqt_bag/src/rqt_bag/timeline_cache.py b/rqt_bag/src/rqt_bag/timeline_cache.py index d6cc26e..cbf555d 100644 --- a/rqt_bag/src/rqt_bag/timeline_cache.py +++ b/rqt_bag/src/rqt_bag/timeline_cache.py @@ -26,12 +26,8 @@ # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. - import bisect -try: - from queue import Queue -except ImportError: - from Queue import Queue +from queue import Queue import threading import time @@ -39,10 +35,7 @@ class TimelineCache(threading.Thread): - - """ - Caches items for timeline renderers - """ + """Caches items for timeline renderers.""" def __init__(self, loader, listener=None, max_cache_size=100): threading.Thread.__init__(self) @@ -78,11 +71,6 @@ def run(self): if self.listener: self.listener(topic, msg_stamp, item) -# else: -# try: -# qWarning('Failed to load:%s' % entry) -# except: -# qWarning('Failed to load cache item') self.queue.task_done() def enqueue(self, entry): @@ -136,9 +124,7 @@ def get_item(self, topic, stamp, time_threshold): return None def _update_last_accessed(self, topic, stamp): - """ - Maintains a sorted list of cache accesses by timestamp for each topic. - """ + """Maintain a sorted list of cache accesses by timestamp for each topic.""" with self.lock: access_time = time.time() @@ -154,7 +140,7 @@ def _update_last_accessed(self, topic, stamp): last_access = topic_item_access[stamp] index = bisect.bisect_left(topic_last_accessed, (last_access, )) - assert(topic_last_accessed[index][1] == stamp) + assert topic_last_accessed[index][1] == stamp del topic_last_accessed[index] @@ -162,16 +148,14 @@ def _update_last_accessed(self, topic, stamp): topic_item_access[stamp] = access_time def _limit_cache(self): - """ - Removes LRU's from cache until size of each topic's cache is <= max_cache_size. - """ + """Remove LRU's from cache until size of each topic's cache is <= max_cache_size.""" with self.lock: for topic, topic_cache in self.items.items(): while len(topic_cache) > self.max_cache_size: lru_stamp = self.last_accessed[topic][0][1] cache_index = bisect.bisect_left(topic_cache, (lru_stamp, )) - assert(topic_cache[cache_index][0] == lru_stamp) + assert topic_cache[cache_index][0] == lru_stamp del topic_cache[cache_index] del self.last_accessed[topic][0] diff --git a/rqt_bag/src/rqt_bag/timeline_frame.py b/rqt_bag/src/rqt_bag/timeline_frame.py index ee80aa3..cdfaa83 100644 --- a/rqt_bag/src/rqt_bag/timeline_frame.py +++ b/rqt_bag/src/rqt_bag/timeline_frame.py @@ -26,20 +26,21 @@ # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -from rclpy.time import Time -from rclpy.duration import Duration +import bisect +import threading from python_qt_binding.QtCore import qDebug, QPointF, QRectF, Qt, qWarning, Slot -from python_qt_binding.QtGui import QBrush, QCursor, QColor, QFont, \ - QFontMetrics, QPen, QPolygonF, QPalette -from python_qt_binding.QtWidgets import QGraphicsItem, QCheckBox +from python_qt_binding.QtGui import QBrush, QColor, QCursor, QFont, \ + QFontMetrics, QPalette, QPen, QPolygonF +from python_qt_binding.QtWidgets import QCheckBox, QGraphicsItem -import bisect -import threading +from rclpy.duration import Duration +from rclpy.time import Time + +from rqt_bag import bag_helper from .index_cache_thread import IndexCacheThread from .plugins.raw_view import RawView -from rqt_bag import bag_helper from .timeline_menu import TimelinePopupMenu @@ -59,9 +60,9 @@ def __init__(self, *, size, on_clicked): class _SelectionMode(object): - """ - SelectionMode states consolidated for readability + SelectionMode states consolidated for readability. + NONE = no region marked or started LEFT_MARKED = one end of the region has been marked MARKED = both ends of the region have been marked @@ -69,6 +70,7 @@ class _SelectionMode(object): MOVE_LEFT = region is marked; currently changing the left boundry of the selected region MOVE_RIGHT = region is marked; currently changing the right boundry of the selected region """ + NONE = 'none' LEFT_MARKED = 'left marked' MARKED = 'marked' @@ -78,9 +80,9 @@ class _SelectionMode(object): class TimelineFrame(QGraphicsItem): - """ - TimelineFrame Draws the framing elements for the bag messages + TimelineFrame Draws the framing elements for the bag messages. + (time delimiters, labels, topic names and backgrounds). Also handles mouse callbacks since they interact closely with the drawn elements """ @@ -139,7 +141,7 @@ def __init__(self, bag_timeline): # or publishing box self._topic_name_spacing = 3 self._topic_font_size = 10 - self._topic_font = QFont("cairo") + self._topic_font = QFont('cairo') self._topic_font.setPointSize(self._topic_font_size) self._topic_font.setBold(False) self._topic_vertical_padding = 4 @@ -152,7 +154,7 @@ def __init__(self, bag_timeline): self._time_tick_height = 5 self._time_font_height = None self._time_font_size = 10 - self._time_font = QFont("cairo") + self._time_font = QFont('cairo') self._time_font.setPointSize(self._time_font_size) self._time_font.setBold(False) @@ -220,8 +222,8 @@ def _get_playhead(self): def _set_playhead(self, playhead): """ - Sets the playhead to the new position, notifies the threads and updates the scene - so it will redraw + Set the playhead to new position, notify threads, and update the scene so it will redraw. + :signal: emits status_bar_changed_signal if the playhead is successfully set :param playhead: Time to set the playhead to, ''rclpy.time.Time()'' """ @@ -288,7 +290,7 @@ def play_region(self): def emit_play_region(self): play_region = self.play_region - if(play_region[0] is not None and play_region[1] is not None): + if play_region[0] is not None and play_region[1] is not None: self.scene().selected_region_changed.emit(*play_region) @property @@ -327,14 +329,10 @@ def _qfont_width(self, name): return QFontMetrics(self._topic_font).width(name) def _trimmed_topic_name(self, topic_name): - """ - This function trims the topic name down to a reasonable percentage of the viewable scene - area - """ + """Trim the topic name down to a reasonable percentage of the viewable scene area.""" allowed_width = self._scene_width * (self._topic_name_max_percent / 100.0) - allowed_width = (allowed_width - - self._topic_name_spacing - self._margin_left - - self._topic_publishing_box_size - self._topic_name_spacing) + allowed_width = (allowed_width - self._topic_name_spacing - self._margin_left - + self._topic_publishing_box_size - self._topic_name_spacing) trimmed_return = topic_name if allowed_width < self._qfont_width(topic_name): # We need to trim the topic @@ -367,9 +365,7 @@ def _trimmed_topic_name(self, topic_name): return trimmed_return def _layout(self): - """ - Recalculate the layout of the timeline to take into account any changes that have occured. - """ + """Recalculate layout of timeline to take into account any changes that have occured.""" # Calculate history left and history width self._scene_width = self.scene().views()[0].size().width() @@ -388,7 +384,8 @@ def _layout(self): # Update the timeline boundries new_history_left = (self._margin_left + self._topic_publishing_box_size + - self._topic_name_spacing + max_topic_name_width + self._topic_name_spacing) + self._topic_name_spacing + max_topic_name_width + + self._topic_name_spacing) new_history_width = self._scene_width - new_history_left - self._margin_right self._history_left = new_history_left self._history_width = new_history_width @@ -407,7 +404,8 @@ def _layout(self): if not topic_height: topic_height = self._topic_font_height + self._topic_vertical_padding - self._history_bounds[topic] = (self._history_left, y, self._history_width, topic_height) + self._history_bounds[topic] = (self._history_left, y, + self._history_width, topic_height) y += topic_height @@ -417,7 +415,8 @@ def _layout(self): def _draw_topic_histories(self, painter): """ - Draw all topic messages + Draw all topic messages. + :param painter: allows access to paint functions,''QPainter'' """ for topic in sorted(self._history_bounds.keys()): @@ -426,6 +425,7 @@ def _draw_topic_histories(self, painter): def _draw_topic_history(self, painter, topic): """ Draw boxes corresponding to message regions on the timeline. + :param painter: allows access to paint functions,''QPainter'' :param topic: the topic for which message boxes should be drawn, ''str'' """ @@ -517,6 +517,7 @@ def _draw_topic_history(self, painter, topic): def _draw_bag_ends(self, painter): """ Draw markers to indicate the area the bag file represents within the current visible area. + :param painter: allows access to paint functions,''QPainter'' """ x_start = self.map_stamp_to_x(bag_helper.to_sec(self._start_stamp)) @@ -531,7 +532,8 @@ def _draw_bag_ends(self, painter): def _draw_topic_dividers(self, painter): """ - Draws horizontal lines between each topic to visually separate the messages + Draw horizontal lines between each topic to visually separate the messages. + :param painter: allows access to paint functions,''QPainter'' """ clip_left = self._history_left @@ -555,7 +557,8 @@ def _draw_topic_dividers(self, painter): def _draw_selected_region(self, painter): """ - Draws a box around the selected region + Draw a box around the selected region. + :param painter: allows access to paint functions,''QPainter'' """ if self._selected_left is None: @@ -594,7 +597,8 @@ def _draw_selected_region(self, painter): def _draw_playhead(self, painter): """ - Draw a line and 2 triangles to denote the current position being viewed + Draw a line and 2 triangles to denote the current position being viewed. + :param painter: ,''QPainter'' """ px = self.map_stamp_to_x(bag_helper.to_sec(self.playhead)) @@ -620,7 +624,8 @@ def _draw_playhead(self, painter): def _draw_history_border(self, painter): """ - Draw a simple black rectangle frame around the timeline view area + Draw a simple black rectangle frame around the timeline view area. + :param painter: ,''QPainter'' """ bounds_width = min(self._history_width, self.scene().width()) @@ -635,7 +640,8 @@ def _draw_history_border(self, painter): def _draw_topic_names(self, painter): """ - Calculate positions of existing topic names and draw them on the left, one for each row + Calculate positions of existing topic names and draw them on the left, one for each row. + :param painter: allows access to pain functions,''QPainter'' """ for topic, bounds in self._history_bounds.items(): @@ -686,6 +692,7 @@ def on_clicked(state, topic=topic): def _draw_time_divisions(self, painter): """ Draw vertical grid-lines showing major and minor time divisions. + :param painter: allows access to paint functions,''QPainter'' """ x_per_sec = self.map_dstamp_to_dx(1.0) @@ -715,6 +722,7 @@ def _draw_time_divisions(self, painter): def _draw_major_divisions(self, painter, stamps, start_stamp, division): """ Draw black hashed vertical grid-lines showing major time divisions. + :param painter: allows access to paint functions,''QPainter'' """ label_y = self._history_top - self._playhead_pointer_size[1] - 5 @@ -731,7 +739,8 @@ def _draw_major_divisions(self, painter, stamps, start_stamp, division): painter.setPen(self._major_division_pen) painter.drawLine( - x, label_y - self._time_tick_height - self._time_font_size, x, self._history_bottom) + x, label_y - self._time_tick_height - self._time_font_size, + x, self._history_bottom) painter.setBrush(self._default_brush) painter.setPen(self._default_pen) @@ -739,6 +748,7 @@ def _draw_major_divisions(self, painter, stamps, start_stamp, division): def _draw_minor_divisions(self, painter, stamps, start_stamp, division): """ Draw grey hashed vertical grid-lines showing minor time divisions. + :param painter: allows access to paint functions,''QPainter'' """ xs = [self.map_stamp_to_x(stamp) for stamp in stamps] @@ -823,6 +833,8 @@ def load_plugins(self): def get_renderers(self): """ + Get the list of currently loaded renderers. + :returns: a list of the currently loaded renderers for the plugins """ renderers = [] @@ -860,7 +872,8 @@ def set_renderer_active(self, topic, active): def _update_index_cache(self, topic): """ - Updates the cache of message timestamps for the given topic. + Update the cache of message timestamps for the given topic. + :return: number of messages added to the index cache """ if self._start_stamp is None or self._end_stamp is None: @@ -895,11 +908,11 @@ def _update_index_cache(self, topic): return len(topic_cache) - topic_cache_len - def cache_message(self, topic, t): """ - Updates the cache of message timestamps with a specific new message, - bypassing any need to read entries from the bag. + Update the cache of message timestamps with a specific new message. + + This bypasses any need to read entries from the bag. """ if self._start_stamp is None or self._end_stamp is None: return 0 @@ -907,10 +920,10 @@ def cache_message(self, topic, t): topic_cache = self.index_cache.setdefault(topic, []) topic_cache.append(bag_helper.to_sec(t)) - def _find_regions(self, stamps, max_interval): """ - Group timestamps into regions connected by timestamps less than max_interval secs apart + Group timestamps into regions connected by timestamps less than max_interval secs apart. + :param start_stamp: a list of stamps, ''list'' :param stamp_step: seconds between each division, ''int'' """ @@ -931,7 +944,8 @@ def _find_regions(self, stamps, max_interval): def _get_stamps(self, start_stamp, stamp_step): """ - Generate visible stamps every stamp_step + Generate visible stamps every stamp_step. + :param start_stamp: beginning of timeline stamp, ''int'' :param stamp_step: seconds between each division, ''int'' """ @@ -947,6 +961,8 @@ def _get_stamps(self, start_stamp, stamp_step): def _get_label(self, division, elapsed): """ + Get the label for a division and time elapsed. + :param division: number of seconds in a division, ''int'' :param elapsed: seconds from the beginning, ''int'' :returns: relevent time elapsed string, ''str'' @@ -978,7 +994,8 @@ def _get_label(self, division, elapsed): # Pixel location/time conversion functions def map_x_to_stamp(self, x, clamp_to_visible=True): """ - converts a pixel x value to a stamp + Convert a pixel x value to a stamp. + :param x: pixel value to be converted, ''int'' :param clamp_to_visible: disallow values that are greater than the current timeline bounds,''bool'' @@ -996,7 +1013,8 @@ def map_x_to_stamp(self, x, clamp_to_visible=True): def map_dx_to_dstamp(self, dx): """ - converts a distance in pixel space to a distance in stamp space + Convert a distance in pixel space to a distance in stamp space. + :param dx: distance in pixel space to be converted, ''int'' :returns: distance in stamp space, ''float'' """ @@ -1004,7 +1022,8 @@ def map_dx_to_dstamp(self, dx): def map_stamp_to_x(self, stamp, clamp_to_visible=True): """ - converts a timestamp to the x value where that stamp exists in the timeline + Convert a timestamp to the x value where that stamp exists in the timeline. + :param stamp: timestamp to be converted, ''int'' :param clamp_to_visible: disallow values that are greater than the current timeline bounds,''bool'' @@ -1117,6 +1136,8 @@ def zoom_timeline(self, zoom, center=None): def get_zoom_interval(self, zoom, center=None): """ + Get the zoom interval. + @rtype: tuple @requires: left & right zoom interval sizes. """ @@ -1267,8 +1288,9 @@ def on_mouse_move(self, event): if dx_drag != 0: self.translate_timeline(-self.map_dx_to_dstamp(dx_drag)) - if (dx_drag == 0 and abs(dy_drag) > 0) or \ - (dx_drag != 0 and abs(float(dy_drag) / dx_drag) > 0.2 and abs(dy_drag) > 1): + dy_drag_only = dx_drag == 0 and abs(dy_drag) > 0 + all_drg = dx_drag != 0 and abs(float(dy_drag) / dx_drag) > 0.2 and abs(dy_drag) > 1 + if dy_drag_only or all_drg: zoom = min( self._max_zoom_speed, max(self._min_zoom_speed, 1.0 + self._zoom_sensitivity * dy_drag)) diff --git a/rqt_bag/src/rqt_bag/timeline_menu.py b/rqt_bag/src/rqt_bag/timeline_menu.py index cffbab7..5506bb4 100644 --- a/rqt_bag/src/rqt_bag/timeline_menu.py +++ b/rqt_bag/src/rqt_bag/timeline_menu.py @@ -27,7 +27,7 @@ # POSSIBILITY OF SUCH DAMAGE. from python_qt_binding.QtCore import qDebug -from python_qt_binding.QtWidgets import QVBoxLayout, QMenu, QWidget, QDockWidget +from python_qt_binding.QtWidgets import QDockWidget, QMenu, QVBoxLayout, QWidget class TopicPopupWidget(QWidget): @@ -60,8 +60,9 @@ def showEvent(self, event): def show(self, context): """ - Make this topic popup visible, if necessary. This includes setting up - the proper close button hacks + Make this topic popup visible, if necessary. + + This includes setting up the proper close button hacks """ if not self.parent(): context.add_widget(self) @@ -92,10 +93,7 @@ def show(self, context): class TimelinePopupMenu(QMenu): - - """ - Custom popup menu displayed on rightclick from timeline - """ + """Custom popup menu displayed on rightclick from timeline.""" def __init__(self, timeline, event, menu_topic): super(TimelinePopupMenu, self).__init__() @@ -137,7 +135,7 @@ def __init__(self, timeline, event, menu_topic): self._thumbnail_hide_action = None for topic, renderer in self._renderers: if menu_topic == topic: - self._thumbnail_actions.append(self.addAction("Thumbnail")) + self._thumbnail_actions.append(self.addAction('Thumbnail')) self._thumbnail_actions[-1].setCheckable(True) self._thumbnail_actions[-1].setChecked( self.timeline._timeline_frame.is_renderer_active(topic)) @@ -181,7 +179,7 @@ def __init__(self, timeline, event, menu_topic): datatype_menu.addMenu(topic_menu) view_type_menu.addMenu(datatype_menu) else: - view_menu = self.addMenu("View") + view_menu = self.addMenu('View') datatype = self.timeline.get_datatype(menu_topic) viewer_types = self.timeline._timeline_frame.get_viewer_types(datatype) @@ -207,7 +205,7 @@ def __init__(self, timeline, event, menu_topic): self._publish_actions[-1].setCheckable(True) self._publish_actions[-1].setChecked(self.timeline.is_publishing(topic)) else: - self._publish_actions.append(self.addAction("Publish")) + self._publish_actions.append(self.addAction('Publish')) self._publish_actions[-1].setCheckable(True) self._publish_actions[-1].setChecked(self.timeline.is_publishing(menu_topic)) self._publish_all = None @@ -219,6 +217,8 @@ def __init__(self, timeline, event, menu_topic): def process(self, action): """ + Process the action. + :param action: action to execute, ''QAction'' :raises: when it doesn't recognice the action passed in, ''Exception'' """ diff --git a/rqt_bag/src/rqt_bag/topic_selection.py b/rqt_bag/src/rqt_bag/topic_selection.py index d638c85..36a605a 100644 --- a/rqt_bag/src/rqt_bag/topic_selection.py +++ b/rqt_bag/src/rqt_bag/topic_selection.py @@ -27,7 +27,8 @@ # POSSIBILITY OF SUCH DAMAGE. from python_qt_binding.QtCore import Qt, Signal -from python_qt_binding.QtWidgets import QWidget, QVBoxLayout, QCheckBox, QScrollArea, QPushButton +from python_qt_binding.QtWidgets import QCheckBox, QPushButton, QScrollArea, QVBoxLayout, QWidget + from .node_selection import NodeSelection @@ -38,7 +39,7 @@ class TopicSelection(QWidget): def __init__(self, node): super(TopicSelection, self).__init__() self._node = node - self.setWindowTitle("Select the topics you want to record") + self.setWindowTitle('Select the topics you want to record') self.resize(500, 700) self.topic_list = [] @@ -47,11 +48,11 @@ def __init__(self, node): self.area = QScrollArea(self) self.main_widget = QWidget(self.area) - self.ok_button = QPushButton("Record", self) + self.ok_button = QPushButton('Record', self) self.ok_button.clicked.connect(self.onButtonClicked) self.ok_button.setEnabled(False) - self.from_nodes_button = QPushButton("From Nodes", self) + self.from_nodes_button = QPushButton('From Nodes', self) self.from_nodes_button.clicked.connect(self.onFromNodesButtonClicked) self.main_vlayout = QVBoxLayout() @@ -61,7 +62,7 @@ def __init__(self, node): self.setLayout(self.main_vlayout) self.selection_vlayout = QVBoxLayout() - self.item_all = QCheckBox("All", self) + self.item_all = QCheckBox('All', self) self.item_all.stateChanged.connect(self.updateList) self.selection_vlayout.addWidget(self.item_all) topic_data_list = self._node.get_topic_names_and_types() diff --git a/rqt_bag/test/test_copyright.py b/rqt_bag/test/test_copyright.py index 0d7306b..02afc51 100644 --- a/rqt_bag/test/test_copyright.py +++ b/rqt_bag/test/test_copyright.py @@ -1,16 +1,32 @@ -# Copyright 2019 Open Source Robotics Foundation, Inc. +# Copyright (c) 2019, Open Source Robotics Foundation, Inc. +# All rights reserved. # -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: # -# http://www.apache.org/licenses/LICENSE-2.0 +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. # -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. from ament_copyright.main import main import pytest @@ -19,5 +35,4 @@ @pytest.mark.copyright @pytest.mark.linter def test_copyright(): - rc = main() - assert rc == 0, 'Found errors' + assert main() == 0, 'Found errors' diff --git a/rqt_bag/test/test_flake8.py b/rqt_bag/test/test_flake8.py new file mode 100644 index 0000000..5b25a61 --- /dev/null +++ b/rqt_bag/test/test_flake8.py @@ -0,0 +1,41 @@ +# Copyright (c) 2024, Open Source Robotics Foundation, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +from ament_flake8.main import main_with_errors +import pytest + + +@pytest.mark.flake8 +@pytest.mark.linter +def test_flake8(): + rc, errors = main_with_errors(argv=[]) + assert rc == 0, \ + 'Found %d code style errors / warnings:\n' % len(errors) + \ + '\n'.join(errors) diff --git a/rqt_bag/test/test_pep257.py b/rqt_bag/test/test_pep257.py new file mode 100644 index 0000000..a49fb77 --- /dev/null +++ b/rqt_bag/test/test_pep257.py @@ -0,0 +1,39 @@ +# Copyright (c) 2024, Open Source Robotics Foundation, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +from ament_pep257.main import main +import pytest + + +@pytest.mark.linter +@pytest.mark.pep257 +def test_pep257(): + rc = main(argv=['.', 'test']) + assert rc == 0, 'Found code style errors / warnings' diff --git a/rqt_bag/test/test_xmllint.py b/rqt_bag/test/test_xmllint.py new file mode 100644 index 0000000..c955681 --- /dev/null +++ b/rqt_bag/test/test_xmllint.py @@ -0,0 +1,39 @@ +# Copyright (c) 2024, Open Source Robotics Foundation, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +from ament_xmllint.main import main +import pytest + + +@pytest.mark.linter +@pytest.mark.xmllint +def test_xmllint() -> None: + rc = main(argv=[]) + assert rc == 0, 'Found errors' From a8a60cca78d5d854bf8ecd71ee8351dcbfff9011 Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Thu, 26 Dec 2024 19:11:17 +0000 Subject: [PATCH 2/4] Add in standard tests for rqt_bag_plugins. This just makes sure it is up to our standards. Signed-off-by: Chris Lalancette --- rqt_bag_plugins/package.xml | 5 ++ .../src/rqt_bag_plugins/image_helper.py | 46 +++++----- .../src/rqt_bag_plugins/image_plugin.py | 22 +++-- .../src/rqt_bag_plugins/image_qt.py | 79 ++++++++--------- .../image_timeline_renderer.py | 63 +++++++------ .../src/rqt_bag_plugins/image_view.py | 41 ++++----- .../src/rqt_bag_plugins/plot_plugin.py | 22 +++-- .../src/rqt_bag_plugins/plot_view.py | 88 +++++++++---------- rqt_bag_plugins/test/test_copyright.py | 38 ++++++++ rqt_bag_plugins/test/test_flake8.py | 41 +++++++++ rqt_bag_plugins/test/test_pep257.py | 39 ++++++++ rqt_bag_plugins/test/test_xmllint.py | 39 ++++++++ 12 files changed, 333 insertions(+), 190 deletions(-) create mode 100644 rqt_bag_plugins/test/test_copyright.py create mode 100644 rqt_bag_plugins/test/test_flake8.py create mode 100644 rqt_bag_plugins/test/test_pep257.py create mode 100644 rqt_bag_plugins/test/test_xmllint.py diff --git a/rqt_bag_plugins/package.xml b/rqt_bag_plugins/package.xml index 82e54e1..052b095 100644 --- a/rqt_bag_plugins/package.xml +++ b/rqt_bag_plugins/package.xml @@ -18,6 +18,7 @@ Mabel Zhang Tim Field + ament_index_python geometry_msgs python3-cairo python3-pil @@ -30,6 +31,10 @@ sensor_msgs std_msgs + ament_copyright + ament_flake8 + ament_pep257 + ament_xmllint python3-pytest diff --git a/rqt_bag_plugins/src/rqt_bag_plugins/image_helper.py b/rqt_bag_plugins/src/rqt_bag_plugins/image_helper.py index 389ec14..2d8f4e9 100755 --- a/rqt_bag_plugins/src/rqt_bag_plugins/image_helper.py +++ b/rqt_bag_plugins/src/rqt_bag_plugins/image_helper.py @@ -1,5 +1,3 @@ -# Software License Agreement (BSD License) -# # Copyright (c) 2012, Willow Garage, Inc. # All rights reserved. # @@ -7,21 +5,21 @@ # modification, are permitted provided that the following conditions # are met: # -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# * Redistributions in binary form must reproduce the above -# copyright notice, this list of conditions and the following -# disclaimer in the documentation and/or other materials provided -# with the distribution. -# * Neither the name of Willow Garage, Inc. nor the names of its -# contributors may be used to endorse or promote products derived -# from this software without specific prior written permission. +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the Willow Garage, Inc. nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER @@ -30,12 +28,8 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -from __future__ import print_function import array -try: - from cStringIO import StringIO -except ImportError: - from io import StringIO +from io import StringIO import sys from PIL import Image @@ -55,20 +49,21 @@ def imgmsg_to_pil(img_msg, msg_type_name, rgba=True): pil_mode = 'RGB' else: pil_mode = 'RGB' - if img_msg.encoding in ['mono8', '8UC1' ]: + if img_msg.encoding in ('mono8', '8UC1'): mode = 'L' elif img_msg.encoding == 'rgb8': mode = 'RGB' elif img_msg.encoding == 'bgr8': mode = 'BGR' - elif img_msg.encoding in ['bayer_rggb8', 'bayer_bggr8', 'bayer_gbrg8', 'bayer_grbg8']: + elif img_msg.encoding in ('bayer_rggb8', 'bayer_bggr8', 'bayer_gbrg8', 'bayer_grbg8'): mode = 'L' - elif img_msg.encoding in ['bayer_rggb16', 'bayer_bggr16', 'bayer_gbrg16', 'bayer_grbg16']: + elif img_msg.encoding in ('bayer_rggb16', 'bayer_bggr16', 'bayer_gbrg16', + 'bayer_grbg16'): pil_mode = 'I;16' if img_msg.is_bigendian: - mode='I;16B' + mode = 'I;16B' else: - mode='I;16L' + mode = 'I;16L' elif img_msg.encoding == 'mono16' or img_msg.encoding == '16UC1': pil_mode = 'F' if img_msg.is_bigendian: @@ -86,9 +81,10 @@ def imgmsg_to_pil(img_msg, msg_type_name, rgba=True): elif img_msg.encoding == 'bgra8': mode = 'RGB' else: - raise Exception("Unsupported image format: %s" % img_msg.encoding) + raise Exception('Unsupported image format: %s' % img_msg.encoding) pil_img = Image.frombuffer( - pil_mode, (img_msg.width, img_msg.height), img_msg.data.tobytes(), 'raw', mode, 0, 1) + pil_mode, (img_msg.width, img_msg.height), + img_msg.data.tobytes(), 'raw', mode, 0, 1) # 16 bits conversion to 8 bits if pil_mode == 'I;16': @@ -104,7 +100,7 @@ def imgmsg_to_pil(img_msg, msg_type_name, rgba=True): return pil_img except Exception as ex: - print('Can\'t convert image: %s' % ex, file=sys.stderr) + print("Can't convert image: %s" % ex, file=sys.stderr) return None diff --git a/rqt_bag_plugins/src/rqt_bag_plugins/image_plugin.py b/rqt_bag_plugins/src/rqt_bag_plugins/image_plugin.py index 45ebc8b..c25978f 100755 --- a/rqt_bag_plugins/src/rqt_bag_plugins/image_plugin.py +++ b/rqt_bag_plugins/src/rqt_bag_plugins/image_plugin.py @@ -1,5 +1,3 @@ -# Software License Agreement (BSD License) -# # Copyright (c) 2012, Willow Garage, Inc. # All rights reserved. # @@ -7,21 +5,21 @@ # modification, are permitted provided that the following conditions # are met: # -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# * Redistributions in binary form must reproduce the above -# copyright notice, this list of conditions and the following -# disclaimer in the documentation and/or other materials provided -# with the distribution. -# * Neither the name of Willow Garage, Inc. nor the names of its -# contributors may be used to endorse or promote products derived -# from this software without specific prior written permission. +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the Willow Garage, Inc. nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER diff --git a/rqt_bag_plugins/src/rqt_bag_plugins/image_qt.py b/rqt_bag_plugins/src/rqt_bag_plugins/image_qt.py index c73e157..67a3f60 100644 --- a/rqt_bag_plugins/src/rqt_bag_plugins/image_qt.py +++ b/rqt_bag_plugins/src/rqt_bag_plugins/image_qt.py @@ -38,20 +38,19 @@ import PIL.Image as Image -from python_qt_binding.QtGui import QImage, QPixmap, qRgba +from python_qt_binding.QtGui import QImage, qRgba + def rgb(r, g, b, a=255): - """(Internal) Turns an RGB color into a Qt compatible color integer.""" + """Turn an RGB color into a Qt compatible color integer.""" # use qRgb to pack the colors, and then turn the resulting long # into a negative integer with the same bitpattern. return qRgba(r, g, b, a) & 0xFFFFFFFF -def align8to32(bytes, width, mode): - """ - converts each scanline of data from 8 bit to 32 bit aligned - """ - bits_per_pixel = {"1": 1, "L": 8, "P": 8, "I;16": 16}[mode] +def align8to32(input_bytes, width, mode): + """Convert each scanline of data from 8 bit to 32 bit aligned.""" + bits_per_pixel = {'1': 1, 'L': 8, 'P': 8, 'I;16': 16}[mode] # calculate bytes per line and the extra padding if needed bits_per_line = bits_per_pixel * width @@ -62,14 +61,14 @@ def align8to32(bytes, width, mode): # already 32 bit aligned by luck if not extra_padding: - return bytes + return input_bytes new_data = [ - bytes[i * bytes_per_line : (i + 1) * bytes_per_line] + b"\x00" * extra_padding - for i in range(len(bytes) // bytes_per_line) + input_bytes[i * bytes_per_line:(i + 1) * bytes_per_line] + b'\x00' * extra_padding + for i in range(len(input_bytes) // bytes_per_line) ] - return b"".join(new_data) + return b''.join(new_data) def is_path(f): @@ -82,54 +81,54 @@ def _toqclass_helper(im): exclusive_fp = False # handle filename, if given instead of image name - if hasattr(im, "toUtf8"): + if hasattr(im, 'toUtf8'): # FIXME - is this really the best way to do this? - im = str(im.toUtf8(), "utf-8") + im = str(im.toUtf8(), 'utf-8') if is_path(im): im = Image.open(im) exclusive_fp = True qt_format = QImage - if im.mode == "1": - format = qt_format.Format_Mono - elif im.mode == "L": - format = qt_format.Format_Indexed8 + if im.mode == '1': + fmt = qt_format.Format_Mono + elif im.mode == 'L': + fmt = qt_format.Format_Indexed8 colortable = [rgb(i, i, i) for i in range(256)] - elif im.mode == "P": - format = qt_format.Format_Indexed8 + elif im.mode == 'P': + fmt = qt_format.Format_Indexed8 palette = im.getpalette() - colortable = [rgb(*palette[i : i + 3]) for i in range(0, len(palette), 3)] - elif im.mode == "RGB": + colortable = [rgb(*palette[i:i + 3]) for i in range(0, len(palette), 3)] + elif im.mode == 'RGB': # Populate the 4th channel with 255 - im = im.convert("RGBA") - - data = im.tobytes("raw", "BGRA") - format = qt_format.Format_RGB32 - elif im.mode == "RGBA": - data = im.tobytes("raw", "BGRA") - format = qt_format.Format_ARGB32 - elif im.mode == "I;16" and hasattr(qt_format, "Format_Grayscale16"): # Qt 5.13+ + im = im.convert('RGBA') + + data = im.tobytes('raw', 'BGRA') + fmt = qt_format.Format_RGB32 + elif im.mode == 'RGBA': + data = im.tobytes('raw', 'BGRA') + fmt = qt_format.Format_ARGB32 + elif im.mode == 'I;16' and hasattr(qt_format, 'Format_Grayscale16'): # Qt 5.13+ im = im.point(lambda i: i * 256) - format = qt_format.Format_Grayscale16 + fmt = qt_format.Format_Grayscale16 else: if exclusive_fp: im.close() - msg = f"unsupported image mode {repr(im.mode)}" + msg = f'unsupported image mode {repr(im.mode)}' raise ValueError(msg) size = im.size __data = data or align8to32(im.tobytes(), size[0], im.mode) if exclusive_fp: im.close() - return {"data": __data, "size": size, "format": format, "colortable": colortable} + return {'data': __data, 'size': size, 'format': fmt, 'colortable': colortable} class ImageQt(QImage): + def __init__(self, im): """ - An PIL image wrapper for Qt. This is a subclass of PyQt's QImage - class. + Construct an PIL image wrapper for Qt, a subclass of PyQt's QImage class. :param im: A PIL Image object, or a file name (given either as Python string or a PyQt string object). @@ -139,12 +138,12 @@ def __init__(self, im): # All QImage constructors that take data operate on an existing # buffer, so this buffer has to hang on for the life of the image. # Fixes https://github.com/python-pillow/Pillow/issues/1370 - self.__data = im_data["data"] + self.__data = im_data['data'] super().__init__( self.__data, - im_data["size"][0], - im_data["size"][1], - im_data["format"], + im_data['size'][0], + im_data['size'][1], + im_data['format'], ) - if im_data["colortable"]: - self.setColorTable(im_data["colortable"]) + if im_data['colortable']: + self.setColorTable(im_data['colortable']) diff --git a/rqt_bag_plugins/src/rqt_bag_plugins/image_timeline_renderer.py b/rqt_bag_plugins/src/rqt_bag_plugins/image_timeline_renderer.py index 71a34fe..419d0b2 100755 --- a/rqt_bag_plugins/src/rqt_bag_plugins/image_timeline_renderer.py +++ b/rqt_bag_plugins/src/rqt_bag_plugins/image_timeline_renderer.py @@ -1,5 +1,3 @@ -# Software License Agreement (BSD License) -# # Copyright (c) 2009, Willow Garage, Inc. # All rights reserved. # @@ -7,21 +5,21 @@ # modification, are permitted provided that the following conditions # are met: # -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# * Redistributions in binary form must reproduce the above -# copyright notice, this list of conditions and the following -# disclaimer in the documentation and/or other materials provided -# with the distribution. -# * Neither the name of Willow Garage, Inc. nor the names of its -# contributors may be used to endorse or promote products derived -# from this software without specific prior written permission. +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the Willow Garage, Inc. nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER @@ -30,44 +28,45 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -from __future__ import print_function -from rclpy.time import Time -# HACK workaround for upstream pillow issue python-pillow/Pillow#400 import sys + +from PIL import Image + +# HACK workaround for upstream pillow issue python-pillow/Pillow#400 from python_qt_binding import QT_BINDING_MODULES if ( not QT_BINDING_MODULES['QtCore'].__name__.startswith('PyQt5') and 'PyQt5' in sys.modules ): sys.modules['PyQt5'] = None -from PIL import Image + +from python_qt_binding.QtCore import Qt +from python_qt_binding.QtGui import QBrush, QPen, QPixmap + +from rclpy.time import Time from rqt_bag import TimelineCache, TimelineRenderer from rqt_bag_plugins import image_helper from rqt_bag_plugins.image_qt import ImageQt -from python_qt_binding.QtCore import Qt -from python_qt_binding.QtGui import QBrush, QPen, QPixmap - class ImageTimelineRenderer(TimelineRenderer): - - """ - Draws thumbnails of sensor_msgs/msg/Image or sensor_msgs/msg/CompressedImage in the timeline. - """ + """Draws thumbnails of sensor_msgs/msg/{Compressed}Image in the timeline.""" def __init__(self, timeline, thumbnail_height=160): super(ImageTimelineRenderer, self).__init__(timeline, msg_combine_px=40.0) self.thumbnail_height = thumbnail_height - - self.thumbnail_combine_px = 20.0 # use cached thumbnail if it's less than this many pixels away - self.min_thumbnail_width = 8 # don't display thumbnails if less than this many pixels across + # use cached thumbnail if it's less than this many pixels away + self.thumbnail_combine_px = 20.0 + # don't display thumbnails if less than this many pixels across + self.min_thumbnail_width = 8 self.quality = Image.NEAREST # quality hint for thumbnail scaling self.thumbnail_cache = TimelineCache( - self._load_thumbnail, lambda topic, msg_stamp, thumbnail: self.timeline.scene().update()) + self._load_thumbnail, lambda topic, msg_stamp, + thumbnail: self.timeline.scene().update()) # TimelineRenderer implementation def get_segment_height(self, topic): @@ -75,7 +74,8 @@ def get_segment_height(self, topic): def draw_timeline_segment(self, painter, topic, stamp_start, stamp_end, x, y, width, height): """ - draws a stream of images for the topic + Draw a stream of images for the topic. + :param painter: painter object, ''QPainter'' :param topic: topic to draw, ''str'' :param stamp_start: stamp to start drawing, ''rclpy.time.Time'' @@ -129,7 +129,8 @@ def draw_timeline_segment(self, painter, topic, stamp_start, stamp_end, x, y, wi QtImage = ImageQt(thumbnail_bitmap) pixmap = QPixmap.fromImage(QtImage) painter.drawPixmap( - int(thumbnail_x), int(thumbnail_y), int(thumbnail_width), int(thumbnail_height), pixmap) + int(thumbnail_x), int(thumbnail_y), int(thumbnail_width), + int(thumbnail_height), pixmap) thumbnail_x += thumbnail_width if width == 1: @@ -149,9 +150,7 @@ def close(self): self.thumbnail_cache.join() def _load_thumbnail(self, topic, stamp, thumbnail_details): - """ - Loads the thumbnail from the bag - """ + """Load the thumbnail from the bag.""" (thumbnail_height,) = thumbnail_details # Find position of stamp using index diff --git a/rqt_bag_plugins/src/rqt_bag_plugins/image_view.py b/rqt_bag_plugins/src/rqt_bag_plugins/image_view.py index 470aaa6..599f2c1 100755 --- a/rqt_bag_plugins/src/rqt_bag_plugins/image_view.py +++ b/rqt_bag_plugins/src/rqt_bag_plugins/image_view.py @@ -1,5 +1,3 @@ -# Software License Agreement (BSD License) -# # Copyright (c) 2012, Willow Garage, Inc. # All rights reserved. # @@ -7,21 +5,21 @@ # modification, are permitted provided that the following conditions # are met: # -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# * Redistributions in binary form must reproduce the above -# copyright notice, this list of conditions and the following -# disclaimer in the documentation and/or other materials provided -# with the distribution. -# * Neither the name of Willow Garage, Inc. nor the names of its -# contributors may be used to endorse or promote products derived -# from this software without specific prior written permission. +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the Willow Garage, Inc. nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER @@ -30,10 +28,11 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. +import sys + from PIL import Image # HACK workaround for upstream pillow issue python-pillow/Pillow#400 -import sys from python_qt_binding import QT_BINDING_MODULES if ( not QT_BINDING_MODULES['QtCore'].__name__.startswith('PyQt5') and @@ -41,19 +40,17 @@ ): sys.modules['PyQt5'] = None +from python_qt_binding.QtGui import QPixmap +from python_qt_binding.QtWidgets import QGraphicsScene, QGraphicsView + from rqt_bag import TopicMessageView from rqt_bag_plugins import image_helper from rqt_bag_plugins.image_qt import ImageQt -from python_qt_binding.QtGui import QPixmap -from python_qt_binding.QtWidgets import QGraphicsScene, QGraphicsView - class ImageView(TopicMessageView): + """Popup image viewer.""" - """ - Popup image viewer - """ name = 'Image' def __init__(self, timeline, parent, topic): @@ -84,9 +81,7 @@ def _resizeEvent(self, event): self.put_image_into_scene() def message_viewed(self, *, entry, ros_message, msg_type_name, topic, **kwargs): - """ - refreshes the image - """ + """Refresh the image.""" TopicMessageView.message_viewed(self, entry=entry) self.set_image(ros_message, msg_type_name, topic, ros_message.header.stamp) @@ -111,7 +106,7 @@ def put_image_into_scene(self): self._scene.addPixmap(pixmap) def set_image(self, image_msg, image_type, image_topic, image_stamp): - if image_type == "sensor_msgs/msg/Image" or image_type == "sensor_msgs/msg/CompressedImage": + if image_type in ('sensor_msgs/msg/Image', 'sensor_msgs/msg/CompressedImage'): self._image_msg = image_msg self._image = image_helper.imgmsg_to_pil(image_msg, image_type) self._image_topic = image_topic diff --git a/rqt_bag_plugins/src/rqt_bag_plugins/plot_plugin.py b/rqt_bag_plugins/src/rqt_bag_plugins/plot_plugin.py index eddfb08..af667dc 100755 --- a/rqt_bag_plugins/src/rqt_bag_plugins/plot_plugin.py +++ b/rqt_bag_plugins/src/rqt_bag_plugins/plot_plugin.py @@ -1,5 +1,3 @@ -# Software License Agreement (BSD License) -# # Copyright (c) 2012, Willow Garage, Inc. # All rights reserved. # @@ -7,21 +5,21 @@ # modification, are permitted provided that the following conditions # are met: # -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# * Redistributions in binary form must reproduce the above -# copyright notice, this list of conditions and the following -# disclaimer in the documentation and/or other materials provided -# with the distribution. -# * Neither the name of Willow Garage, Inc. nor the names of its -# contributors may be used to endorse or promote products derived -# from this software without specific prior written permission. +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the Willow Garage, Inc. nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER diff --git a/rqt_bag_plugins/src/rqt_bag_plugins/plot_view.py b/rqt_bag_plugins/src/rqt_bag_plugins/plot_view.py index 67afe99..1a51a8a 100755 --- a/rqt_bag_plugins/src/rqt_bag_plugins/plot_view.py +++ b/rqt_bag_plugins/src/rqt_bag_plugins/plot_view.py @@ -1,5 +1,3 @@ -# Software License Agreement (BSD License) -# # Copyright (c) 2014, Austin Hendrix, Stanford University # All rights reserved. # @@ -7,21 +5,21 @@ # modification, are permitted provided that the following conditions # are met: # -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# * Redistributions in binary form must reproduce the above -# copyright notice, this list of conditions and the following -# disclaimer in the documentation and/or other materials provided -# with the distribution. -# * Neither the name of Willow Garage, Inc. nor the names of its -# contributors may be used to endorse or promote products derived -# from this software without specific prior written permission. +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the Willow Garage, Inc. nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER @@ -62,37 +60,32 @@ # doesn't make sense to make it align with the timeline. This could be done # if someone wanted to implement a separate timeline view -import os -import math import codecs +import math +import os import threading -from rqt_bag import MessageView from ament_index_python import get_resource + from python_qt_binding import loadUi -from python_qt_binding.QtCore import Qt, qWarning, Signal +from python_qt_binding.QtCore import Qt, qWarning from python_qt_binding.QtGui import QDoubleValidator, QIcon from python_qt_binding.QtWidgets import \ - QWidget, QPushButton, QTreeWidget, QTreeWidgetItem, QSizePolicy - -from rqt_plot.data_plot import DataPlot -from rqt_bag import bag_helper + QPushButton, QSizePolicy, QTreeWidget, QTreeWidgetItem, QWidget # rclpy used for Time and Duration objects, for interacting with rosbag from rclpy.duration import Duration from rclpy.time import Time -# compatibility fix for python2/3 -try: - long -except NameError: - long = int +from rqt_bag import bag_helper +from rqt_bag import MessageView + +from rqt_plot.data_plot import DataPlot + class PlotView(MessageView): + """Popup plot viewer.""" - """ - Popup plot viewer - """ name = 'Plot' def __init__(self, timeline, parent, topic): @@ -103,10 +96,9 @@ def __init__(self, timeline, parent, topic): parent.layout().addWidget(self.plot_widget) def message_viewed(self, *, entry, ros_message, msg_type_name, **kwargs): - """ - refreshes the plot - """ - cursor_position = bag_helper.to_sec((Time(nanoseconds=entry.timestamp) - self.plot_widget.start_stamp)) + """Refresh the plot.""" + rclpy_time = Time(nanoseconds=entry.timestamp) + cursor_position = bag_helper.to_sec(rclpy_time - self.plot_widget.start_stamp) self.plot_widget.message_tree.set_message(ros_message, msg_type_name) self.plot_widget.set_cursor(cursor_position) @@ -156,12 +148,12 @@ def __init__(self, timeline, parent, topic): self.data_plot_layout.addWidget(self.plot) self._home_button = QPushButton() - self._home_button.setToolTip("Reset View") + self._home_button.setToolTip('Reset View') self._home_button.setIcon(QIcon.fromTheme('go-home')) self._home_button.clicked.connect(self.home) self.plot_toolbar_layout.addWidget(self._home_button) - self._config_button = QPushButton("Configure Plot") + self._config_button = QPushButton('Configure Plot') self._config_button.clicked.connect(self.plot.doSettingsDialog) self.plot_toolbar_layout.addWidget(self._config_button) @@ -205,7 +197,7 @@ def remove_plot(self, path): self.plot.redraw() def load_data(self): - """get a generator for the specified time range on our bag""" + """Get a generator for the specified time range on our bag.""" return self.bag.get_entries_in_range(self.start_stamp + Duration(seconds=self.limits[0]), self.start_stamp + Duration(seconds=self.limits[1]), self.msgtopic) @@ -261,7 +253,8 @@ def _resample_thread(self): # the minimum and maximum values present within a sample # If the data has spikes, this is particularly bad because they # will be missed entirely at some resolutions and offsets - if x[path] == [] or bag_helper.to_sec(timestamp - self.start_stamp) - x[path][-1] >= self.timestep: + bag_sec = bag_helper.to_sec(timestamp - self.start_stamp) + if x[path] == [] or bag_sec - x[path][-1] >= self.timestep: y_value = ros_message for field in path.split('.'): index = None @@ -287,7 +280,7 @@ def _resample_thread(self): # update the plot with final resampled data for path in self.resample_fields: if len(x[path]) < 1: - qWarning("Resampling resulted in 0 data points for %s" % path) + qWarning('Resampling resulted in 0 data points for %s' % path) else: if path in self.paths_on: self.plot.clear_values(path) @@ -413,7 +406,8 @@ def set_message(self, msg, msg_type): self.update() def get_item_path(self, item): - return item.data(0, Qt.UserRole)[0].replace(' ', '') # remove spaces that may get introduced in indexing, e.g. [ 3] is [3] + # remove spaces that may get introduced in indexing, e.g. [ 3] is [3] + return item.data(0, Qt.UserRole)[0].replace(' ', '') def get_all_items(self): items = [] @@ -436,7 +430,8 @@ def _add_msg_object(self, parent, path, name, obj, obj_type): label = name[1:] if name.startswith('_') else name if hasattr(obj, '_fields_and_field_types'): - subobjs = [(field_name, getattr(obj, field_name)) for field_name in obj.get_fields_and_field_types().keys()] + field_keys = obj.get_fields_and_field_types().keys() + subobjs = [(field_name, getattr(obj, field_name)) for field_name in field_keys] elif type(obj) in [list, tuple]: len_obj = len(obj) if len_obj == 0: @@ -448,9 +443,9 @@ def _add_msg_object(self, parent, path, name, obj, obj_type): subobjs = [] plotitem = False - if type(obj) in [int, long, float]: + if type(obj) in [int, float]: plotitem = True - if type(obj) == float: + if type(obj) is float: obj_repr = '%.6f' % obj else: obj_repr = str(obj) @@ -460,7 +455,7 @@ def _add_msg_object(self, parent, path, name, obj, obj_type): else: label += ': %s' % obj_repr - elif type(obj) in [str, bool, int, long, float, complex, Time]: + elif type(obj) in [str, bool, int, float, complex, Time]: # Ignore any binary data obj_repr = codecs.utf_8_decode(str(obj).encode(), 'ignore')[0] @@ -476,7 +471,7 @@ def _add_msg_object(self, parent, path, name, obj, obj_type): self.addTopLevelItem(item) else: parent.addChild(item) - if plotitem == True: + if plotitem: if path.replace(' ', '') in self._checked_states: item.setCheckState(0, Qt.Checked) else: @@ -515,12 +510,13 @@ def on_key_press(self, event): self.selectAll() def handleChanged(self, item, column): - if item.data(0, Qt.UserRole) == None: + if item.data(0, Qt.UserRole) is None: pass else: # Strip the leading underscore from each of the path segments - segments = [segment[1:] if segment[0] == '_' else segment for segment in self.get_item_path(item).split('.')] - path = '.'.join(segments) + split_item_path = self.get_item_path(item).split('.') + segments = [seg[1:] if seg[0] == '_' else seg for seg in split_item_path] + path = '.'.join(segments) if item.checkState(column) == Qt.Checked: if path not in self.plot_list: diff --git a/rqt_bag_plugins/test/test_copyright.py b/rqt_bag_plugins/test/test_copyright.py new file mode 100644 index 0000000..478ef5a --- /dev/null +++ b/rqt_bag_plugins/test/test_copyright.py @@ -0,0 +1,38 @@ +# Copyright (c) 2019, Open Source Robotics Foundation, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +from ament_copyright.main import main +import pytest + + +@pytest.mark.copyright +@pytest.mark.linter +def test_copyright(): + assert main(argv=['--exclude', 'src/rqt_bag_plugins/image_qt.py']) == 0, 'Found errors' diff --git a/rqt_bag_plugins/test/test_flake8.py b/rqt_bag_plugins/test/test_flake8.py new file mode 100644 index 0000000..5b25a61 --- /dev/null +++ b/rqt_bag_plugins/test/test_flake8.py @@ -0,0 +1,41 @@ +# Copyright (c) 2024, Open Source Robotics Foundation, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +from ament_flake8.main import main_with_errors +import pytest + + +@pytest.mark.flake8 +@pytest.mark.linter +def test_flake8(): + rc, errors = main_with_errors(argv=[]) + assert rc == 0, \ + 'Found %d code style errors / warnings:\n' % len(errors) + \ + '\n'.join(errors) diff --git a/rqt_bag_plugins/test/test_pep257.py b/rqt_bag_plugins/test/test_pep257.py new file mode 100644 index 0000000..a49fb77 --- /dev/null +++ b/rqt_bag_plugins/test/test_pep257.py @@ -0,0 +1,39 @@ +# Copyright (c) 2024, Open Source Robotics Foundation, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +from ament_pep257.main import main +import pytest + + +@pytest.mark.linter +@pytest.mark.pep257 +def test_pep257(): + rc = main(argv=['.', 'test']) + assert rc == 0, 'Found code style errors / warnings' diff --git a/rqt_bag_plugins/test/test_xmllint.py b/rqt_bag_plugins/test/test_xmllint.py new file mode 100644 index 0000000..c955681 --- /dev/null +++ b/rqt_bag_plugins/test/test_xmllint.py @@ -0,0 +1,39 @@ +# Copyright (c) 2024, Open Source Robotics Foundation, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +from ament_xmllint.main import main +import pytest + + +@pytest.mark.linter +@pytest.mark.xmllint +def test_xmllint() -> None: + rc = main(argv=[]) + assert rc == 0, 'Found errors' From 424eab6c6a5b7f81abe260f164f64af4e45657ed Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Fri, 3 Jan 2025 14:11:52 +0000 Subject: [PATCH 3/4] Update from review. Signed-off-by: Chris Lalancette --- rqt_bag_plugins/src/rqt_bag_plugins/plot_view.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rqt_bag_plugins/src/rqt_bag_plugins/plot_view.py b/rqt_bag_plugins/src/rqt_bag_plugins/plot_view.py index 1a51a8a..2b907be 100755 --- a/rqt_bag_plugins/src/rqt_bag_plugins/plot_view.py +++ b/rqt_bag_plugins/src/rqt_bag_plugins/plot_view.py @@ -445,7 +445,7 @@ def _add_msg_object(self, parent, path, name, obj, obj_type): plotitem = False if type(obj) in [int, float]: plotitem = True - if type(obj) is float: + if isinstance(obj, float): obj_repr = '%.6f' % obj else: obj_repr = str(obj) From a20cb06ee9106036a0fbb407fc98e5b800eb33b5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Tue, 7 Jan 2025 12:39:05 +0100 Subject: [PATCH 4/4] Include suggestions MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- rqt_bag/src/rqt_bag/bag_timeline.py | 3 +-- rqt_bag/src/rqt_bag/recorder.py | 3 +-- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/rqt_bag/src/rqt_bag/bag_timeline.py b/rqt_bag/src/rqt_bag/bag_timeline.py index 101775b..0f1b261 100644 --- a/rqt_bag/src/rqt_bag/bag_timeline.py +++ b/rqt_bag/src/rqt_bag/bag_timeline.py @@ -752,8 +752,7 @@ def _message_recorded(self, topic, msg, t): try: listener.timeline_changed() except Exception as ex: - listen_type = type(listener) - qWarning('Error calling timeline_changed on %s: %s' % (listen_type, str(ex))) + qWarning(f'Error calling timeline_changed on {type(listener)}: {str(ex)}') # Dynamically resize the timeline, if necessary, to make visible any new messages # that might otherwise have exceeded the bounds of the window diff --git a/rqt_bag/src/rqt_bag/recorder.py b/rqt_bag/src/rqt_bag/recorder.py index 2320a6e..885eb2d 100644 --- a/rqt_bag/src/rqt_bag/recorder.py +++ b/rqt_bag/src/rqt_bag/recorder.py @@ -28,8 +28,7 @@ """Recorder subscribes to ROS messages and writes them to a bag file.""" -from queue import Empty -from queue import Queue +from queue import Empty, Queue import re import sys import threading