Skip to content

Commit 5342f80

Browse files
committed
cras_cpp_common: count_messages: Fixed launching in component container.
1 parent 58b4833 commit 5342f80

File tree

1 file changed

+22
-12
lines changed

1 file changed

+22
-12
lines changed

cras_topic_tools/src/count_messages.cpp

Lines changed: 22 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212

1313
#include <cxxopts.hpp>
1414

15+
#include <rclcpp/utilities.hpp>
1516
#include <rclcpp/generic_subscription.hpp>
1617
#include <rclcpp/node.hpp>
1718
#include <rclcpp/serialized_message.hpp>
@@ -138,29 +139,38 @@ CountMessagesComponent::CountMessagesComponent(const ::rclcpp::NodeOptions& opti
138139
{
139140
cxxopts::Options parser("count_messages", "Count ROS messages");
140141
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");
142+
("topic", "Topic", cxxopts::value<std::string>()->default_value("input"))
143+
("qos-profile,p", "QoS Profile", cxxopts::value<std::string>()->default_value(""))
144+
("report,r", "Reporting interval", cxxopts::value<double>()->default_value("0")->implicit_value("1"))
145+
("help,h", "Help");
145146
parser.parse_positional({"topic", "qos-profile"});
146147
parser.positional_help("[TOPIC [QOS-PROFILE]]");
147148
parser.show_positional_help();
148149

150+
// Convert all args to argc/argv, remove ROS-specific args and convert to argc/argv again
149151
std::vector<const char*> argv;
150152
for (const auto& arg : options.arguments())
151153
argv.push_back(arg.c_str());
152-
const auto args = parser.parse(argv.size(), argv.data());
154+
const auto tmpArgs = rclcpp::remove_ros_arguments(argv.size(), argv.data());
155+
argv.clear();
156+
for (const auto& arg : tmpArgs)
157+
argv.push_back(arg.c_str());
158+
159+
if (argv.size() > 0)
160+
{
161+
const auto args = parser.parse(argv.size(), argv.data());
153162

154-
if (args.count("help"))
155-
throw std::invalid_argument(parser.help());
163+
if (args.count("help"))
164+
throw std::invalid_argument(parser.help());
156165

157-
this->topic = args["topic"].as<std::string>();
166+
this->topic = args["topic"].as<std::string>();
158167

159-
if (args.count("qos-profile") == 1 && !args["qos-profile"].as<std::string>().empty())
160-
qosProfileStr = args["qos-profile"].as<std::string>();
168+
if (args.count("qos-profile") == 1 && !args["qos-profile"].as<std::string>().empty())
169+
qosProfileStr = args["qos-profile"].as<std::string>();
161170

162-
if (args.count("report") == 1)
163-
reportIntervalDouble = args["report"].as<double>();
171+
if (args.count("report") == 1)
172+
reportIntervalDouble = args["report"].as<double>();
173+
}
164174
}
165175

166176
const auto reportInterval = std::chrono::round<std::chrono::nanoseconds>(

0 commit comments

Comments
 (0)