Skip to content

Commit

Permalink
use custom allocator from publisher option.
Browse files Browse the repository at this point in the history
Signed-off-by: Tomoya Fujita <[email protected]>
  • Loading branch information
fujitatomoya committed Apr 14, 2024
1 parent 90e4511 commit 5fd47c4
Showing 1 changed file with 6 additions and 4 deletions.
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

0 comments on commit 5fd47c4

Please sign in to comment.