From d6d81e00aecf7024e240a93f768a8ddc703909c0 Mon Sep 17 00:00:00 2001 From: Chen Lihui Date: Fri, 1 Sep 2023 08:28:46 +0800 Subject: [PATCH 1/2] fix TypeAdapter deduction Signed-off-by: Chen Lihui --- rclcpp/include/rclcpp/experimental/intra_process_manager.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rclcpp/include/rclcpp/experimental/intra_process_manager.hpp b/rclcpp/include/rclcpp/experimental/intra_process_manager.hpp index a152632a53..dfcda6207b 100644 --- a/rclcpp/include/rclcpp/experimental/intra_process_manager.hpp +++ b/rclcpp/include/rclcpp/experimental/intra_process_manager.hpp @@ -486,13 +486,13 @@ class IntraProcessManager "subscription use different allocator types, which is not supported"); } - if constexpr (rclcpp::TypeAdapter::is_specialized::value) { + if constexpr (rclcpp::TypeAdapter::is_specialized::value) { ROSMessageTypeAllocator ros_message_alloc(allocator); auto ptr = ros_message_alloc.allocate(1); ros_message_alloc.construct(ptr); ROSMessageTypeDeleter deleter; allocator::set_allocator_for_deleter(&deleter, &allocator); - rclcpp::TypeAdapter::convert_to_ros_message(*message, *ptr); + rclcpp::TypeAdapter::convert_to_ros_message(*message, *ptr); auto ros_msg = std::unique_ptr(ptr, deleter); ros_message_subscription->provide_intra_process_message(std::move(ros_msg)); } else { From f852e580a1b052d9bc4bc4b201854d5ab49075fc Mon Sep 17 00:00:00 2001 From: Chen Lihui Date: Fri, 1 Sep 2023 14:21:23 +0800 Subject: [PATCH 2/2] add a test Signed-off-by: Chen Lihui --- .../test_publisher_with_type_adapter.cpp | 57 ++++++++++++++----- 1 file changed, 43 insertions(+), 14 deletions(-) diff --git a/rclcpp/test/rclcpp/test_publisher_with_type_adapter.cpp b/rclcpp/test/rclcpp/test_publisher_with_type_adapter.cpp index c041d86aee..e96e1e3a38 100644 --- a/rclcpp/test/rclcpp/test_publisher_with_type_adapter.cpp +++ b/rclcpp/test/rclcpp/test_publisher_with_type_adapter.cpp @@ -152,33 +152,54 @@ TEST_F(TestPublisher, conversion_exception_is_passed_up) { } } +using UseTakeSharedMethod = bool; +class TestPublisherFixture + : public TestPublisher, + public ::testing::WithParamInterface +{ +}; + /* * Testing that publisher sends type adapted types and ROS message types with intra proccess communications. */ -TEST_F( - TestPublisher, +TEST_P( + TestPublisherFixture, check_type_adapted_message_is_sent_and_received_intra_process) { using StringTypeAdapter = rclcpp::TypeAdapter; const std::string message_data = "Message Data"; const std::string topic_name = "topic_name"; bool is_received; - auto callback = - [message_data, &is_received]( - const rclcpp::msg::String::ConstSharedPtr msg, - const rclcpp::MessageInfo & message_info - ) -> void - { - is_received = true; - ASSERT_STREQ(message_data.c_str(), msg->data.c_str()); - ASSERT_TRUE(message_info.get_rmw_message_info().from_intra_process); - }; - auto node = rclcpp::Node::make_shared( "test_intra_process", rclcpp::NodeOptions().use_intra_process_comms(true)); auto pub = node->create_publisher(topic_name, 10); - auto sub = node->create_subscription(topic_name, 1, callback); + rclcpp::Subscription::SharedPtr sub; + if (GetParam()) { + auto callback = + [message_data, &is_received]( + const rclcpp::msg::String::ConstSharedPtr msg, + const rclcpp::MessageInfo & message_info + ) -> void + { + is_received = true; + ASSERT_STREQ(message_data.c_str(), msg->data.c_str()); + ASSERT_TRUE(message_info.get_rmw_message_info().from_intra_process); + }; + sub = node->create_subscription(topic_name, 1, callback); + } else { + auto callback_unique = + [message_data, &is_received]( + rclcpp::msg::String::UniquePtr msg, + const rclcpp::MessageInfo & message_info + ) -> void + { + is_received = true; + ASSERT_STREQ(message_data.c_str(), msg->data.c_str()); + ASSERT_TRUE(message_info.get_rmw_message_info().from_intra_process); + }; + sub = node->create_subscription(topic_name, 1, callback_unique); + } auto wait_for_message_to_be_received = [&is_received, &node]() { rclcpp::executors::SingleThreadedExecutor executor; @@ -239,6 +260,14 @@ TEST_F( } } +INSTANTIATE_TEST_SUITE_P( + TestPublisherFixtureWithParam, + TestPublisherFixture, + ::testing::Values( + true, // use take shared method + false // not use take shared method +)); + /* * Testing that publisher sends type adapted types and ROS message types with inter proccess communications. */