diff --git a/demo_nodes_cpp/src/topics/allocator_tutorial.cpp b/demo_nodes_cpp/src/topics/allocator_tutorial.cpp index a84b6e998..8d6f37b91 100644 --- a/demo_nodes_cpp/src/topics/allocator_tutorial.cpp +++ b/demo_nodes_cpp/src/topics/allocator_tutorial.cpp @@ -170,12 +170,19 @@ int main(int argc, char ** argv) // Create a custom allocator and pass the allocator to the publisher and subscriber. auto alloc = std::make_shared>(); - auto publisher = node->create_publisher("allocator_tutorial", 10, alloc); + rclcpp::PublisherOptionsWithAllocator> publisher_options; + publisher_options.allocator = alloc; + // pub_opts.allocator = alloc; + auto publisher = node->create_publisher( + "allocator_tutorial", 10, publisher_options); + + rclcpp::SubscriptionOptionsWithAllocator> subscription_options; + subscription_options.allocator = alloc; auto msg_mem_strat = std::make_shared< rclcpp::message_memory_strategy::MessageMemoryStrategy< std_msgs::msg::UInt32, MyAllocator<>>>(alloc); auto subscriber = node->create_subscription( - "allocator_tutorial", callback, 10, nullptr, false, msg_mem_strat, alloc); + "allocator_tutorial", callback, 10, subscription_options, msg_mem_strat); // Create a MemoryStrategy, which handles the allocations made by the Executor during the // execution path, and inject the MemoryStrategy into the Executor.