Skip to content

Commit 25d5437

Browse files
AiVerisimilitudemergify[bot]
authored andcommitted
Fix C++20 allocator construct deprecation (#2292)
Signed-off-by: Guilherme Rodrigues <[email protected]> (cherry picked from commit fa732b9)
1 parent b82da1a commit 25d5437

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

rclcpp/include/rclcpp/experimental/intra_process_manager.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -483,8 +483,8 @@ class IntraProcessManager
483483

484484
if constexpr (rclcpp::TypeAdapter<MessageT, ROSMessageType>::is_specialized::value) {
485485
ROSMessageTypeAllocator ros_message_alloc(allocator);
486-
auto ptr = ros_message_alloc.allocate(1);
487-
ros_message_alloc.construct(ptr);
486+
auto ptr = ROSMessageTypeAllocatorTraits::allocate(ros_message_alloc, 1);
487+
ROSMessageTypeAllocatorTraits::construct(ros_message_alloc, ptr);
488488
ROSMessageTypeDeleter deleter;
489489
allocator::set_allocator_for_deleter(&deleter, &allocator);
490490
rclcpp::TypeAdapter<MessageT, ROSMessageType>::convert_to_ros_message(*message, *ptr);

0 commit comments

Comments
 (0)