Skip to content

Commit 19a18ba

Browse files
committed
Address review comments
Signed-off-by: Devin Bonnie <dbbonnie@amazon.com>
1 parent 0f5c5ff commit 19a18ba

File tree

3 files changed

+70
-41
lines changed

3 files changed

+70
-41
lines changed

rclcpp/CMakeLists.txt

+4-4
Original file line numberDiff line numberDiff line change
@@ -541,9 +541,9 @@ if(BUILD_TESTING)
541541
target_link_libraries(test_wait_set ${PROJECT_NAME})
542542
endif()
543543

544-
ament_add_gtest(test_subscriber_topic_statistics test/topic_statistics/test_subscriber_topic_statistics.cpp)
545-
if(TARGET test_subscriber_topic_statistics)
546-
ament_target_dependencies(test_subscriber_topic_statistics
544+
ament_add_gtest(test_subscription_topic_statistics test/topic_statistics/test_subscription_topic_statistics.cpp)
545+
if(TARGET test_subscription_topic_statistics)
546+
ament_target_dependencies(test_subscription_topic_statistics
547547
"libstatistics_collector"
548548
"rcl_interfaces"
549549
"rcutils"
@@ -552,7 +552,7 @@ if(BUILD_TESTING)
552552
"rosidl_typesupport_cpp"
553553
"statistics_msgs"
554554
"test_msgs")
555-
target_link_libraries(test_subscriber_topic_statistics ${PROJECT_NAME})
555+
target_link_libraries(test_subscription_topic_statistics ${PROJECT_NAME})
556556
endif()
557557

558558
ament_add_gtest(test_subscription_options test/test_subscription_options.cpp)

rclcpp/include/rclcpp/topic_statistics/subscriber_topic_statistics.hpp rclcpp/include/rclcpp/topic_statistics/subscription_topic_statistics.hpp

+38-32
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef RCLCPP__TOPIC_STATISTICS__SUBSCRIBER_TOPIC_STATISTICS_HPP_
16-
#define RCLCPP__TOPIC_STATISTICS__SUBSCRIBER_TOPIC_STATISTICS_HPP_
15+
#ifndef RCLCPP__TOPIC_STATISTICS__SUBSCRIPTION_TOPIC_STATISTICS_HPP_
16+
#define RCLCPP__TOPIC_STATISTICS__SUBSCRIPTION_TOPIC_STATISTICS_HPP_
1717

1818
#include <memory>
1919
#include <string>
@@ -37,8 +37,8 @@ namespace rclcpp
3737
namespace topic_statistics
3838
{
3939

40-
constexpr const char kDefaultPublishTopicName[]{"topic_statistics"};
41-
constexpr const std::chrono::milliseconds kDefaultPublishingPeriod{std::chrono::minutes(1)};
40+
constexpr const char kDefaultPublishTopicName[]{"/statistics"};
41+
constexpr const std::chrono::milliseconds kDefaultPublishingPeriod{std::chrono::seconds(1)};
4242

4343
using libstatistics_collector::collector::GenerateStatisticMessage;
4444
using statistics_msgs::msg::MetricsMessage;
@@ -51,7 +51,7 @@ using libstatistics_collector::moving_average_statistics::StatisticData;
5151
* \tparam CallbackMessageT the subscribed message type
5252
*/
5353
template<typename CallbackMessageT>
54-
class SubscriberTopicStatistics
54+
class SubscriptionTopicStatistics
5555
{
5656
using TopicStatsCollector =
5757
libstatistics_collector::topic_statistics_collector::TopicStatisticsCollector<
@@ -61,28 +61,33 @@ class SubscriberTopicStatistics
6161
CallbackMessageT>;
6262

6363
public:
64-
/// Construct a SubscriberTopicStatistics object.
64+
/// Construct a SubscriptionTopicStatistics object.
6565
/**
6666
* This object wraps utilities, defined in libstatistics_collector, to collect,
67-
* measure, and publish topic statistics data.
67+
* measure, and publish topic statistics data. This throws an invalid_argument
68+
* if the input publisher is null.
6869
*
69-
* @param node_name the name of the node, which created this instance, in order to denote
70+
* \param node_name the name of the node, which created this instance, in order to denote
7071
* topic source
71-
* @param publisher instance constructed by the node in order to publish statistics data.
72-
* This class owns the publisher/
72+
* \param publisher instance constructed by the node in order to publish statistics data.
73+
* This class owns the publisher.
7374
*/
74-
SubscriberTopicStatistics(
75+
SubscriptionTopicStatistics(
7576
const std::string & node_name,
7677
rclcpp::Publisher<statistics_msgs::msg::MetricsMessage>::SharedPtr publisher)
7778
: node_name_(node_name),
7879
publisher_(std::move(publisher))
7980
{
8081
// TODO(dbbonnie): ros-tooling/aws-roadmap/issues/226, received message age
81-
// TODO(dbbonnie) throw if publisher is null
82+
83+
if (nullptr == publisher_) {
84+
throw std::invalid_argument("publisher pointer is nullptr");
85+
}
86+
8287
bring_up();
8388
}
8489

85-
virtual ~SubscriberTopicStatistics()
90+
virtual ~SubscriptionTopicStatistics()
8691
{
8792
tear_down();
8893
}
@@ -101,29 +106,16 @@ class SubscriberTopicStatistics
101106
}
102107
}
103108

104-
/// Return a vector of all the currently collected data
105-
/**
106-
* \return a vector of all the collected data
107-
*/
108-
std::vector<StatisticData> get_current_collector_data() const
109-
{
110-
std::vector<StatisticData> data;
111-
for (const auto & collector : subscriber_statistics_collectors_) {
112-
data.push_back(collector->GetStatisticsResults());
113-
}
114-
return data;
115-
}
116-
117109
/// Set the timer used to publish statistics messages.
118110
/**
119-
* @param measurement_timer the timer to fire the publisher, created by the node
111+
* \param measurement_timer the timer to fire the publisher, created by the node
120112
*/
121-
void set_publisher_timer(const rclcpp::TimerBase::SharedPtr & publisher_timer)
113+
void set_publisher_timer(rclcpp::TimerBase::SharedPtr publisher_timer)
122114
{
123115
publisher_timer_ = publisher_timer;
124116
}
125117

126-
/// Publish a populated MetricsStatisticsMessage
118+
/// Publish a populated MetricsStatisticsMessage.
127119
virtual void publish_message()
128120
{
129121
rclcpp::Time window_end{get_current_nanoseconds_since_epoch()};
@@ -143,6 +135,20 @@ class SubscriberTopicStatistics
143135
window_start_ = window_end;
144136
}
145137

138+
protected:
139+
/// Return a vector of all the currently collected data.
140+
/**
141+
* \return a vector of all the collected data
142+
*/
143+
std::vector<StatisticData> get_current_collector_data() const
144+
{
145+
std::vector<StatisticData> data;
146+
for (const auto & collector : subscriber_statistics_collectors_) {
147+
data.push_back(collector->GetStatisticsResults());
148+
}
149+
return data;
150+
}
151+
146152
private:
147153
/// Construct and start all collectors and set window_start_.
148154
void bring_up()
@@ -175,7 +181,7 @@ class SubscriberTopicStatistics
175181
/**
176182
* \return the current nanoseconds (count) since epoch
177183
*/
178-
int64_t get_current_nanoseconds_since_epoch()
184+
int64_t get_current_nanoseconds_since_epoch() const
179185
{
180186
const auto now = std::chrono::system_clock::now();
181187
return std::chrono::duration_cast<std::chrono::nanoseconds>(now.time_since_epoch()).count();
@@ -184,7 +190,7 @@ class SubscriberTopicStatistics
184190
/// Collection of statistics collectors
185191
std::vector<std::unique_ptr<TopicStatsCollector>> subscriber_statistics_collectors_{};
186192
/// Node name used to generate topic statistics messages to be published
187-
std::string node_name_;
193+
const std::string node_name_;
188194
/// Publisher, created by the node, used to publish topic statistics messages
189195
rclcpp::Publisher<statistics_msgs::msg::MetricsMessage>::SharedPtr publisher_;
190196
/// Timer which fires the publisher
@@ -195,4 +201,4 @@ class SubscriberTopicStatistics
195201
} // namespace topic_statistics
196202
} // namespace rclcpp
197203

198-
#endif // RCLCPP__TOPIC_STATISTICS__SUBSCRIBER_TOPIC_STATISTICS_HPP_
204+
#endif // RCLCPP__TOPIC_STATISTICS__SUBSCRIPTION_TOPIC_STATISTICS_HPP_

rclcpp/test/topic_statistics/test_subscriber_topic_statistics.cpp rclcpp/test/topic_statistics/test_subscription_topic_statistics.cpp

+28-5
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616

1717
#include <memory>
1818
#include <string>
19+
#include <vector>
1920

2021
#include "libstatistics_collector/moving_average_statistics/types.hpp"
2122

@@ -24,7 +25,7 @@
2425
#include "rclcpp/qos.hpp"
2526
#include "rclcpp/rclcpp.hpp"
2627

27-
#include "rclcpp/topic_statistics/subscriber_topic_statistics.hpp"
28+
#include "rclcpp/topic_statistics/subscription_topic_statistics.hpp"
2829

2930
#include "statistics_msgs/msg/metrics_message.hpp"
3031
#include "test_msgs/msg/empty.hpp"
@@ -39,9 +40,29 @@ constexpr const uint64_t kNoSamples{0};
3940

4041
using test_msgs::msg::Empty;
4142
using statistics_msgs::msg::MetricsMessage;
42-
using rclcpp::topic_statistics::SubscriberTopicStatistics;
43+
using rclcpp::topic_statistics::SubscriptionTopicStatistics;
4344
using libstatistics_collector::moving_average_statistics::StatisticData;
4445

46+
template<typename CallbackMessageT>
47+
class TestSubscriptionTopicStatistics : public SubscriptionTopicStatistics<CallbackMessageT>
48+
{
49+
public:
50+
TestSubscriptionTopicStatistics(
51+
const std::string & node_name,
52+
rclcpp::Publisher<statistics_msgs::msg::MetricsMessage>::SharedPtr publisher)
53+
: SubscriptionTopicStatistics<CallbackMessageT>(node_name, publisher)
54+
{
55+
}
56+
57+
virtual ~TestSubscriptionTopicStatistics() = default;
58+
59+
/// Exposed for testing
60+
std::vector<StatisticData> get_current_collector_data() const
61+
{
62+
return SubscriptionTopicStatistics<CallbackMessageT>::get_current_collector_data();
63+
}
64+
};
65+
4566
/**
4667
* Empty subscriber node: used to create subscriber topic statistics requirements
4768
*/
@@ -61,6 +82,8 @@ class EmptySubscriber : public rclcpp::Node
6182
callback);
6283
}
6384

