diff --git a/rclcpp/test/rclcpp/strategies/test_allocator_memory_strategy.cpp b/rclcpp/test/rclcpp/strategies/test_allocator_memory_strategy.cpp index c068e8f640..e1b916e9c0 100644 --- a/rclcpp/test/rclcpp/strategies/test_allocator_memory_strategy.cpp +++ b/rclcpp/test/rclcpp/strategies/test_allocator_memory_strategy.cpp @@ -497,14 +497,8 @@ TEST_F(TestAllocatorMemoryStrategy, add_remove_waitables) { TEST_F(TestAllocatorMemoryStrategy, number_of_entities_with_subscription) { RclWaitSetSizes expected_sizes = {}; expected_sizes.size_of_subscriptions = 1; - const std::string implementation_identifier = rmw_get_implementation_identifier(); - if (implementation_identifier == "rmw_cyclonedds_cpp" || - implementation_identifier == "rmw_connextdds") - { - // For cyclonedds and connext, a subscription will also add an event and waitable - expected_sizes.size_of_events += 1; - expected_sizes.size_of_waitables += 1; - } + expected_sizes.size_of_events = 1; + expected_sizes.size_of_waitables = 1; auto node_with_subscription = create_node_with_subscription("subscription_node"); EXPECT_TRUE(TestNumberOfEntitiesAfterCollection(node_with_subscription, expected_sizes)); } diff --git a/rclcpp/test/rclcpp/test_qos_event.cpp b/rclcpp/test/rclcpp/test_qos_event.cpp index ebf0e14afb..f234591e33 100644 --- a/rclcpp/test/rclcpp/test_qos_event.cpp +++ b/rclcpp/test/rclcpp/test_qos_event.cpp @@ -37,9 +37,6 @@ class TestQosEvent : public ::testing::Test void SetUp() { - is_fastrtps = - std::string(rmw_get_implementation_identifier()).find("rmw_fastrtps") != std::string::npos; - node = std::make_shared("test_qos_event", "/ns"); message_callback = [node = node.get()](test_msgs::msg::Empty::ConstSharedPtr /*msg*/) { @@ -54,7 +51,6 @@ class TestQosEvent : public ::testing::Test static constexpr char topic_name[] = "test_topic"; rclcpp::Node::SharedPtr node; - bool is_fastrtps; std::function message_callback; }; @@ -101,12 +97,8 @@ TEST_F(TestQosEvent, test_publisher_constructor) "Offered incompatible qos - total %d (delta %d), last_policy_kind: %d", event.total_count, event.total_count_change, event.last_policy_kind); }; - try { - publisher = node->create_publisher( - topic_name, 10, options); - } catch (const rclcpp::UnsupportedEventTypeException & /*exc*/) { - EXPECT_TRUE(is_fastrtps); - } + publisher = node->create_publisher( + topic_name, 10, options); } /* @@ -151,12 +143,8 @@ TEST_F(TestQosEvent, test_subscription_constructor) "Requested incompatible qos - total %d (delta %d), last_policy_kind: %d", event.total_count, event.total_count_change, event.last_policy_kind); }; - try { - subscription = node->create_subscription( - topic_name, 10, message_callback, options); - } catch (const rclcpp::UnsupportedEventTypeException & /*exc*/) { - EXPECT_TRUE(is_fastrtps); - } + subscription = node->create_subscription( + topic_name, 10, message_callback, options); } /* @@ -210,22 +198,17 @@ TEST_F(TestQosEvent, test_default_incompatible_qos_callbacks) ex.add_node(node->get_node_base_interface()); // This future won't complete on fastrtps, so just timeout immediately - const auto timeout = (is_fastrtps) ? std::chrono::milliseconds(5) : std::chrono::seconds(10); + const auto timeout = std::chrono::seconds(10); ex.spin_until_future_complete(log_msgs_future, timeout); - if (is_fastrtps) { - EXPECT_EQ("", pub_log_msg); - EXPECT_EQ("", sub_log_msg); - } else { - EXPECT_EQ( - "New subscription discovered on topic '/ns/test_topic', requesting incompatible QoS. " - "No messages will be sent to it. Last incompatible policy: DURABILITY_QOS_POLICY", - pub_log_msg); - EXPECT_EQ( - "New publisher discovered on topic '/ns/test_topic', offering incompatible QoS. " - "No messages will be sent to it. Last incompatible policy: DURABILITY_QOS_POLICY", - sub_log_msg); - } + EXPECT_EQ( + "New subscription discovered on topic '/ns/test_topic', requesting incompatible QoS. " + "No messages will be sent to it. Last incompatible policy: DURABILITY_QOS_POLICY", + pub_log_msg); + EXPECT_EQ( + "New publisher discovered on topic '/ns/test_topic', offering incompatible QoS. " + "No messages will be sent to it. Last incompatible policy: DURABILITY_QOS_POLICY", + sub_log_msg); rcutils_logging_set_output_handler(original_output_handler); }