Skip to content

Commit

Permalink
Add compression_threads_priority to the node params parser
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Orlov <[email protected]>
  • Loading branch information
MichaelOrlov authored and jmachowinski committed Dec 14, 2023
1 parent ed3d4e4 commit b0f0aa2
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -235,6 +235,10 @@ RecordOptions get_record_options_from_node_params(rclcpp::Node & node)
node, "record.compression_threads", 0, std::numeric_limits<int64_t>::max(),
record_options.compression_threads);

record_options.compression_threads_priority = param_utils::declare_integer_node_params<int32_t>(
node, "record.compression_threads_priority", std::numeric_limits<int32_t>::min(),
std::numeric_limits<int32_t>::max(), record_options.compression_threads_priority);

std::string qos_profile_overrides_path =
node.declare_parameter<std::string>("record.qos_profile_overrides_path", "");

Expand Down
1 change: 1 addition & 0 deletions rosbag2_transport/test/resources/recorder_node_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::string, rclcpp::QoS> topic_qos_profile_overrides{
std::pair{
"/overrided_topic_qos",
Expand Down

0 comments on commit b0f0aa2

Please sign in to comment.