From ecc7e1bafe44bb1fadebbca076b00b9da65d5e0e Mon Sep 17 00:00:00 2001 From: maksymdidukh Date: Tue, 5 Mar 2024 14:06:35 +0200 Subject: [PATCH 1/2] adjust main() Signed-off-by: maksymdidukh --- topic_tools/src/throttle.cpp | 42 +++++++++++++++++------------------- 1 file changed, 20 insertions(+), 22 deletions(-) diff --git a/topic_tools/src/throttle.cpp b/topic_tools/src/throttle.cpp index 48c6f728..f14e1de6 100644 --- a/topic_tools/src/throttle.cpp +++ b/topic_tools/src/throttle.cpp @@ -20,29 +20,27 @@ int main(int argc, char * argv[]) { auto args = rclcpp::init_and_remove_ros_arguments(argc, argv); - auto options = rclcpp::NodeOptions{}; + auto options = rclcpp::NodeOptions {}; - if (args.size() < 2) { - std::cout << "Throttle type is missing." << std::endl; - return 0; - } - if (args.at(1) == "messages") { - options.append_parameter_override("throttle_type", "messages"); - if (args.size() >= 4) { - options.append_parameter_override("input_topic", args.at(2)); - options.append_parameter_override("msgs_per_sec", std::stod(args.at(3))); - if (args.size() >= 5) { - options.append_parameter_override("output_topic", args.at(4)); + if (args.size() >= 2) { + if (args.at(1) == "messages") { + options.append_parameter_override("throttle_type", "messages"); + if (args.size() >= 4) { + options.append_parameter_override("input_topic", args.at(2)); + options.append_parameter_override("msgs_per_sec", std::stod(args.at(3))); + if (args.size() >= 5) { + options.append_parameter_override("output_topic", args.at(4)); + } } - } - } else if (args.at(1) == "bytes") { - options.append_parameter_override("throttle_type", "bytes"); - if (args.size() >= 5) { - options.append_parameter_override("input_topic", args.at(2)); - options.append_parameter_override("bytes_per_sec", std::stoi(args.at(3))); - options.append_parameter_override("window", std::stod(args.at(4))); - if (args.size() >= 6) { - options.append_parameter_override("output_topic", args.at(5)); + } else if (args.at(1) == "bytes") { + options.append_parameter_override("throttle_type", "bytes"); + if (args.size() >= 5) { + options.append_parameter_override("input_topic", args.at(2)); + options.append_parameter_override("bytes_per_sec", std::stoi(args.at(3))); + options.append_parameter_override("window", std::stod(args.at(4))); + if (args.size() >= 6) { + options.append_parameter_override("output_topic", args.at(5)); + } } } } @@ -52,4 +50,4 @@ int main(int argc, char * argv[]) rclcpp::spin(node); rclcpp::shutdown(); return 0; -} +} \ No newline at end of file From ead174e4cba07549515e752b378c0aa22cd76523 Mon Sep 17 00:00:00 2001 From: maksymdidukh Date: Tue, 5 Mar 2024 14:45:36 +0200 Subject: [PATCH 2/2] fix linting Signed-off-by: maksymdidukh --- topic_tools/src/throttle.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/topic_tools/src/throttle.cpp b/topic_tools/src/throttle.cpp index f14e1de6..7c137242 100644 --- a/topic_tools/src/throttle.cpp +++ b/topic_tools/src/throttle.cpp @@ -50,4 +50,4 @@ int main(int argc, char * argv[]) rclcpp::spin(node); rclcpp::shutdown(); return 0; -} \ No newline at end of file +}