Skip to content

Commit

Permalink
Fix common func name
Browse files Browse the repository at this point in the history
  • Loading branch information
roncapat committed Aug 8, 2023
1 parent bc74937 commit 7888b96
Showing 1 changed file with 3 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ get_storage_options_from_node_params(std::shared_ptr<rclcpp::Node> node)

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

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

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

auto desc_mcs = param_utils::int_parameter_description(
auto desc_mcs = param_utils::int_param_description(
"Max chache size (messages)",
1,
std::numeric_limits<int64_t>::max());
Expand Down

0 comments on commit 7888b96

Please sign in to comment.