1414
1515#include < gtest/gtest.h>
1616
17+ #include < atomic>
1718#include < chrono>
1819#include < functional>
1920#include < future>
@@ -313,6 +314,11 @@ TEST_F(TestQosEvent, add_to_wait_set) {
313314
314315TEST_F (TestQosEvent, test_on_new_event_callback)
315316{
317+ // rmw_connextdds doesn't support rmw_event_set_callback() interface
318+ if (std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 ) {
319+ GTEST_SKIP ();
320+ }
321+
316322 auto offered_deadline = rclcpp::Duration (std::chrono::milliseconds (1 ));
317323 auto requested_deadline = rclcpp::Duration (std::chrono::milliseconds (2 ));
318324
@@ -354,6 +360,11 @@ TEST_F(TestQosEvent, test_on_new_event_callback)
354360
355361TEST_F (TestQosEvent, test_invalid_on_new_event_callback)
356362{
363+ // rmw_connextdds doesn't support rmw_event_set_callback() interface
364+ if (std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 ) {
365+ GTEST_SKIP ();
366+ }
367+
357368 auto pub = node->create_publisher <test_msgs::msg::Empty>(topic_name, 10 );
358369 auto sub = node->create_subscription <test_msgs::msg::Empty>(topic_name, 10 , message_callback);
359370 auto dummy_cb = [](size_t count_events) {(void )count_events;};
@@ -376,6 +387,12 @@ TEST_F(TestQosEvent, test_invalid_on_new_event_callback)
376387 EXPECT_NO_THROW (
377388 pub->clear_on_new_qos_event_callback (RCL_PUBLISHER_OFFERED_INCOMPATIBLE_QOS));
378389
390+ EXPECT_NO_THROW (
391+ pub->set_on_new_qos_event_callback (dummy_cb, RCL_PUBLISHER_MATCHED));
392+
393+ EXPECT_NO_THROW (
394+ pub->clear_on_new_qos_event_callback (RCL_PUBLISHER_MATCHED));
395+
379396 EXPECT_NO_THROW (
380397 sub->set_on_new_qos_event_callback (dummy_cb, RCL_SUBSCRIPTION_REQUESTED_DEADLINE_MISSED));
381398
@@ -394,6 +411,12 @@ TEST_F(TestQosEvent, test_invalid_on_new_event_callback)
394411 EXPECT_NO_THROW (
395412 sub->clear_on_new_qos_event_callback (RCL_SUBSCRIPTION_REQUESTED_INCOMPATIBLE_QOS));
396413
414+ EXPECT_NO_THROW (
415+ sub->set_on_new_qos_event_callback (dummy_cb, RCL_SUBSCRIPTION_MATCHED));
416+
417+ EXPECT_NO_THROW (
418+ sub->clear_on_new_qos_event_callback (RCL_SUBSCRIPTION_MATCHED));
419+
397420 std::function<void (size_t )> invalid_cb;
398421
399422 rclcpp::SubscriptionOptions sub_options;
@@ -413,3 +436,170 @@ TEST_F(TestQosEvent, test_invalid_on_new_event_callback)
413436 pub->set_on_new_qos_event_callback (invalid_cb, RCL_PUBLISHER_OFFERED_DEADLINE_MISSED),
414437 std::invalid_argument);
415438}
439+
440+ TEST_F (TestQosEvent, test_pub_matched_event_by_set_event_callback)
441+ {
442+ // rmw_connextdds doesn't support rmw_event_set_callback() interface
443+ if (std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 ) {
444+ GTEST_SKIP ();
445+ }
446+
447+ std::atomic_size_t matched_count = 0 ;
448+
449+ rclcpp::PublisherOptions pub_options;
450+ pub_options.event_callbacks .matched_callback = [](auto ) {};
451+ auto pub = node->create_publisher <test_msgs::msg::Empty>(
452+ topic_name, 10 , pub_options);
453+
454+ auto matched_event_callback = [&matched_count](size_t count) {
455+ matched_count += count;
456+ };
457+
458+ pub->set_on_new_qos_event_callback (matched_event_callback, RCL_PUBLISHER_MATCHED);
459+
460+ rclcpp::executors::SingleThreadedExecutor ex;
461+ ex.add_node (node->get_node_base_interface ());
462+
463+ const auto timeout = std::chrono::milliseconds (200 );
464+
465+ {
466+ auto sub1 = node->create_subscription <test_msgs::msg::Empty>(topic_name, 10 , message_callback);
467+ ex.spin_some (timeout);
468+ EXPECT_EQ (matched_count, static_cast <size_t >(1 ));
469+
470+ {
471+ auto sub2 = node->create_subscription <test_msgs::msg::Empty>(
472+ topic_name, 10 , message_callback);
473+ ex.spin_some (timeout);
474+ EXPECT_EQ (matched_count, static_cast <size_t >(2 ));
475+ }
476+ ex.spin_some (timeout);
477+ EXPECT_EQ (matched_count, static_cast <size_t >(3 ));
478+ }
479+
480+ ex.spin_some (timeout);
481+ EXPECT_EQ (matched_count, static_cast <size_t >(4 ));
482+ }
483+
484+ TEST_F (TestQosEvent, test_sub_matched_event_by_set_event_callback)
485+ {
486+ // rmw_connextdds doesn't support rmw_event_set_callback() interface
487+ if (std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 ) {
488+ GTEST_SKIP ();
489+ }
490+
491+ std::atomic_size_t matched_count = 0 ;
492+
493+ rclcpp::SubscriptionOptions sub_options;
494+ sub_options.event_callbacks .matched_callback = [](auto ) {};
495+ auto sub = node->create_subscription <test_msgs::msg::Empty>(
496+ topic_name, 10 , message_callback, sub_options);
497+
498+ auto matched_event_callback = [&matched_count](size_t count) {
499+ matched_count += count;
500+ };
501+
502+ sub->set_on_new_qos_event_callback (matched_event_callback, RCL_SUBSCRIPTION_MATCHED);
503+
504+ rclcpp::executors::SingleThreadedExecutor ex;
505+ ex.add_node (node->get_node_base_interface ());
506+
507+ const auto timeout = std::chrono::milliseconds (200 );
508+
509+ {
510+ auto pub1 = node->create_publisher <test_msgs::msg::Empty>(topic_name, 10 );
511+
512+ ex.spin_some (timeout);
513+ EXPECT_EQ (matched_count, static_cast <size_t >(1 ));
514+
515+ {
516+ auto pub2 = node->create_publisher <test_msgs::msg::Empty>(topic_name, 10 );
517+ ex.spin_some (timeout);
518+ EXPECT_EQ (matched_count, static_cast <size_t >(2 ));
519+ }
520+
521+ ex.spin_some (timeout);
522+ EXPECT_EQ (matched_count, static_cast <size_t >(3 ));
523+ }
524+
525+ ex.spin_some (timeout);
526+ EXPECT_EQ (matched_count, static_cast <size_t >(4 ));
527+ }
528+
529+ TEST_F (TestQosEvent, test_pub_matched_event_by_option_event_callback)
530+ {
531+ rmw_matched_status_t matched_expected_result;
532+
533+ rclcpp::PublisherOptions pub_options;
534+ pub_options.event_callbacks .matched_callback =
535+ [&matched_expected_result](rmw_matched_status_t & s) {
536+ EXPECT_EQ (s.total_count , matched_expected_result.total_count );
537+ EXPECT_EQ (s.total_count_change , matched_expected_result.total_count_change );
538+ EXPECT_EQ (s.current_count , matched_expected_result.current_count );
539+ EXPECT_EQ (s.current_count_change , matched_expected_result.current_count_change );
540+ };
541+
542+ auto pub = node->create_publisher <test_msgs::msg::Empty>(
543+ topic_name, 10 , pub_options);
544+
545+ rclcpp::executors::SingleThreadedExecutor ex;
546+ ex.add_node (node->get_node_base_interface ());
547+
548+ // Create a connected subscription
549+ matched_expected_result.total_count = 1 ;
550+ matched_expected_result.total_count_change = 1 ;
551+ matched_expected_result.current_count = 1 ;
552+ matched_expected_result.current_count_change = 1 ;
553+
554+ const auto timeout = std::chrono::milliseconds (200 );
555+
556+ {
557+ auto sub = node->create_subscription <test_msgs::msg::Empty>(topic_name, 10 , message_callback);
558+ ex.spin_some (timeout);
559+
560+ // destroy a connected subscription
561+ matched_expected_result.total_count = 1 ;
562+ matched_expected_result.total_count_change = 0 ;
563+ matched_expected_result.current_count = 0 ;
564+ matched_expected_result.current_count_change = -1 ;
565+ }
566+ ex.spin_some (timeout);
567+ }
568+
569+ TEST_F (TestQosEvent, test_sub_matched_event_by_option_event_callback)
570+ {
571+ rmw_matched_status_t matched_expected_result;
572+
573+ rclcpp::SubscriptionOptions sub_options;
574+ sub_options.event_callbacks .matched_callback =
575+ [&matched_expected_result](rmw_matched_status_t & s) {
576+ EXPECT_EQ (s.total_count , matched_expected_result.total_count );
577+ EXPECT_EQ (s.total_count_change , matched_expected_result.total_count_change );
578+ EXPECT_EQ (s.current_count , matched_expected_result.current_count );
579+ EXPECT_EQ (s.current_count_change , matched_expected_result.current_count_change );
580+ };
581+ auto sub = node->create_subscription <test_msgs::msg::Empty>(
582+ topic_name, 10 , message_callback, sub_options);
583+
584+ rclcpp::executors::SingleThreadedExecutor ex;
585+ ex.add_node (node->get_node_base_interface ());
586+
587+ // Create a connected publisher
588+ matched_expected_result.total_count = 1 ;
589+ matched_expected_result.total_count_change = 1 ;
590+ matched_expected_result.current_count = 1 ;
591+ matched_expected_result.current_count_change = 1 ;
592+
593+ const auto timeout = std::chrono::milliseconds (200 );
594+ {
595+ auto pub1 = node->create_publisher <test_msgs::msg::Empty>(topic_name, 10 );
596+ ex.spin_some (timeout);
597+
598+ // destroy a connected publisher
599+ matched_expected_result.total_count = 1 ;
600+ matched_expected_result.total_count_change = 0 ;
601+ matched_expected_result.current_count = 0 ;
602+ matched_expected_result.current_count_change = -1 ;
603+ }
604+ ex.spin_some (timeout);
605+ }
0 commit comments