85+
virtual ~EmptySubscriber() = default;
86+
6487
private:
6588
void receive_message(const Empty &) const
6689
{
@@ -72,7 +95,7 @@ class EmptySubscriber : public rclcpp::Node
7295
/**
7396
* Test fixture to bring up and teardown rclcpp
7497
*/
75-
class TestSubscriberTopicStatisticsFixture : public ::testing::Test
98+
class TestSubscriptionTopicStatisticsFixture : public ::testing::Test
7699
{
77100
protected:
78101
void SetUp()
@@ -91,7 +114,7 @@ class TestSubscriberTopicStatisticsFixture : public ::testing::Test
91114
std::shared_ptr<EmptySubscriber> empty_subscriber;
92115
};
93116

94-
TEST_F(TestSubscriberTopicStatisticsFixture, test_manual_construction)
117+
TEST_F(TestSubscriptionTopicStatisticsFixture, test_manual_construction)
95118
{
96119
// manually create publisher tied to the node
97120
auto topic_stats_publisher =
@@ -100,7 +123,7 @@ TEST_F(TestSubscriberTopicStatisticsFixture, test_manual_construction)
100123
10);
101124

102125
// construct the instance
103-
auto sub_topic_stats = std::make_unique<SubscriberTopicStatistics<Empty>>(
126+
auto sub_topic_stats = std::make_unique<TestSubscriptionTopicStatistics<Empty>>(
104127
empty_subscriber->get_name(),
105128
topic_stats_publisher);
106129

0 commit comments

Comments
 (0)