From 89ca9da5dbabb178215df14953eb1084c701e0d1 Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Tue, 2 Apr 2024 22:40:20 -0700 Subject: [PATCH] use custom allocator from publisher option. Signed-off-by: Tomoya Fujita --- rclcpp/include/rclcpp/publisher.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rclcpp/include/rclcpp/publisher.hpp b/rclcpp/include/rclcpp/publisher.hpp index c6f16643c6..0bc9e0aeb7 100644 --- a/rclcpp/include/rclcpp/publisher.hpp +++ b/rclcpp/include/rclcpp/publisher.hpp @@ -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(); + auto ros_msg_ptr = create_ros_message_unique_ptr(); rclcpp::TypeAdapter::convert_to_ros_message(*msg, *ros_msg_ptr); this->do_inter_process_publish(*ros_msg_ptr); return; @@ -367,7 +367,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(); + auto ros_msg_ptr = create_ros_message_unique_ptr(); rclcpp::TypeAdapter::convert_to_ros_message(msg, *ros_msg_ptr); this->do_inter_process_publish(*ros_msg_ptr); return;