@@ -181,8 +181,9 @@ class SubscriberWithTopicStatistics : public rclcpp::Node
181
181
public:
182
182
SubscriberWithTopicStatistics (
183
183
const std::string & name, const std::string & topic,
184
- std::chrono::milliseconds publish_period = defaultStatisticsPublishPeriod)
185
- : Node(name)
184
+ std::chrono::milliseconds publish_period = defaultStatisticsPublishPeriod,
185
+ bool use_intra_process = false )
186
+ : Node(name, rclcpp::NodeOptions().use_intra_process_comms(use_intra_process))
186
187
{
187
188
// Manually enable topic statistics via options
188
189
auto options = rclcpp::SubscriptionOptions ();
@@ -265,7 +266,7 @@ TEST_F(TestSubscriptionTopicStatisticsFixture, test_invalid_publish_period)
265
266
{
266
267
ASSERT_THROW (
267
268
SubscriberWithTopicStatistics<Empty>(
268
- " test_period_node" , " should_throw_invalid_arg" , std::chrono::milliseconds (0 )
269
+ " test_period_node" , " should_throw_invalid_arg" , std::chrono::milliseconds (0 ), false
269
270
),
270
271
std::invalid_argument);
271
272
}
@@ -278,7 +279,9 @@ TEST_F(TestSubscriptionTopicStatisticsFixture, test_manual_construction)
278
279
{
279
280
auto empty_subscriber = std::make_shared<SubscriberWithTopicStatistics<Empty>>(
280
281
kTestSubNodeName ,
281
- kTestSubStatsEmptyTopic );
282
+ kTestSubStatsEmptyTopic ,
283
+ defaultStatisticsPublishPeriod,
284
+ false );
282
285
283
286
// Manually create publisher tied to the node
284
287
auto topic_stats_publisher =
@@ -322,7 +325,9 @@ TEST_F(TestSubscriptionTopicStatisticsFixture, test_receive_stats_for_message_no
322
325
323
326
auto empty_subscriber = std::make_shared<SubscriberWithTopicStatistics<Empty>>(
324
327
kTestSubNodeName ,
325
- kTestSubStatsEmptyTopic );
328
+ kTestSubStatsEmptyTopic ,
329
+ defaultStatisticsPublishPeriod,
330
+ false );
326
331
327
332
rclcpp::executors::SingleThreadedExecutor ex;
328
333
ex.add_node (empty_publisher);
@@ -367,7 +372,9 @@ TEST_F(TestSubscriptionTopicStatisticsFixture, test_receive_stats_include_window
367
372
auto msg_subscriber_with_topic_statistics =
368
373
std::make_shared<SubscriberWithTopicStatistics<test_msgs::msg::Strings>>(
369
374
kTestSubNodeName ,
370
- kTestSubStatsTopic );
375
+ kTestSubStatsTopic ,
376
+ defaultStatisticsPublishPeriod,
377
+ false );
371
378
372
379
// Create a message publisher
373
380
auto msg_publisher =
@@ -421,3 +428,45 @@ TEST_F(TestSubscriptionTopicStatisticsFixture, test_receive_stats_include_window
421
428
}
422
429
}
423
430
}
431
+
432
+ void run_intra_process_test (bool use_intra_process)
433
+ {
434
+ auto empty_publisher = std::make_shared<PublisherNode<Empty>>(
435
+ kTestPubNodeName ,
436
+ kTestSubStatsEmptyTopic );
437
+ auto statistics_listener = std::make_shared<rclcpp::topic_statistics::MetricsMessageSubscriber>(
438
+ use_intra_process ? " stats_listener_intra" : " stats_listener_inter" ,
439
+ " /statistics" ,
440
+ kNumExpectedWindows );
441
+ auto empty_subscriber = std::make_shared<SubscriberWithTopicStatistics<Empty>>(
442
+ kTestSubNodeName ,
443
+ kTestSubStatsEmptyTopic ,
444
+ defaultStatisticsPublishPeriod,
445
+ use_intra_process);
446
+
447
+ rclcpp::executors::SingleThreadedExecutor ex;
448
+ ex.add_node (empty_publisher);
449
+ ex.add_node (statistics_listener);
450
+ ex.add_node (empty_subscriber);
451
+
452
+ ex.spin_until_future_complete (statistics_listener->GetFuture (), kTestTimeout );
453
+
454
+ const auto received_messages = statistics_listener->GetReceivedMessages ();
455
+ EXPECT_EQ (kNumExpectedWindows , received_messages.size ());
456
+
457
+ for (const auto & msg : received_messages) {
458
+ if (msg.metrics_source == kMessagePeriodSourceLabel ) {
459
+ check_if_statistic_message_is_populated (msg);
460
+ }
461
+ }
462
+ }
463
+
464
+ TEST_F (TestSubscriptionTopicStatisticsFixture, test_stats_period_inter_process)
465
+ {
466
+ run_intra_process_test (false );
467
+ }
468
+
469
+ TEST_F (TestSubscriptionTopicStatisticsFixture, test_stats_period_intra_process)
470
+ {
471
+ run_intra_process_test (true );
472
+ }
0 commit comments