@@ -152,33 +152,54 @@ TEST_F(TestPublisher, conversion_exception_is_passed_up) {
152152 }
153153}
154154
155+ using UseTakeSharedMethod = bool ;
156+ class TestPublisherFixture
157+ : public TestPublisher,
158+ public ::testing::WithParamInterface<UseTakeSharedMethod>
159+ {
160+ };
161+
155162/*
156163 * Testing that publisher sends type adapted types and ROS message types with intra proccess communications.
157164 */
158- TEST_F (
159- TestPublisher ,
165+ TEST_P (
166+ TestPublisherFixture ,
160167 check_type_adapted_message_is_sent_and_received_intra_process) {
161168 using StringTypeAdapter = rclcpp::TypeAdapter<std::string, rclcpp::msg::String>;
162169 const std::string message_data = " Message Data" ;
163170 const std::string topic_name = " topic_name" ;
164171 bool is_received;
165172
166- auto callback =
167- [message_data, &is_received](
168- const rclcpp::msg::String::ConstSharedPtr msg,
169- const rclcpp::MessageInfo & message_info
170- ) -> void
171- {
172- is_received = true ;
173- ASSERT_STREQ (message_data.c_str (), msg->data .c_str ());
174- ASSERT_TRUE (message_info.get_rmw_message_info ().from_intra_process );
175- };
176-
177173 auto node = rclcpp::Node::make_shared (
178174 " test_intra_process" ,
179175 rclcpp::NodeOptions ().use_intra_process_comms (true ));
180176 auto pub = node->create_publisher <StringTypeAdapter>(topic_name, 10 );
181- auto sub = node->create_subscription <rclcpp::msg::String>(topic_name, 1 , callback);
177+ rclcpp::Subscription<rclcpp::msg::String>::SharedPtr sub;
178+ if (GetParam ()) {
179+ auto callback =
180+ [message_data, &is_received](
181+ const rclcpp::msg::String::ConstSharedPtr msg,
182+ const rclcpp::MessageInfo & message_info
183+ ) -> void
184+ {
185+ is_received = true ;
186+ ASSERT_STREQ (message_data.c_str (), msg->data .c_str ());
187+ ASSERT_TRUE (message_info.get_rmw_message_info ().from_intra_process );
188+ };
189+ sub = node->create_subscription <rclcpp::msg::String>(topic_name, 1 , callback);
190+ } else {
191+ auto callback_unique =
192+ [message_data, &is_received](
193+ rclcpp::msg::String::UniquePtr msg,
194+ const rclcpp::MessageInfo & message_info
195+ ) -> void
196+ {
197+ is_received = true ;
198+ ASSERT_STREQ (message_data.c_str (), msg->data .c_str ());
199+ ASSERT_TRUE (message_info.get_rmw_message_info ().from_intra_process );
200+ };
201+ sub = node->create_subscription <rclcpp::msg::String>(topic_name, 1 , callback_unique);
202+ }
182203
183204 auto wait_for_message_to_be_received = [&is_received, &node]() {
184205 rclcpp::executors::SingleThreadedExecutor executor;
@@ -239,6 +260,14 @@ TEST_F(
239260 }
240261}
241262
263+ INSTANTIATE_TEST_SUITE_P (
264+ TestPublisherFixtureWithParam,
265+ TestPublisherFixture,
266+ ::testing::Values (
267+ true , // use take shared method
268+ false // not use take shared method
269+ ));
270+
242271/*
243272 * Testing that publisher sends type adapted types and ROS message types with inter proccess communications.
244273 */
0 commit comments