1010#include < functional>
1111#include < mutex>
1212
13+ #include < cxxopts.hpp>
14+
1315#include < rclcpp/generic_subscription.hpp>
1416#include < rclcpp/node.hpp>
1517#include < rclcpp/serialized_message.hpp>
@@ -117,9 +119,7 @@ CountMessagesComponent::CountMessagesComponent(const ::rclcpp::NodeOptions& opti
117119 this ->useParams = this ->declare_parameter (" use_parameters" , this ->useParams );
118120 this ->intraprocessComms = this ->declare_parameter (" intraprocess_comms" , this ->intraprocessComms );
119121 this ->topicStats = this ->declare_parameter (" topic_statistics" , this ->topicStats );
120- const auto reportIntervalDouble = this ->declare_parameter (" report_interval" , 0.0 );
121- const auto reportInterval = std::chrono::round<std::chrono::nanoseconds>(
122- std::chrono::duration<float >(reportIntervalDouble));
122+ auto reportIntervalDouble = this ->declare_parameter (" report_interval" , 0.0 );
123123
124124 auto qosProfileStr = this ->declare_parameter (" qos_profile" , " " );
125125 auto qosDepthParam = maybeParam<int >(this ->declare_parameter (" qos_depth" , rclcpp::PARAMETER_INTEGER));
@@ -136,13 +136,36 @@ CountMessagesComponent::CountMessagesComponent(const ::rclcpp::NodeOptions& opti
136136 // Support direct command-line usage
137137 if (options.arguments ().size () > 1 )
138138 {
139- if (options.arguments ().size () > 3 )
140- throw std::invalid_argument (" Usage: count_messages [<topic_name> [<qos_profile>]]" );
141- this ->topic = options.arguments ()[1 ];
142- if (options.arguments ().size () > 2 )
143- qosProfileStr = options.arguments ()[2 ];
139+ cxxopts::Options parser (" count_messages" , " Count ROS messages" );
140+ parser.add_options ()
141+ (" topic" , " Topic" , cxxopts::value<std::string>()->default_value (" input" ))
142+ (" qos-profile,p" , " QoS Profile" , cxxopts::value<std::string>()->default_value (" " ))
143+ (" report,r" , " Reporting interval" , cxxopts::value<double >()->default_value (" 0" )->implicit_value (" 1" ))
144+ (" help,h" , " Help" );
145+ parser.parse_positional ({" topic" , " qos-profile" });
146+ parser.positional_help (" [TOPIC [QOS-PROFILE]]" );
147+ parser.show_positional_help ();
148+
149+ std::vector<const char *> argv;
150+ for (const auto & arg : options.arguments ())
151+ argv.push_back (arg.c_str ());
152+ const auto args = parser.parse (argv.size (), argv.data ());
153+
154+ if (args.count (" help" ))
155+ throw std::invalid_argument (parser.help ());
156+
157+ this ->topic = args[" topic" ].as <std::string>();
158+
159+ if (args.count (" qos-profile" ) == 1 && !args[" qos-profile" ].as <std::string>().empty ())
160+ qosProfileStr = args[" qos-profile" ].as <std::string>();
161+
162+ if (args.count (" report" ) == 1 )
163+ reportIntervalDouble = args[" report" ].as <double >();
144164 }
145165
166+ const auto reportInterval = std::chrono::round<std::chrono::nanoseconds>(
167+ std::chrono::duration<float >(reportIntervalDouble));
168+
146169 const auto defaultQoS = rclcpp::BestAvailableQoS ().keep_last (1000 );
147170 this ->qosProfile = qosProfileStr.empty () ? defaultQoS : parseQoSPreset (qosProfileStr);
148171 cras::configureQoSProfile (this ->qosProfile , qosDepthParam, qosHistoryParam, qosReliabilityParam, qosDurabilityParam,
0 commit comments