Skip to content

Commit cdf6632

Browse files
committed
Adds test_stats_with_intra_process_comms to verify that statistics are
collected when use_intra_process_comms=true. Signed-off-by: jayyoung <jay.young@gmail.com>
1 parent e87ed41 commit cdf6632

File tree

1 file changed

+62
-5
lines changed

1 file changed

+62
-5
lines changed

rclcpp/test/rclcpp/topic_statistics/test_subscription_topic_statistics.cpp

Lines changed: 62 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -101,8 +101,9 @@ class PublisherNode : public rclcpp::Node
101101
public:
102102
PublisherNode(
103103
const std::string & name, const std::string & topic,
104-
const std::chrono::milliseconds & publish_period = std::chrono::milliseconds{100})
105-
: Node(name)
104+
const std::chrono::milliseconds & publish_period = std::chrono::milliseconds{100},
105+
bool use_intra_process_comms = false)
106+
: Node(name, rclcpp::NodeOptions().use_intra_process_comms(use_intra_process_comms))
106107
{
107108
publisher_ = create_publisher<MessageT>(topic, 10);
108109
publish_timer_ = this->create_wall_timer(
@@ -181,8 +182,9 @@ class SubscriberWithTopicStatistics : public rclcpp::Node
181182
public:
182183
SubscriberWithTopicStatistics(
183184
const std::string & name, const std::string & topic,
184-
std::chrono::milliseconds publish_period = defaultStatisticsPublishPeriod)
185-
: Node(name)
185+
std::chrono::milliseconds publish_period = defaultStatisticsPublishPeriod,
186+
bool use_intra_process_comms = false)
187+
: Node(name, rclcpp::NodeOptions().use_intra_process_comms(use_intra_process_comms))
186188
{
187189
// Manually enable topic statistics via options
188190
auto options = rclcpp::SubscriptionOptions();
@@ -195,7 +197,7 @@ class SubscriberWithTopicStatistics : public rclcpp::Node
195197
subscription_ = create_subscription<MessageT,
196198
std::function<void(typename MessageT::UniquePtr)>>(
197199
topic,
198-
rclcpp::QoS(rclcpp::KeepAll()),
200+
use_intra_process_comms ? rclcpp::QoS(10) : rclcpp::QoS(rclcpp::KeepAll()),
199201
callback,
200202
options);
201203
}
@@ -421,3 +423,58 @@ TEST_F(TestSubscriptionTopicStatisticsFixture, test_receive_stats_include_window
421423
}
422424
}
423425
}
426+
427+
/**
428+
* Test topic statistics are collected when use_intra_process_comms is enabled.
429+
* This validates a fix for ros2/rclcpp#2911 where IPC subscriptions never called the
430+
* stat handler causing all statistics to report NaN values.
431+
* Also verifies message_age is non-NaN, validating that source_timestamp is set correctly.
432+
*/
433+
TEST_F(TestSubscriptionTopicStatisticsFixture, test_stats_with_intra_process_comms)
434+
{
435+
auto empty_publisher = std::make_shared<PublisherNode<Empty>>(
436+
kTestPubNodeName,
437+
kTestSubStatsEmptyTopic,
438+
std::chrono::milliseconds{100},
439+
true);
440+
441+
auto statistics_listener = std::make_shared<rclcpp::topic_statistics::MetricsMessageSubscriber>(
442+
"test_ipc_stats_listener",
443+
"/statistics",
444+
kNumExpectedMessages);
445+
446+
auto empty_subscriber = std::make_shared<SubscriberWithTopicStatistics<Empty>>(
447+
kTestSubNodeName,
448+
kTestSubStatsEmptyTopic,
449+
defaultStatisticsPublishPeriod,
450+
true);
451+
452+
rclcpp::executors::SingleThreadedExecutor ex;
453+
ex.add_node(empty_publisher);
454+
ex.add_node(statistics_listener);
455+
ex.add_node(empty_subscriber);
456+
457+
ex.spin_until_future_complete(statistics_listener->GetFuture(), kTestTimeout);
458+
459+
const auto received_messages = statistics_listener->GetReceivedMessages();
460+
EXPECT_EQ(kNumExpectedMessages, received_messages.size());
461+
462+
uint64_t message_age_count{0};
463+
uint64_t message_period_count{0};
464+
465+
for (const auto & msg : received_messages) {
466+
if (msg.metrics_source == kMessageAgeSourceLabel) {
467+
message_age_count++;
468+
// Verify message_age stats are non-NaN to validates source_timestamp fix
469+
for (const auto & stats_point : msg.statistics) {
470+
EXPECT_FALSE(std::isnan(stats_point.data));
471+
}
472+
}
473+
if (msg.metrics_source == kMessagePeriodSourceLabel) {
474+
message_period_count++;
475+
}
476+
}
477+
478+
EXPECT_EQ(kNumExpectedMessageAgeMessages, message_age_count);
479+
EXPECT_EQ(kNumExpectedMessagePeriodMessages, message_period_count);
480+
}

0 commit comments

Comments
 (0)