Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Topic correct typeadapter deduction #2294

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/experimental/intra_process_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -486,13 +486,13 @@ class IntraProcessManager
"subscription use different allocator types, which is not supported");
}

if constexpr (rclcpp::TypeAdapter<MessageT>::is_specialized::value) {
if constexpr (rclcpp::TypeAdapter<MessageT, ROSMessageType>::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<MessageT>::convert_to_ros_message(*message, *ptr);
rclcpp::TypeAdapter<MessageT, ROSMessageType>::convert_to_ros_message(*message, *ptr);
auto ros_msg = std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>(ptr, deleter);
ros_message_subscription->provide_intra_process_message(std::move(ros_msg));
} else {
Expand Down
57 changes: 43 additions & 14 deletions rclcpp/test/rclcpp/test_publisher_with_type_adapter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -152,33 +152,54 @@ TEST_F(TestPublisher, conversion_exception_is_passed_up) {
}
}

using UseTakeSharedMethod = bool;
class TestPublisherFixture
: public TestPublisher,
public ::testing::WithParamInterface<UseTakeSharedMethod>
{
};

/*
* 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<std::string, rclcpp::msg::String>;
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<StringTypeAdapter>(topic_name, 10);
auto sub = node->create_subscription<rclcpp::msg::String>(topic_name, 1, callback);
rclcpp::Subscription<rclcpp::msg::String>::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<rclcpp::msg::String>(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<rclcpp::msg::String>(topic_name, 1, callback_unique);
}

auto wait_for_message_to_be_received = [&is_received, &node]() {
rclcpp::executors::SingleThreadedExecutor executor;
Expand Down Expand Up @@ -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.
*/
Expand Down