Skip to content

Commit c6234b8

Browse files
committed
use custom allocator from publisher option.
Signed-off-by: Tomoya Fujita <[email protected]>
1 parent b50f9ab commit c6234b8

File tree

1 file changed

+6
-4
lines changed

1 file changed

+6
-4
lines changed

rclcpp/include/rclcpp/publisher.hpp

+6-4
Original file line numberDiff line numberDiff line change
@@ -320,7 +320,7 @@ class Publisher : public PublisherBase
320320
{
321321
if (!intra_process_is_enabled_) {
322322
// In this case we're not using intra process.
323-
auto ros_msg_ptr = std::make_unique<ROSMessageType>();
323+
auto ros_msg_ptr = create_ros_message_unique_ptr();
324324
rclcpp::TypeAdapter<MessageT>::convert_to_ros_message(*msg, *ros_msg_ptr);
325325
this->do_inter_process_publish(*ros_msg_ptr);
326326
return;
@@ -330,7 +330,8 @@ class Publisher : public PublisherBase
330330
get_subscription_count() > get_intra_process_subscription_count();
331331

332332
if (inter_process_publish_needed) {
333-
auto ros_msg_ptr = std::make_shared<ROSMessageType>();
333+
auto ros_msg_ptr = std::allocate_shared<
334+
ROSMessageType, ROSMessageTypeAllocator>(ros_message_type_allocator_);
334335
rclcpp::TypeAdapter<MessageT>::convert_to_ros_message(*msg, *ros_msg_ptr);
335336
this->do_intra_process_publish(std::move(msg));
336337
this->do_inter_process_publish(*ros_msg_ptr);
@@ -339,7 +340,8 @@ class Publisher : public PublisherBase
339340
}
340341
} else {
341342
if (buffer_) {
342-
auto ros_msg_ptr = std::make_shared<ROSMessageType>();
343+
auto ros_msg_ptr = std::allocate_shared<
344+
ROSMessageType, ROSMessageTypeAllocator>(ros_message_type_allocator_);
343345
rclcpp::TypeAdapter<MessageT>::convert_to_ros_message(*msg, *ros_msg_ptr);
344346
buffer_->add_shared(ros_msg_ptr);
345347
}
@@ -367,7 +369,7 @@ class Publisher : public PublisherBase
367369
{
368370
if (!intra_process_is_enabled_) {
369371
// Convert to the ROS message equivalent and publish it.
370-
auto ros_msg_ptr = std::make_unique<ROSMessageType>();
372+
auto ros_msg_ptr = create_ros_message_unique_ptr();
371373
rclcpp::TypeAdapter<MessageT>::convert_to_ros_message(msg, *ros_msg_ptr);
372374
this->do_inter_process_publish(*ros_msg_ptr);
373375
return;

0 commit comments

Comments
 (0)