Skip to content

Potential new/delete mismatch when publishing a custom type that has overloaded new/delete operators (e.g. pcl::PointCloud) using type adapters #2951

@iv461

Description

@iv461

Generated by Generative AI

No

Operating System:

Ubuntu 24

ROS version or commit hash:

jazzy

RMW implementation (if applicable):

zenoh

RMW Configuration (if applicable):

No response

Client library (if applicable):

rclcpp

'ros2 doctor --report' output

No response

Steps to reproduce issue

Using the following minimal code

#include <pcl/point_cloud.h>
#include <pcl/point_types.h>

#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>

template <class PointType>
struct rclcpp::TypeAdapter<pcl::PointCloud<PointType>, sensor_msgs::msg::PointCloud2> {
  using is_specialized = std::true_type;
  using custom_type = pcl::PointCloud<PointType>;
  using ros_message_type = sensor_msgs::msg::PointCloud2;

  static void convert_to_ros_message(const pcl::PointCloud<PointType>& source,
                                     sensor_msgs::msg::PointCloud2& destination) {}

  static void convert_to_custom(const sensor_msgs::msg::PointCloud2& source,
                                pcl::PointCloud<PointType>& destination) {}
};

int main() {
  auto node = std::make_shared<rclcpp::Node>("mismatched_new_delete_reproducer");
  auto pub = node->create_publisher<
      rclcpp::adapt_type<pcl::PointCloud<pcl::PointXYZ>>::as<sensor_msgs::msg::PointCloud2>>(
      "/point_cloud", 1);
  
  pcl::PointCloud<pcl::PointXYZ> point_cloud;
  pub->publish(point_cloud);
  
}

the compiler correctly detects a new/delete mismatch and reports a warning:


In file included from /usr/include/eigen3/Eigen/Core:166,
                 from /usr/include/eigen3/Eigen/Dense:1,
                 from /home/ivo/colcon_ws/src/my_package/my_node.cpp:
In function ‘void Eigen::internal::aligned_free(void*)’,
    inlined from ‘void Eigen::internal::conditional_aligned_free(void*) [with bool Align = true]’ at /usr/include/eigen3/Eigen/src/Core/util/Memory.h:259:15,
    inlined from ‘static void pcl::PointCloud<PointT>::operator delete(void*) [with PointT = pcl::PointXYZ]’ at /usr/include/pcl-1.14/pcl/point_cloud.h:900:7,
    inlined from ‘void std::default_delete<_Tp>::operator()(_Tp*) const [with _Tp = pcl::PointCloud<pcl::PointXYZ>]’ at /usr/include/c++/13/bits/unique_ptr.h:99:2,
    inlined from ‘std::unique_ptr<_Tp, _Dp>::~unique_ptr() [with _Tp = pcl::PointCloud<pcl::PointXYZ>; _Dp = std::default_delete<pcl::PointCloud<pcl::PointXYZ> >]’ at /usr/include/c++/13/bits/unique_ptr.h:404:17,
    inlined from ‘std::enable_if_t<(typename rclcpp::TypeAdapter<MessageT>::is_specialized::value && std::is_same<T, typename rclcpp::TypeAdapter<MessageT>::custom_type>::value)> rclcpp::Publisher<MessageT, AllocatorT>::publish(const T&) [with T = pcl::PointCloud<pcl::PointXYZ>; MessageT = rclcpp::TypeAdapter<pcl::PointCloud<pcl::PointXYZ>, sensor_msgs::msg::PointCloud2_<std::allocator<void> >, void>; AllocatorT = std::allocator<void>]’ at /opt/ros/jazzy/include/rclcpp/rclcpp/publisher.hpp:390:18,
    inlined from ‘void fsd::FSDGMMMapping::publish_sensor_model(const std::string&)’ at /home/ivo/colcon_ws/src/my_package/my_node.cpp:354:57:
/usr/include/eigen3/Eigen/src/Core/util/Memory.h:203:9: warning: ‘void free(void*)’ called on pointer returned from a mismatched allocation function [-Wmismatched-new-delete]
  203 |     free(ptr);
      |     ~~~~^~~~~
In file included from /usr/include/x86_64-linux-gnu/c++/13/bits/c++allocator.h:33,
                 from /usr/include/c++/13/bits/allocator.h:46,
                 from /usr/include/c++/13/string:43,
                 from /usr/include/c++/13/bits/locale_classes.h:40,
                 from /usr/include/c++/13/bits/ios_base.h:41,
                 from /usr/include/c++/13/ios:44,
                 from /usr/include/c++/13/istream:40,
                 from /usr/include/c++/13/sstream:40,
                 from /usr/include/c++/13/chrono:45,
                 from /usr/include/pcl-1.14/pcl/common/time.h:41,
                 from /home/ivo/colcon_ws/src/my_package/my_node.cpp:1:
