Skip to content

Commit

Permalink
adjust main()
Browse files Browse the repository at this point in the history
Signed-off-by: maksymdidukh <[email protected]>
  • Loading branch information
maksymdidukh committed Mar 5, 2024
1 parent cefac47 commit ecc7e1b
Showing 1 changed file with 20 additions and 22 deletions.
42 changes: 20 additions & 22 deletions topic_tools/src/throttle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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));
}
}
}
}
Expand All @@ -52,4 +50,4 @@ int main(int argc, char * argv[])
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
}

0 comments on commit ecc7e1b

Please sign in to comment.