启用主题统计(C++)
目标: 启用 ROS 2 主题统计并查看输出统计数据。
教程级别: 高级
时间: 10 分钟
背景
这是一个简短的教程,介绍如何在 ROS 2 中启用主题统计信息并使用命令行工具 (ros2topic) 查看已发布的统计信息输出。
ROS 2 为任何订阅收到的消息提供综合统计测量,称为主题统计信息。 启用订阅的主题统计信息后,您可以描述系统的性能或使用数据帮助诊断任何现有问题。
有关更多详细信息,请参阅 主题统计信息概念页面。
先决条件
从二进制文件或源代码安装。
在之前的教程中,您学习了如何:doc:创建工作区、 创建包,以及如何创建:doc:C++ 发布者和订阅者。
本教程假设您仍然拥有:doc:C++ 教程中的 cpp_pubsub
包。
任务
1 编写启用统计信息的订阅者节点
导航到在 上一个教程 中创建的 ros2_ws/src/cpp_pubsub/src
文件夹,然后
输入以下命令下载示例 talker 代码:
wget -O member_function_with_topic_statistics.cpp https://raw.githubusercontent.com/ros2/examples/rolling/rclcpp/topics/minimal_subscriber/member_function_with_topic_statistics.cpp
wget -O member_function_with_topic_statistics.cpp https://raw.githubusercontent.com/ros2/examples/rolling/rclcpp/topics/minimal_subscriber/member_function_with_topic_statistics.cpp
Right click this link and select Save As publisher_member_function.cpp
:
现在将有一个名为“member_function_with_topic_statistics.cpp”的新文件。 使用您喜欢的文本编辑器打开该文件。
#include <chrono>
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/subscription_options.hpp"
#include "std_msgs/msg/string.hpp"
class MinimalSubscriberWithTopicStatistics : public rclcpp::Node
{
public:
MinimalSubscriberWithTopicStatistics()
: Node("minimal_subscriber_with_topic_statistics")
{
// manually enable topic statistics via options
auto options = rclcpp::SubscriptionOptions();
options.topic_stats_options.state = rclcpp::TopicStatisticsState::Enable;
// configure the collection window and publish period (default 1s)
options.topic_stats_options.publish_period = std::chrono::seconds(10);
// configure the topic name (default '/statistics')
// options.topic_stats_options.publish_topic = "/topic_statistics"
auto callback = [this](std_msgs::msg::String::SharedPtr msg) {
this->topic_callback(msg);
};
subscription_ = this->create_subscription<std_msgs::msg::String>(
"topic", 10, callback, options);
}
private:
void topic_callback(const std_msgs::msg::String::ConstSharedPtr msg) const
{
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
}
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalSubscriberWithTopicStatistics>());
rclcpp::shutdown();
return 0;
}
1.1 检查代码
如 C++ 教程中所述,我们有一个订阅者节点,它从 topic_callback
函数接收来自
topic
主题的字符串消息。
但是,我们现在添加了选项来配置订阅,以便使用
rclcpp::SubscriptionOptions()
选项结构启用主题统计信息。
// manually enable topic statistics via options
auto options = rclcpp::SubscriptionOptions();
options.topic_stats_options.state = rclcpp::TopicStatisticsState::Enable;
可选地,还可以配置诸如统计数据收集/发布期以及用于发布统计数据的主题等字段。
// configure the collection window and publish period (default 1s)
options.topic_stats_options.publish_period = std::chrono::seconds(10);
// configure the topic name (default '/statistics')
// options.topic_stats_options.publish_topic = "/my_topic"
可配置字段说明如下表:
Subscription Config Field |
Purpose |
---|---|
topic_stats_options.state |
Enable or disable topic statistics (default |
topic_stats_options.publish_period |
The period in which to collect statistics data and publish a statistics message (default |
topic_stats_options.publish_topic |
The topic to use when publishing statistics data (default |
1.2 CMakeLists.txt
现在打开“CMakeLists.txt”文件。
添加可执行文件并将其命名为“listener_with_topic_statistics”,以便您可以使用“ros2 run”运行您的节点:
add_executable(listener_with_topic_statistics src/member_function_with_topic_statistics.cpp)
ament_target_dependencies(listener_with_topic_statistics rclcpp std_msgs)
install(TARGETS
talker
listener
listener_with_topic_statistics
DESTINATION lib/${PROJECT_NAME})
确保保存文件,然后启用了主题统计信息的发布/订阅系统 就可以使用了。
2 构建并运行
要构建,请参阅发布/订阅教程中的 构建并运行 部分。
运行启用了统计信息的订阅者节点:
ros2 run cpp_pubsub listener_with_topic_statistics
现在运行 talker 节点:
ros2 run cpp_pubsub talker
终端应该每 0.5 秒开始发布一次信息消息,如下所示:
[INFO] [minimal_publisher]: Publishing: "Hello World: 0"
[INFO] [minimal_publisher]: Publishing: "Hello World: 1"
[INFO] [minimal_publisher]: Publishing: "Hello World: 2"
[INFO] [minimal_publisher]: Publishing: "Hello World: 3"
[INFO] [minimal_publisher]: Publishing: "Hello World: 4"
监听器将开始将消息打印到控制台,从发布者当时的消息计数开始,如下所示:
[INFO] [minimal_subscriber_with_topic_statistics]: I heard: "Hello World: 10"
[INFO] [minimal_subscriber_with_topic_statistics]: I heard: "Hello World: 11"
[INFO] [minimal_subscriber_with_topic_statistics]: I heard: "Hello World: 12"
[INFO] [minimal_subscriber_with_topic_statistics]: I heard: "Hello World: 13"
[INFO] [minimal_subscriber_with_topic_statistics]: I heard: "Hello World: 14"
现在订阅者节点正在接收消息,它将定期发布统计消息。 我们将在下一节中观察这些消息。
3 观察已发布的统计数据
在节点运行时,打开一个新的终端窗口。 执行以下命令:
ros2 topic list
这将列出所有当前活跃的主题。 您应该看到以下内容:
/parameter_events
/rosout
/statistics
/topic
如果您在本教程前面部分中选择性地更改了 topic_stats_options.publish_topic
字段,
那么您将看到该名称而不是 /statistics
。
您创建的订阅者节点正在将主题 topic
的统计信息发布到输出主题
/statistics
。
我们可以使用 RQt 来可视化它
现在我们可以通过以下命令查看发布到该主题的统计数据:
ros2 topic echo /statistics
终端应该开始每 10 秒发布一次统计消息,因为“topic_stats_options.publish_period”订阅配置在本教程前面可以选择更改。
---
measurement_source_name: minimal_subscriber_with_topic_statistics
metrics_source: message_age
unit: ms
window_start:
sec: 1594856666
nanosec: 931527366
window_stop:
sec: 1594856676
nanosec: 930797670
statistics:
- data_type: 1
data: .nan
- data_type: 3
data: .nan
- data_type: 2
data: .nan
- data_type: 5
data: 0.0
- data_type: 4
data: .nan
---
measurement_source_name: minimal_subscriber_with_topic_statistics
metrics_source: message_period
unit: ms
window_start:
sec: 1594856666
nanosec: 931527366
window_stop:
sec: 1594856676
nanosec: 930797670
statistics:
- data_type: 1
data: 499.2746365105009
- data_type: 3
data: 500.0
- data_type: 2
data: 499.0
- data_type: 5
data: 619.0
- data_type: 4
data: 0.4463309283488427
---
From the message definition
the data_types
are as follows
data_type value |
statistics |
---|---|
1 |
average |
2 |
minimum |
3 |
maximum |
4 |
standard deviation |
5 |
sample count |
这里我们可以看到 minimal_publisher
发布到 /topic
的 std_msgs::msg::String
消息目前可能计算的两个统计数据。
由于 std_msgs::msg::String
没有消息头,因此无法执行 message_age
计算,
因此返回 NaN。
但是,可以计算 message_period
,并且我们看到统计数据填充在上面的消息中。
摘要
您创建了一个启用了主题统计信息的订阅者节点,它从 C++ 的发布者节点发布统计数据。您可以编译并运行此节点。在运行时,
您可以观察统计数据。
相关内容
要观察“message_age”周期的计算方式,请参阅 ROS 2 Topic Statistics demo.