Skip to content

Commit 58b4833

Browse files
committed
cras_topic_tools: change_header: Added --report CLI option.
1 parent 201cdf7 commit 58b4833

File tree

3 files changed

+35
-9
lines changed

3 files changed

+35
-9
lines changed

cras_topic_tools/CMakeLists.txt

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,8 @@
11
cmake_minimum_required(VERSION 3.20.2)
22
project(cras_topic_tools)
33

4+
find_package(cxxopts REQUIRED)
5+
46
find_package(ament_cmake REQUIRED)
57
find_package(cras_cpp_common REQUIRED)
68
find_package(cras_msgs REQUIRED)
@@ -28,7 +30,7 @@ target_include_directories(cras_count_messages PUBLIC
2830
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
2931
target_link_libraries(cras_count_messages PUBLIC rclcpp::rclcpp)
3032
target_link_libraries(cras_count_messages PRIVATE
31-
rclcpp_components::component ${cras_cpp_common_TARGETS})
33+
rclcpp_components::component cxxopts::cxxopts ${cras_cpp_common_TARGETS})
3234
rclcpp_components_register_node(cras_count_messages PLUGIN cras::CountMessagesComponent EXECUTABLE count_messages)
3335
add_dependencies(count_messages cras_count_messages) # workaround https://github.com/ros2/rclcpp/issues/2868
3436

cras_topic_tools/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
<depend>rclcpp_components</depend>
2121

2222
<build_depend>cras_msgs</build_depend>
23+
<build_depend>libcxxopts-dev</build_depend>
2324
<build_depend>std_msgs</build_depend>
2425
<build_depend>topic_tools</build_depend>
2526

cras_topic_tools/src/count_messages.cpp

Lines changed: 31 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,8 @@
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

Comments
 (0)