diff --git a/rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp b/rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp index 49dc587ac5..3af2976c9d 100644 --- a/rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp +++ b/rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp @@ -235,6 +235,10 @@ RecordOptions get_record_options_from_node_params(rclcpp::Node & node) node, "record.compression_threads", 0, std::numeric_limits::max(), record_options.compression_threads); + record_options.compression_threads_priority = param_utils::declare_integer_node_params( + node, "record.compression_threads_priority", std::numeric_limits::min(), + std::numeric_limits::max(), record_options.compression_threads_priority); + std::string qos_profile_overrides_path = node.declare_parameter("record.qos_profile_overrides_path", ""); diff --git a/rosbag2_transport/test/resources/recorder_node_params.yaml b/rosbag2_transport/test/resources/recorder_node_params.yaml index b5ca93b7b1..8fd6123988 100644 --- a/rosbag2_transport/test/resources/recorder_node_params.yaml +++ b/rosbag2_transport/test/resources/recorder_node_params.yaml @@ -18,6 +18,7 @@ recorder_params_node: compression_format: "h264" compression_queue_size: 10 compression_threads: 2 + compression_threads_priority: -1 qos_profile_overrides_path: "" include_hidden_topics: true include_unpublished_topics: true diff --git a/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp b/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp index 54dbbe055e..3b9d494d6c 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp @@ -220,6 +220,7 @@ TEST_P(ComposableRecorderTests, recorder_can_parse_parameters_from_file) { EXPECT_EQ(record_options.compression_format, "h264"); EXPECT_EQ(record_options.compression_queue_size, 10); EXPECT_EQ(record_options.compression_threads, 2); + EXPECT_EQ(record_options.compression_threads_priority, -1); std::unordered_map topic_qos_profile_overrides{ std::pair{ "/overrided_topic_qos",