Skip to content

Commit

Permalink
Remove fastrtps customization on tests (#1887)
Browse files Browse the repository at this point in the history
Signed-off-by: Miguel Company <[email protected]>
  • Loading branch information
MiguelCompany authored Feb 22, 2022
1 parent 4f77819 commit c5a16dc
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 38 deletions.
10 changes: 2 additions & 8 deletions rclcpp/test/rclcpp/strategies/test_allocator_memory_strategy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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));
}
Expand Down
43 changes: 13 additions & 30 deletions rclcpp/test/rclcpp/test_qos_event.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<rclcpp::Node>("test_qos_event", "/ns");

message_callback = [node = node.get()](test_msgs::msg::Empty::ConstSharedPtr /*msg*/) {
Expand All @@ -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<void(test_msgs::msg::Empty::ConstSharedPtr)> message_callback;
};

Expand Down Expand Up @@ -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<test_msgs::msg::Empty>(
topic_name, 10, options);
} catch (const rclcpp::UnsupportedEventTypeException & /*exc*/) {
EXPECT_TRUE(is_fastrtps);
}
publisher = node->create_publisher<test_msgs::msg::Empty>(
topic_name, 10, options);
}

/*
Expand Down Expand Up @@ -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<test_msgs::msg::Empty>(
topic_name, 10, message_callback, options);
} catch (const rclcpp::UnsupportedEventTypeException & /*exc*/) {
EXPECT_TRUE(is_fastrtps);
}
subscription = node->create_subscription<test_msgs::msg::Empty>(
topic_name, 10, message_callback, options);
}

/*
Expand Down Expand Up @@ -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);
}
Expand Down

0 comments on commit c5a16dc

Please sign in to comment.