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 <Tomoya.Fujita@sony.com>
  • Loading branch information
fujitatomoya committed Apr 3, 2024
1 parent b50f9ab commit 89ca9da
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 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 Down Expand Up @@ -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<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 89ca9da

Please sign in to comment.