Skip to content

Commit

Permalink
Comments and brace-init
Browse files Browse the repository at this point in the history
Signed-off-by: Anas Abou Allaban <[email protected]>
  • Loading branch information
piraka9011 committed Apr 10, 2020
1 parent 0f4025f commit febadb0
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 6 deletions.
2 changes: 1 addition & 1 deletion ros2bag/test/resources/empty_bag/metadata.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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: ""
compression_mode: ""
2 changes: 2 additions & 0 deletions ros2bag/test/test_play_qos_profiles.py
Original file line number Diff line number Diff line change
Expand Up @@ -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(),
Expand All @@ -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(),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,15 +61,15 @@ std::unordered_map<std::string, rclcpp::QoS> PyObject_AsTopicQoSMap(PyObject * o
{
std::unordered_map<std::string, rclcpp::QoS> 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<std::string, rclcpp::QoS>(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."};
Expand Down Expand Up @@ -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<char **>(kwlist),
&uri,
Expand Down

0 comments on commit febadb0

Please sign in to comment.