From d98854e3812fca3f2dc4e7f50705db9287ed07a1 Mon Sep 17 00:00:00 2001 From: Brian Gerkey Date: Thu, 8 Oct 2009 19:43:04 +0000 Subject: [PATCH] Fixed command-line parsing to handle ROS args, #1862 --- tools/topic_tools/src/drop.cpp | 16 +++++++++++----- tools/topic_tools/src/throttle.cpp | 9 +++++---- 2 files changed, 16 insertions(+), 9 deletions(-) diff --git a/tools/topic_tools/src/drop.cpp b/tools/topic_tools/src/drop.cpp index d9130b31..0831d12e 100644 --- a/tools/topic_tools/src/drop.cpp +++ b/tools/topic_tools/src/drop.cpp @@ -66,18 +66,24 @@ void in_cb(const boost::shared_ptr& msg) s_count = 0; } +#define USAGE "\nusage: drop IN_TOPIC X Y [OUT_TOPIC]\n\n" \ + " This program will drop X out of every Y messages from IN_TOPIC,\n" \ + " forwarding the rest to OUT_TOPIC if given, else to a topic \n" \ + " named IN_TOPIC_drop\n\n" int main(int argc, char **argv) { - if ((argc != 4 && argc != 5) || atoi(argv[2]) < 0 || atoi(argv[3]) < 1) + if(argc < 2) { - printf("\nusage: drop IN_TOPIC X Y [OUT_TOPIC]\n\n" - " This program will drop X out of every Y messages from IN_TOPIC,\n" - " forwarding the rest to OUT_TOPIC if given, else to a topic \n" - " named IN_TOPIC_drop\n\n"); + puts(USAGE); return 1; } ros::init(argc, argv, string(argv[1]) + string("_drop"), ros::init_options::AnonymousName); + if ((argc != 4 && argc != 5) || atoi(argv[2]) < 0 || atoi(argv[3]) < 1) + { + puts(USAGE); + return 1; + } if (argc == 4) g_output_topic = string(argv[1]) + string("_drop"); else // argc == 5 diff --git a/tools/topic_tools/src/throttle.cpp b/tools/topic_tools/src/throttle.cpp index 01306c22..bc8cfe50 100644 --- a/tools/topic_tools/src/throttle.cpp +++ b/tools/topic_tools/src/throttle.cpp @@ -125,6 +125,11 @@ int main(int argc, char **argv) return 1; } + string intopic = string(argv[2]); + + ros::init(argc, argv, intopic + string("_throttle"), + ros::init_options::AnonymousName); + if(!strcmp(argv[1], "messages")) g_use_messages = true; else if(!strcmp(argv[1], "bytes")) @@ -134,8 +139,6 @@ int main(int argc, char **argv) puts(USAGE); return 1; } - - string intopic = string(argv[2]); if(g_use_messages && argc == 5) g_output_topic = string(argv[4]); @@ -159,8 +162,6 @@ int main(int argc, char **argv) g_window = atof(argv[4]); } - ros::init(argc, argv, intopic + string("_throttle"), - ros::init_options::AnonymousName); ros::NodeHandle n; g_node = &n; ros::Subscriber sub = n.subscribe(intopic, 10, &in_cb);