@@ -314,11 +314,6 @@ TEST_F(TestQosEvent, add_to_wait_set) {
314314
315315TEST_F (TestQosEvent, test_on_new_event_callback)
316316{
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-
322317 auto offered_deadline = rclcpp::Duration (std::chrono::milliseconds (1 ));
323318 auto requested_deadline = rclcpp::Duration (std::chrono::milliseconds (2 ));
324319
@@ -360,11 +355,6 @@ TEST_F(TestQosEvent, test_on_new_event_callback)
360355
361356TEST_F (TestQosEvent, test_invalid_on_new_event_callback)
362357{
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-
368358 auto pub = node->create_publisher <test_msgs::msg::Empty>(topic_name, 10 );
369359 auto sub = node->create_subscription <test_msgs::msg::Empty>(topic_name, 10 , message_callback);
370360 auto dummy_cb = [](size_t count_events) {(void )count_events;};
@@ -439,11 +429,6 @@ TEST_F(TestQosEvent, test_invalid_on_new_event_callback)
439429
440430TEST_F (TestQosEvent, test_pub_matched_event_by_set_event_callback)
441431{
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-
447432 std::atomic_size_t matched_count = 0 ;
448433
449434 rclcpp::PublisherOptions pub_options;
@@ -483,11 +468,6 @@ TEST_F(TestQosEvent, test_pub_matched_event_by_set_event_callback)
483468
484469TEST_F (TestQosEvent, test_sub_matched_event_by_set_event_callback)
485470{
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-
491471 std::atomic_size_t matched_count = 0 ;
492472
493473 rclcpp::SubscriptionOptions sub_options;
0 commit comments