TypeAdapted publishing doesn't use provided allocator
Bug report
Required Info:
- Operating System:
- Ubuntu 20.04
- Installation type:
- From source
- Version or commit hash:
- DDS implementation:
- Fast-RTPS, RTI Connext
- Client library (if applicable):
- rclcpp
Steps to reproduce issue
Create a publisher using an adapted type and a custom allocator
using AdaptedType = rclcpp::adapt_type<std::string>::as<std_msgs::msg::String>;
auto alloc = std::make_shared<MyAllocator<void>>();
rclcpp::PublisherOptionsWithAllocator<MyAllocator<void>> publisher_options;
publisher_options.allocator = alloc;
auto publisher = node->create_publisher<AdaptedType>(
"allocator_tutorial", 10, publisher_options);
publisher->publish("A string");
Expected behavior
The ROS message that is created by Publisher::publish() will be allocated using the provided allocator.
Actual behavior
The ROS message is allocated using std::make_unique<ROSMessageType>()
Additional information
Rather than using std::make_unique<ROSMessageType>(), the create_ros_message_unique_ptr() can be used instead in the following two locations:
- https://github.com/ros2/rclcpp/blob/f9c4894f96ea083fc5acfcea4f1ea83850759e63/rclcpp/include/rclcpp/publisher.hpp#L323
- https://github.com/ros2/rclcpp/blob/f9c4894f96ea083fc5acfcea4f1ea83850759e63/rclcpp/include/rclcpp/publisher.hpp#L370
- auto ros_msg_ptr = std::make_unique<ROSMessageType>();
+ auto ros_msg_ptr = create_ros_message_unique_ptr();
@thomasmoore-torc thank you for creating the issue and suggested fix, see https://github.com/ros2/rclcpp/pull/2478
@fujitatomoya - I noticed that the Windows build had some test failures, and while looking into that, I noticed that there were some similar issues to this introduced as part of https://github.com/ros2/rclcpp/pull/2303. Would it make sense to incorporate the following changes as part of this issue?
- https://github.com/ros2/rclcpp/blob/f9c4894f96ea083fc5acfcea4f1ea83850759e63/rclcpp/include/rclcpp/publisher.hpp#L333
- https://github.com/ros2/rclcpp/blob/f9c4894f96ea083fc5acfcea4f1ea83850759e63/rclcpp/include/rclcpp/publisher.hpp#L342
- auto ros_msg_ptr = std::make_shared<ROSMessageType>();
+ auto ros_msg_ptr = std::allocate_shared<ROSMessageType, ROSMessageTypeAllocator>(ros_message_type_allocator_);
@thomasmoore-torc thanks for checking this. i was aware of windows failure. will try to patch it as well.