Skip to content

Commit 119a7bc

Browse files
Add test creating two content filter topics with the same topic name (#2546) (#2549) (#2552)
Signed-off-by: Mario-DL <[email protected]> Co-authored-by: Mario Domínguez López <[email protected]> (cherry picked from commit 7c09688) Co-authored-by: Alejandro Hernández Cordero <[email protected]>
1 parent 0beba97 commit 119a7bc

File tree

1 file changed

+22
-0
lines changed

1 file changed

+22
-0
lines changed

rclcpp/test/rclcpp/test_subscription_content_filter.cpp

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -310,3 +310,25 @@ TEST_F(CLASSNAME(TestContentFilterSubscription, RMW_IMPLEMENTATION), content_fil
310310
}
311311
}
312312
}
313+
314+
TEST_F(
315+
CLASSNAME(
316+
TestContentFilterSubscription,
317+
RMW_IMPLEMENTATION), create_two_content_filters_with_same_topic_name_and_destroy) {
318+
319+
// Create another content filter
320+
auto options = rclcpp::SubscriptionOptions();
321+
322+
std::string filter_expression = "int32_value > %0";
323+
std::vector<std::string> expression_parameters = {"4"};
324+
325+
options.content_filter_options.filter_expression = filter_expression;
326+
options.content_filter_options.expression_parameters = expression_parameters;
327+
328+
auto callback = [](std::shared_ptr<const test_msgs::msg::BasicTypes>) {};
329+
auto sub_2 = node->create_subscription<test_msgs::msg::BasicTypes>(
330+
"content_filter_topic", qos, callback, options);
331+
332+
EXPECT_NE(nullptr, sub_2);
333+
sub_2.reset();
334+
}

0 commit comments

Comments
 (0)