Skip to content

Commit 7888b96

Browse files
committed
Fix common func name
1 parent bc74937 commit 7888b96

File tree

1 file changed

+3
-3
lines changed

1 file changed

+3
-3
lines changed

rosbag2_transport/src/rosbag2_transport/storage_options_from_node_params.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ get_storage_options_from_node_params(std::shared_ptr<rclcpp::Node> node)
2929

3030
storage_options.storage_config_uri = node->declare_parameter<std::string>("config_uri", "");
3131

32-
auto desc_mbs = param_utils::int_parameter_description(
32+
auto desc_mbs = param_utils::int_param_description(
3333
"Max bagfile size (bytes)",
3434
1,
3535
std::numeric_limits<int64_t>::max());
@@ -39,7 +39,7 @@ get_storage_options_from_node_params(std::shared_ptr<rclcpp::Node> node)
3939
desc_mbs);
4040
storage_options.max_bagfile_size = static_cast<uint64_t>(max_bagfile_size_);
4141

42-
auto desc_mbd = param_utils::int_parameter_description(
42+
auto desc_mbd = param_utils::int_param_description(
4343
"Max bagfile duration (nanoseconds)",
4444
1,
4545
std::numeric_limits<int64_t>::max());
@@ -49,7 +49,7 @@ get_storage_options_from_node_params(std::shared_ptr<rclcpp::Node> node)
4949
desc_mbd);
5050
storage_options.max_bagfile_duration = static_cast<uint64_t>(max_bagfile_duration_);
5151

52-
auto desc_mcs = param_utils::int_parameter_description(
52+
auto desc_mcs = param_utils::int_param_description(
5353
"Max chache size (messages)",
5454
1,
5555
std::numeric_limits<int64_t>::max());

0 commit comments

Comments
 (0)