@@ -320,7 +320,7 @@ class Publisher : public PublisherBase
320
320
{
321
321
if (!intra_process_is_enabled_) {
322
322
// 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 ();
324
324
rclcpp::TypeAdapter<MessageT>::convert_to_ros_message (*msg, *ros_msg_ptr);
325
325
this ->do_inter_process_publish (*ros_msg_ptr);
326
326
return ;
@@ -330,7 +330,8 @@ class Publisher : public PublisherBase
330
330
get_subscription_count () > get_intra_process_subscription_count ();
331
331
332
332
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_);
334
335
rclcpp::TypeAdapter<MessageT>::convert_to_ros_message (*msg, *ros_msg_ptr);
335
336
this ->do_intra_process_publish (std::move (msg));
336
337
this ->do_inter_process_publish (*ros_msg_ptr);
@@ -339,7 +340,8 @@ class Publisher : public PublisherBase
339
340
}
340
341
} else {
341
342
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_);
343
345
rclcpp::TypeAdapter<MessageT>::convert_to_ros_message (*msg, *ros_msg_ptr);
344
346
buffer_->add_shared (ros_msg_ptr);
345
347
}
@@ -367,7 +369,7 @@ class Publisher : public PublisherBase
367
369
{
368
370
if (!intra_process_is_enabled_) {
369
371
// 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 ();
371
373
rclcpp::TypeAdapter<MessageT>::convert_to_ros_message (msg, *ros_msg_ptr);
372
374
this ->do_inter_process_publish (*ros_msg_ptr);
373
375
return ;
0 commit comments