diff --git a/ros2bag/ros2bag/api/__init__.py b/ros2bag/ros2bag/api/__init__.py index 1eeb97148..565cae52a 100644 --- a/ros2bag/ros2bag/api/__init__.py +++ b/ros2bag/ros2bag/api/__init__.py @@ -24,20 +24,20 @@ from typing import Optional from rclpy.duration import Duration -from rclpy.qos import QoSDurabilityPolicy -from rclpy.qos import QoSHistoryPolicy -from rclpy.qos import QoSLivelinessPolicy +from rclpy.qos import DurabilityPolicy +from rclpy.qos import HistoryPolicy +from rclpy.qos import LivelinessPolicy from rclpy.qos import QoSProfile -from rclpy.qos import QoSReliabilityPolicy +from rclpy.qos import ReliabilityPolicy from ros2cli.entry_points import get_entry_points import rosbag2_py # This map needs to be updated when new policies are introduced _QOS_POLICY_FROM_SHORT_NAME = { - 'history': QoSHistoryPolicy.get_from_short_key, - 'reliability': QoSReliabilityPolicy.get_from_short_key, - 'durability': QoSDurabilityPolicy.get_from_short_key, - 'liveliness': QoSLivelinessPolicy.get_from_short_key + 'history': HistoryPolicy.get_from_short_key, + 'reliability': ReliabilityPolicy.get_from_short_key, + 'durability': DurabilityPolicy.get_from_short_key, + 'liveliness': LivelinessPolicy.get_from_short_key } _DURATION_KEYS = ['deadline', 'lifespan', 'liveliness_lease_duration'] _VALUE_KEYS = ['depth', 'avoid_ros_namespace_conventions'] diff --git a/ros2bag/test/test_api.py b/ros2bag/test/test_api.py index b9f9a7d51..a711a4827 100644 --- a/ros2bag/test/test_api.py +++ b/ros2bag/test/test_api.py @@ -14,9 +14,9 @@ import unittest -from rclpy.qos import QoSDurabilityPolicy -from rclpy.qos import QoSHistoryPolicy -from rclpy.qos import QoSReliabilityPolicy +from rclpy.qos import DurabilityPolicy +from rclpy.qos import HistoryPolicy +from rclpy.qos import ReliabilityPolicy from ros2bag.api import convert_yaml_to_qos_profile from ros2bag.api import dict_to_duration from ros2bag.api import interpret_dict_as_qos_profile @@ -38,7 +38,7 @@ def test_dict_to_duration_invalid(self): def test_interpret_dict_as_qos_profile_valid(self): qos_dict = {'history': 'keep_last', 'depth': 10} qos_profile = interpret_dict_as_qos_profile(qos_dict) - assert qos_profile.history == QoSHistoryPolicy.KEEP_LAST + assert qos_profile.history == HistoryPolicy.KEEP_LAST expected_seconds = 1 expected_nanoseconds = int((expected_seconds * 1e9)) qos_dict = {'history': 'keep_all', 'deadline': {'sec': expected_seconds, 'nsec': 0}} @@ -65,15 +65,11 @@ def test_convert_yaml_to_qos_profile(self): 'history': 'keep_all', 'avoid_ros_namespace_conventions': expected_convention} } qos_profiles = convert_yaml_to_qos_profile(qos_dict) - assert qos_profiles[topic_name_1].durability == \ - QoSDurabilityPolicy.VOLATILE - assert qos_profiles[topic_name_1].reliability == \ - QoSReliabilityPolicy.RELIABLE - assert qos_profiles[topic_name_1].history == \ - QoSHistoryPolicy.KEEP_ALL + assert qos_profiles[topic_name_1].durability == DurabilityPolicy.VOLATILE + assert qos_profiles[topic_name_1].reliability == ReliabilityPolicy.RELIABLE + assert qos_profiles[topic_name_1].history == HistoryPolicy.KEEP_ALL assert qos_profiles[topic_name_2].avoid_ros_namespace_conventions == expected_convention - assert qos_profiles[topic_name_2].history == \ - QoSHistoryPolicy.KEEP_ALL + assert qos_profiles[topic_name_2].history == HistoryPolicy.KEEP_ALL def test_interpret_dict_as_qos_profile_negative(self): qos_dict = {'history': 'keep_all', 'depth': -1}