In member function ‘_Tp* std::__new_allocator<_Tp>::allocate(size_type, const void*) [with _Tp = pcl::PointCloud<pcl::PointXYZ>]’,
    inlined from ‘constexpr _Tp* std::allocator< <template-parameter-1-1> >::allocate(std::size_t) [with _Tp = pcl::PointCloud<pcl::PointXYZ>]’ at /usr/include/c++/13/bits/allocator.h:198:40,
    inlined from ‘static constexpr _Tp* std::allocator_traits<std::allocator<_CharT> >::allocate(allocator_type&, size_type) [with _Tp = pcl::PointCloud<pcl::PointXYZ>]’ at /usr/include/c++/13/bits/alloc_traits.h:482:28,
    inlined from ‘std::unique_ptr<typename rclcpp::TypeAdapter<MessageT>::custom_type, typename std::conditional<std::is_same<typename std::allocator_traits<typename std::allocator_traits<_Allocator>::rebind_traits<typename rclcpp::TypeAdapter<MessageT, void, void>::custom_type>::allocator_type>::rebind_alloc<typename rclcpp::TypeAdapter<MessageT, void, void>::custom_type>, std::allocator<typename rclcpp::TypeAdapter<MessageT>::custom_type> >::value, std::default_delete<typename rclcpp::TypeAdapter<MessageT>::custom_type>, rclcpp::allocator::AllocatorDeleter<typename std::allocator_traits<_Allocator>::rebind_traits<typename rclcpp::TypeAdapter<MessageT, void, void>::custom_type>::allocator_type> >::type> rclcpp::Publisher<MessageT, AllocatorT>::duplicate_type_adapt_message_as_unique_ptr(const PublishedType&) [with MessageT = rclcpp::TypeAdapter<pcl::PointCloud<pcl::PointXYZ>, sensor_msgs::msg::PointCloud2_<std::allocator<void> >, void>; AllocatorT = std::allocator<void>]’ at /opt/ros/jazzy/include/rclcpp/rclcpp/publisher.hpp:603:54,
    inlined from ‘std::enable_if_t<(typename rclcpp::TypeAdapter<MessageT>::is_specialized::value && std::is_same<T, typename rclcpp::TypeAdapter<MessageT>::custom_type>::value)> rclcpp::Publisher<MessageT, AllocatorT>::publish(const T&) [with T = pcl::PointCloud<pcl::PointXYZ>; MessageT = rclcpp::TypeAdapter<pcl::PointCloud<pcl::PointXYZ>, sensor_msgs::msg::PointCloud2_<std::allocator<void> >, void>; AllocatorT = std::allocator<void>]’ at /opt/ros/jazzy/include/rclcpp/rclcpp/publisher.hpp:389:10,

Edit: This issue is only present when using the ROS-package pcl_ros that pulls in the dependency on PCL. This is because pcl_ros still specifies C++14 standard (causing -D EIGEN_HAS_CXX17_OVERALIGN=0 to be present in the compiler commandline). Since C++17, the aligned allocators that PCL uses were standartized and therefore the pcl::PointCloud does not have custom new/delete operators anymore.
This means, if you would depend directly on a recent version of PCL instead of using pcl_ros, you will not observe this problem.

Expected behavior

rclcpp should use matching new/delete operators to prevent heap corruptions

Actual behavior

New/delete mismatch detected at compile time in form of a warning

Additional information

Consider a custom type that has overloaded new and delete operators, i.e. the commonly used pcl::PointCloud. We can publish this type by using type adapters, i.e. as a sensor_msgs/PointCloud2. If we publish this type by value however, a new/delete mismatch occurs: global operator new is used together with the custom operator delete.
This occurs only if we publish by value, if we publish by std::unique_ptr, this issue is not present.

Root cause

This is due to the following publish-overload that first copies the given message:
https://github.com/ros2/rclcpp/blob/rolling/rclcpp/include/rclcpp/publisher.hpp#L357

The root cause of not using the custom operator new is that rclcpp allows for custom allocators, and how they work. If the message is published by value, it is first copied using std::allocator_traits<A>:: allocate/construct in the following function, which always uses the global placement new operator (cppreference](https://en.cppreference.com/w/cpp/memory/allocator/construct.html)):

https://github.com/ros2/rclcpp/blob/rolling/rclcpp/include/rclcpp/publisher.hpp#L575

Proposed solution

Add a static_assert in the publish(const T&) overload that asserts the type has no custom operator new. Suggest the user should use the publish(std::unique_ptr<T>) overload instead.

Metadata

Metadata

Assignees

Labels

backlogbugSomething isn't working

Type

No type

Projects

No projects

Milestone

No milestone

Relationships

None yet

Development

No branches or pull requests

Issue actions