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

use custom allocator from publisher option. #2478

Open
wants to merge 2 commits into
base: rolling
Choose a base branch
from
Open
Changes from 1 commit
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
10 changes: 6 additions & 4 deletions rclcpp/include/rclcpp/publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -320,7 +320,7 @@ class Publisher : public PublisherBase
{
if (!intra_process_is_enabled_) {
// In this case we're not using intra process.
auto ros_msg_ptr = std::make_unique<ROSMessageType>();
auto ros_msg_ptr = create_ros_message_unique_ptr();
rclcpp::TypeAdapter<MessageT>::convert_to_ros_message(*msg, *ros_msg_ptr);
this->do_inter_process_publish(*ros_msg_ptr);
return;
Expand All @@ -330,7 +330,8 @@ class Publisher : public PublisherBase
get_subscription_count() > get_intra_process_subscription_count();

if (inter_process_publish_needed) {
auto ros_msg_ptr = std::make_shared<ROSMessageType>();
auto ros_msg_ptr = std::allocate_shared<
ROSMessageType, ROSMessageTypeAllocator>(ros_message_type_allocator_);
rclcpp::TypeAdapter<MessageT>::convert_to_ros_message(*msg, *ros_msg_ptr);
this->do_intra_process_publish(std::move(msg));
this->do_inter_process_publish(*ros_msg_ptr);
Expand All @@ -339,7 +340,8 @@ class Publisher : public PublisherBase
}
} else {
if (buffer_) {
auto ros_msg_ptr = std::make_shared<ROSMessageType>();
auto ros_msg_ptr = std::allocate_shared<
ROSMessageType, ROSMessageTypeAllocator>(ros_message_type_allocator_);
rclcpp::TypeAdapter<MessageT>::convert_to_ros_message(*msg, *ros_msg_ptr);
buffer_->add_shared(ros_msg_ptr);
}
Expand Down Expand Up @@ -367,7 +369,7 @@ class Publisher : public PublisherBase
{
if (!intra_process_is_enabled_) {
// Convert to the ROS message equivalent and publish it.
auto ros_msg_ptr = std::make_unique<ROSMessageType>();
auto ros_msg_ptr = create_ros_message_unique_ptr();
rclcpp::TypeAdapter<MessageT>::convert_to_ros_message(msg, *ros_msg_ptr);
this->do_inter_process_publish(*ros_msg_ptr);
return;
Expand Down