Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add standard tests for rqt_bag and rqt_bag_plugins #171

Merged
merged 4 commits into from
Jan 7, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 7 additions & 0 deletions rqt_bag/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,13 +16,20 @@
<author email="mabel@openrobotics.org">Mabel Zhang</author>
<author>Tim Field</author>

<exec_depend>ament_index_python</exec_depend>
<exec_depend>builtin_interfaces</exec_depend>
<exec_depend>python3-yaml</exec_depend>
<exec_depend version_gte="0.2.19">python_qt_binding</exec_depend>
<exec_depend>rclpy</exec_depend>
<exec_depend>rosbag2_py</exec_depend>
<exec_depend>rosidl_runtime_py</exec_depend>
<exec_depend version_gte="0.2.12">rqt_gui</exec_depend>
<exec_depend>rqt_gui_py</exec_depend>

<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
<test_depend>ament_pep257</test_depend>
<test_depend>ament_xmllint</test_depend>
<test_depend>python3-pytest</test_depend>

<export>
Expand Down
10 changes: 5 additions & 5 deletions rqt_bag/src/rqt_bag/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
9 changes: 4 additions & 5 deletions rqt_bag/src/rqt_bag/bag.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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''
"""
Expand Down
3 changes: 2 additions & 1 deletion rqt_bag/src/rqt_bag/bag_helper.py
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
93 changes: 58 additions & 35 deletions rqt_bag/src/rqt_bag/bag_timeline.py
Original file line number Diff line number Diff line change
Expand Up @@ -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''
Expand Down Expand Up @@ -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
Expand All @@ -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:
Expand All @@ -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)
Expand Down Expand Up @@ -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:
Expand All @@ -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:
Expand All @@ -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:
Expand All @@ -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:
Expand All @@ -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''
"""
Expand All @@ -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''
Expand Down Expand Up @@ -280,15 +296,15 @@ 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''
:returns: tuple of (bag, entry) for the entries in the bag file, ''(rosbag2.bag, msg)''
"""
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:
Expand All @@ -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)''
Expand All @@ -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)''
"""
Expand All @@ -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)''
"""
Expand All @@ -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:
Expand All @@ -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:
Expand All @@ -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:
Expand All @@ -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''
Expand All @@ -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

Expand All @@ -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''
Expand Down Expand Up @@ -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
Expand All @@ -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
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -729,7 +752,7 @@ 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)))
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
Expand Down
Loading