From 7c6a2a5a38709fe9aa31acdb443d7490f78f8cfe Mon Sep 17 00:00:00 2001 From: Aditya Ardiya Date: Sat, 19 Nov 2022 03:39:32 +0900 Subject: [PATCH] Avoid redundant boost::make_shared copy in pcl_ros::Publisher (#380) `boost make_shared` is actually making a copy. This PR introduces the `sensor_msgs::PointCloud2` as pointer directly so that it doesn't need a `boost::make_shared` convertsion to pointer anymore. --- pcl_ros/include/pcl_ros/publisher.hpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/pcl_ros/include/pcl_ros/publisher.hpp b/pcl_ros/include/pcl_ros/publisher.hpp index 4de04e8f..9f92745f 100644 --- a/pcl_ros/include/pcl_ros/publisher.hpp +++ b/pcl_ros/include/pcl_ros/publisher.hpp @@ -114,9 +114,9 @@ public: publish(const pcl::PointCloud & point_cloud) const { // Fill point cloud binary data - sensor_msgs::PointCloud2 msg; - pcl::toROSMsg(point_cloud, msg); - pub_.publish(boost::make_shared(msg)); + sensor_msgs::PointCloud2::Ptr msg_ptr(new sensor_msgs::PointCloud2); + pcl::toROSMsg(point_cloud, *msg_ptr); + pub_.publish(msg_ptr); } };