Skip to content

Commit 2b94e70

Browse files
author
Prajakta Gokhale
authored
Create new topic statistics demo package (#454)
* Create new topic statistics demo package Signed-off-by: Prajakta Gokhale <[email protected]> * Remove dependencies Signed-off-by: Prajakta Gokhale <[email protected]> * Add demo files Signed-off-by: Prajakta Gokhale <[email protected]> * Add uniform distribution to msg age calculation Signed-off-by: Prajakta Gokhale <[email protected]> * Log when timestamp offset is added Signed-off-by: Prajakta Gokhale <[email protected]>
1 parent ab95bef commit 2b94e70

File tree

10 files changed

+691
-0
lines changed

10 files changed

+691
-0
lines changed
Lines changed: 40 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,40 @@
1+
cmake_minimum_required(VERSION 3.5)
2+
3+
project(topic_statistics_demo)
4+
5+
# Default to C++14
6+
if(NOT CMAKE_CXX_STANDARD)
7+
set(CMAKE_CXX_STANDARD 14)
8+
endif()
9+
10+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
11+
add_compile_options(-Wall -Wextra -Wpedantic)
12+
endif()
13+
14+
find_package(ament_cmake REQUIRED)
15+
find_package(rclcpp REQUIRED)
16+
find_package(rcutils)
17+
find_package(sensor_msgs REQUIRED)
18+
find_package(statistics_msgs REQUIRED)
19+
20+
include_directories(include)
21+
ament_export_include_directories(include)
22+
23+
add_executable(display_topic_statistics
24+
src/imu_talker_listener_nodes.cpp
25+
src/display_topic_statistics.cpp
26+
src/string_talker_listener_nodes.cpp
27+
src/topic_statistics_listener.cpp)
28+
ament_target_dependencies(display_topic_statistics
29+
"rclcpp"
30+
"rcutils"
31+
"sensor_msgs"
32+
"statistics_msgs")
33+
install(TARGETS display_topic_statistics DESTINATION lib/${PROJECT_NAME})
34+
35+
if(BUILD_TESTING)
36+
find_package(ament_lint_auto REQUIRED)
37+
ament_lint_auto_find_test_dependencies()
38+
endif()
39+
40+
ament_package()

topic_statistics_demo/README.md

Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,20 @@
1+
# Topic Statistics Demo
2+
3+
The demo application in this package demonstrates [Topic Statistics](https://index.ros.org/doc/ros2/Concepts/About-Topic-Statistics/) feature in ROS 2.
4+
The application creates ROS 2 nodes to publish messages to topics, subscribes to the statistics topic and displays the statistics data received.
5+
6+
The demo application in this package `display_topic_statistics` creates the following ROS 2 nodes:
7+
1. Talker and Listener nodes to generate message traffic
8+
2. Statistics listener node to display generated statistics
9+
10+
The application requires an argument `message_type` - the type of message chatter to generate.
11+
Possible values are `string` and `imu`.
12+
13+
The application also accepts the following optional arguments to configure the Listener node's subscription:
14+
1. `--publish-topic`: Topic to which topic statistics are published. Default topic is `/statistics`.
15+
2. `--publish-period`: Publish period for publication of statistics. Default value is 5s.
16+
17+
Once the application starts, the talker node will publish messages on a topic that the listener node has subscribed to.
18+
The listener's subscription will generate topic statistics upon receiving messages.
19+
Statistics are published to the statistics topic at a pre-determined frequency.
20+
The statistics listener node listens to these statistics and prints them for the user to see.
Lines changed: 86 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,86 @@
1+
// Copyright 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef TOPIC_STATISTICS_DEMO__IMU_TALKER_LISTENER_NODES_HPP_
16+
#define TOPIC_STATISTICS_DEMO__IMU_TALKER_LISTENER_NODES_HPP_
17+
18+
#include <chrono>
19+
#include <memory>
20+
#include <random>
21+
#include <string>
22+
23+
#include "rclcpp/rclcpp.hpp"
24+
#include "sensor_msgs/msg/imu.hpp"
25+
26+
namespace imu_msgs
27+
{
28+
constexpr char DEFAULT_TOPIC_NAME[] = "imu_chatter";
29+
}
30+
31+
class ImuTalker : public rclcpp::Node
32+
{
33+
public:
34+
/// Standard constructor.
35+
/**
36+
* \param[in] topic_name Topic to publish chatter messages to.
37+
* \param[in] publish_period Frequency of publishing chatter messages.
38+
**/
39+
ImuTalker(
40+
const std::string & topic_name = imu_msgs::DEFAULT_TOPIC_NAME,
41+
std::chrono::milliseconds publish_period = std::chrono::milliseconds(1000));
42+
43+
/// Initialize the publisher.
44+
void initialize();
45+
46+
/// Publish a single message.
47+
void publish();
48+
49+
private:
50+
rclcpp::Publisher<sensor_msgs::msg::Imu>::SharedPtr publisher_ = nullptr;
51+
52+
const std::string topic_name_;
53+
std::chrono::milliseconds publish_period_ = std::chrono::milliseconds(1000);
54+
rclcpp::TimerBase::SharedPtr publish_timer_ = nullptr;
55+
56+
std::random_device random_number_seed_;
57+
std::mt19937 random_generator_;
58+
std::uniform_real_distribution<> random_distribution_;
59+
};
60+
61+
class ImuListener : public rclcpp::Node
62+
{
63+
public:
64+
/// Standard Constructor.
65+
/**
66+
* \param[in] topic_name Topic to subscribe to.
67+
* \param[in] subscription_options SubscriptionOptions to use for the subscription.
68+
*/
69+
ImuListener(
70+
const std::string & topic_name = imu_msgs::DEFAULT_TOPIC_NAME,
71+
const rclcpp::SubscriptionOptions & subscription_options = rclcpp::SubscriptionOptions());
72+
73+
/// Initialize the listener node.
74+
void initialize();
75+
76+
/// Instantiate a Subscription to the chatter topic.
77+
void start_listening();
78+
79+
private:
80+
rclcpp::SubscriptionOptions subscription_options_;
81+
rclcpp::Subscription<sensor_msgs::msg::Imu>::SharedPtr subscription_ = nullptr;
82+
83+
const std::string topic_name_;
84+
};
85+
86+
#endif // TOPIC_STATISTICS_DEMO__IMU_TALKER_LISTENER_NODES_HPP_
Lines changed: 83 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,83 @@
1+
// Copyright 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef TOPIC_STATISTICS_DEMO__STRING_TALKER_LISTENER_NODES_HPP_
16+
#define TOPIC_STATISTICS_DEMO__STRING_TALKER_LISTENER_NODES_HPP_
17+
18+
#include <chrono>
19+
#include <memory>
20+
#include <string>
21+
22+
#include "rclcpp/rclcpp.hpp"
23+
#include "std_msgs/msg/string.hpp"
24+
25+
namespace string_msgs
26+
{
27+
constexpr char DEFAULT_TOPIC_NAME[] = "string_chatter";
28+
}
29+
30+
class StringTalker : public rclcpp::Node
31+
{
32+
public:
33+
/// Standard constructor.
34+
/**
35+
* \param[in] topic_name Topic to publish chatter messages to.
36+
* \param[in] publish_period Frequency of publishing chatter messages.
37+
**/
38+
StringTalker(
39+
const std::string & topic_name = string_msgs::DEFAULT_TOPIC_NAME,
40+
std::chrono::milliseconds publish_period = std::chrono::milliseconds(1000));
41+
42+
/// Initialize the publisher.
43+
void initialize();
44+
45+
/// Publish a single message.
46+
void publish();
47+
48+
private:
49+
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_ = nullptr;
50+
51+
const std::string topic_name_;
52+
53+
std::chrono::milliseconds publish_period_ = std::chrono::milliseconds(1000);
54+
rclcpp::TimerBase::SharedPtr publish_timer_ = nullptr;
55+
size_t publish_count_ = 0;
56+
};
57+
58+
class StringListener : public rclcpp::Node
59+
{
60+
public:
61+
/// Standard constructor.
62+
/**
63+
* \param[in] topic_name Topic to subscribe to.
64+
* \param[in] subscription_options SubscriptionOptions to use for the subscription.
65+
*/
66+
StringListener(
67+
const std::string & topic_name = string_msgs::DEFAULT_TOPIC_NAME,
68+
const rclcpp::SubscriptionOptions & subscription_options = rclcpp::SubscriptionOptions());
69+
70+
/// Initialize the listener node.
71+
void initialize();
72+
73+
/// Instantiate a Subscription to the chatter topic.
74+
void start_listening();
75+
76+
private:
77+
rclcpp::SubscriptionOptions subscription_options_;
78+
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_ = nullptr;
79+
80+
const std::string topic_name_;
81+
};
82+
83+
#endif // TOPIC_STATISTICS_DEMO__STRING_TALKER_LISTENER_NODES_HPP_
Lines changed: 58 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,58 @@
1+
// Copyright 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef TOPIC_STATISTICS_DEMO__TOPIC_STATISTICS_LISTENER_HPP_
16+
#define TOPIC_STATISTICS_DEMO__TOPIC_STATISTICS_LISTENER_HPP_
17+
18+
#include <string>
19+
20+
#include "rclcpp/rclcpp.hpp"
21+
#include "statistics_msgs/msg/metrics_message.hpp"
22+
23+
namespace topic_stats_demo
24+
{
25+
constexpr char STATISTICS_TOPIC_NAME[] = "statistics";
26+
}
27+
28+
class TopicStatisticsListener : public rclcpp::Node
29+
{
30+
public:
31+
/// Standard Constructor.
32+
/**
33+
* \param[in] topic_name Topic to which statistics are published.
34+
*/
35+
explicit TopicStatisticsListener(
36+
const std::string & topic_name = topic_stats_demo::STATISTICS_TOPIC_NAME);
37+
38+
/// Initialize the listener node.
39+
void initialize();
40+
41+
/// Return string representation of a MetricsMessage.
42+
/**
43+
* \param[in] results Statistics heard form the subscribed topic.
44+
* \param[out] String representation of the input statistics.
45+
*/
46+
std::string MetricsMessageToString(const statistics_msgs::msg::MetricsMessage & results);
47+
48+
/// Instantiate a Subscription to the statistics topic.
49+
void start_listening();
50+
51+
private:
52+
rclcpp::SubscriptionOptions subscription_options_;
53+
rclcpp::Subscription<statistics_msgs::msg::MetricsMessage>::SharedPtr subscription_ = nullptr;
54+
55+
const std::string topic_name_;
56+
};
57+
58+
#endif // TOPIC_STATISTICS_DEMO__TOPIC_STATISTICS_LISTENER_HPP_

topic_statistics_demo/package.xml

Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,30 @@
1+
<?xml version="1.0"?>
2+
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
3+
<package format="3">
4+
<name>topic_statistics_demo</name>
5+
<version>0.9.3</version>
6+
<description>C++ demo application for topic statistics feature.</description>
7+
8+
<maintainer email="[email protected]">Amazon ROS Contributions</maintainer>
9+
10+
<license>Apache License 2.0</license>
11+
12+
<buildtool_depend>ament_cmake</buildtool_depend>
13+
14+
<build_depend>rclcpp</build_depend>
15+
<build_depend>rcutils</build_depend>
16+
<build_depend>sensor_msgs</build_depend>
17+
<build_depend>statistics_msgs</build_depend>
18+
19+
<exec_depend>rclcpp</exec_depend>
20+
<exec_depend>rcutils</exec_depend>
21+
<exec_depend>sensor_msgs</exec_depend>
22+
<exec_depend>statistics_msgs</exec_depend>
23+
24+
<test_depend>ament_lint_auto</test_depend>
25+
<test_depend>ament_lint_common</test_depend>
26+
27+
<export>
28+
<build_type>ament_cmake</build_type>
29+
</export>
30+
</package>

0 commit comments

Comments
 (0)