diff --git a/ros2bag/test/resources/empty_bag/metadata.yaml b/ros2bag/test/resources/empty_bag/metadata.yaml index d8b475bbea..bf90464011 100644 --- a/ros2bag/test/resources/empty_bag/metadata.yaml +++ b/ros2bag/test/resources/empty_bag/metadata.yaml @@ -22,4 +22,4 @@ rosbag2_bagfile_information: offered_qos_profiles: "- history: 3\n depth: 0\n reliability: 1\n durability: 1\n deadline:\n sec: 2147483647\n nsec: 4294967295\n lifespan:\n sec: 10\n nsec: 0\n liveliness: 1\n liveliness_lease_duration:\n sec: 2147483647\n nsec: 4294967295\n avoid_ros_namespace_conventions: false" message_count: 0 compression_format: "" - compression_mode: "" \ No newline at end of file + compression_mode: "" diff --git a/ros2bag/test/test_play_qos_profiles.py b/ros2bag/test/test_play_qos_profiles.py index f63297779a..b6f719d48d 100644 --- a/ros2bag/test/test_play_qos_profiles.py +++ b/ros2bag/test/test_play_qos_profiles.py @@ -60,6 +60,7 @@ def launch_bag_command(self, arguments, **kwargs): cls.launch_bag_command = launch_bag_command def test_qos_simple(self): + """Test with a full QoS profile override for a single topic.""" profile_path = RESOURCES_PATH / 'qos_profile.yaml' bag_path = RESOURCES_PATH / 'empty_bag' arguments = ['play', '--qos-profile-overrides-path', profile_path.as_posix(), @@ -71,6 +72,7 @@ def test_qos_simple(self): assert not matches, print('ros2bag CLI did not produce the expected output') def test_qos_incomplete(self): + """Test a partially filled QoS profile for a single topic.""" profile_path = RESOURCES_PATH / 'incomplete_qos_profile.yaml' bag_path = RESOURCES_PATH / 'empty_bag' arguments = ['play', '--qos-profile-overrides-path', profile_path.as_posix(), diff --git a/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp b/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp index c8cbc6f3a3..0aca3d510d 100644 --- a/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp +++ b/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp @@ -61,15 +61,15 @@ std::unordered_map PyObject_AsTopicQoSMap(PyObject * o { std::unordered_map topic_qos_overrides{}; if (PyDict_Check(object)) { - PyObject * key = nullptr; - PyObject * value = nullptr; - Py_ssize_t pos = 0; + PyObject * key{nullptr}; + PyObject * value{nullptr}; + Py_ssize_t pos{0}; while (PyDict_Next(object, &pos, &key, &value)) { auto topic_name = PyObject_AsStdString(key); auto rmw_qos_profile = PyQoSProfile_AsRmwQoSProfile(value); auto qos_init = rclcpp::QoSInitialization::from_rmw(*rmw_qos_profile); auto qos_profile = rclcpp::QoS(qos_init, *rmw_qos_profile); - topic_qos_overrides.insert(std::pair(topic_name, qos_profile)); + topic_qos_overrides.insert({topic_name, qos_profile}); } } else { throw std::runtime_error{"QoS profile overrides object is not a Python dictionary."}; @@ -216,7 +216,7 @@ rosbag2_transport_play(PyObject * Py_UNUSED(self), PyObject * args, PyObject * k char * node_prefix; size_t read_ahead_queue_size; float rate; - PyObject * qos_profile_overrides; + PyObject * qos_profile_overrides{nullptr}; if (!PyArg_ParseTupleAndKeywords( args, kwargs, "sss|kfO", const_cast(kwlist), &uri,