|
12 | 12 |
|
13 | 13 | #include <cxxopts.hpp> |
14 | 14 |
|
| 15 | +#include <rclcpp/utilities.hpp> |
15 | 16 | #include <rclcpp/generic_subscription.hpp> |
16 | 17 | #include <rclcpp/node.hpp> |
17 | 18 | #include <rclcpp/serialized_message.hpp> |
@@ -138,29 +139,38 @@ CountMessagesComponent::CountMessagesComponent(const ::rclcpp::NodeOptions& opti |
138 | 139 | { |
139 | 140 | cxxopts::Options parser("count_messages", "Count ROS messages"); |
140 | 141 | 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"); |
145 | 146 | parser.parse_positional({"topic", "qos-profile"}); |
146 | 147 | parser.positional_help("[TOPIC [QOS-PROFILE]]"); |
147 | 148 | parser.show_positional_help(); |
148 | 149 |
|
| 150 | + // Convert all args to argc/argv, remove ROS-specific args and convert to argc/argv again |
149 | 151 | std::vector<const char*> argv; |
150 | 152 | for (const auto& arg : options.arguments()) |
151 | 153 | 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()); |
153 | 162 |
|
154 | | - if (args.count("help")) |
155 | | - throw std::invalid_argument(parser.help()); |
| 163 | + if (args.count("help")) |
| 164 | + throw std::invalid_argument(parser.help()); |
156 | 165 |
|
157 | | - this->topic = args["topic"].as<std::string>(); |
| 166 | + this->topic = args["topic"].as<std::string>(); |
158 | 167 |
|
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>(); |
161 | 170 |
|
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 | + } |
164 | 174 | } |
165 | 175 |
|
166 | 176 | const auto reportInterval = std::chrono::round<std::chrono::nanoseconds>( |
|
0 commit comments