Skip to content

Commit ecc7e1b

Browse files
committed
adjust main()
Signed-off-by: maksymdidukh <maxym.didukh@logivations.com>
1 parent cefac47 commit ecc7e1b

File tree

1 file changed

+20
-22
lines changed

1 file changed

+20
-22
lines changed

topic_tools/src/throttle.cpp

Lines changed: 20 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -20,29 +20,27 @@
2020
int main(int argc, char * argv[])
2121
{
2222
auto args = rclcpp::init_and_remove_ros_arguments(argc, argv);
23-
auto options = rclcpp::NodeOptions{};
23+
auto options = rclcpp::NodeOptions {};
2424

25-
if (args.size() < 2) {
26-
std::cout << "Throttle type is missing." << std::endl;
27-
return 0;
28-
}
29-
if (args.at(1) == "messages") {
30-
options.append_parameter_override("throttle_type", "messages");
31-
if (args.size() >= 4) {
32-
options.append_parameter_override("input_topic", args.at(2));
33-
options.append_parameter_override("msgs_per_sec", std::stod(args.at(3)));
34-
if (args.size() >= 5) {
35-
options.append_parameter_override("output_topic", args.at(4));
25+
if (args.size() >= 2) {
26+
if (args.at(1) == "messages") {
27+
options.append_parameter_override("throttle_type", "messages");
28+
if (args.size() >= 4) {
29+
options.append_parameter_override("input_topic", args.at(2));
30+
options.append_parameter_override("msgs_per_sec", std::stod(args.at(3)));
31+
if (args.size() >= 5) {
32+
options.append_parameter_override("output_topic", args.at(4));
33+
}
3634
}
37-
}
38-
} else if (args.at(1) == "bytes") {
39-
options.append_parameter_override("throttle_type", "bytes");
40-
if (args.size() >= 5) {
41-
options.append_parameter_override("input_topic", args.at(2));
42-
options.append_parameter_override("bytes_per_sec", std::stoi(args.at(3)));
43-
options.append_parameter_override("window", std::stod(args.at(4)));
44-
if (args.size() >= 6) {
45-
options.append_parameter_override("output_topic", args.at(5));
35+
} else if (args.at(1) == "bytes") {
36+
options.append_parameter_override("throttle_type", "bytes");
37+
if (args.size() >= 5) {
38+
options.append_parameter_override("input_topic", args.at(2));
39+
options.append_parameter_override("bytes_per_sec", std::stoi(args.at(3)));
40+
options.append_parameter_override("window", std::stod(args.at(4)));
41+
if (args.size() >= 6) {
42+
options.append_parameter_override("output_topic", args.at(5));
43+
}
4644
}
4745
}
4846
}
@@ -52,4 +50,4 @@ int main(int argc, char * argv[])
5250
rclcpp::spin(node);
5351
rclcpp::shutdown();
5452
return 0;
55-
}
53+
}

0 commit comments

Comments
 (0)