Avoid redundant boost::make_shared copy in pcl_ros::Publisher<PointT> (#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.
This commit is contained in:
Aditya Ardiya 2022-11-19 03:39:32 +09:00 committed by GitHub
parent 389297dfad
commit 7c6a2a5a38
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23

View File

@ -114,9 +114,9 @@ public:
publish(const pcl::PointCloud<PointT> & point_cloud) const
{
// Fill point cloud binary data
sensor_msgs::PointCloud2 msg;
pcl::toROSMsg(point_cloud, msg);
pub_.publish(boost::make_shared<const sensor_msgs::PointCloud2>(msg));
sensor_msgs::PointCloud2::Ptr msg_ptr(new sensor_msgs::PointCloud2);
pcl::toROSMsg(point_cloud, *msg_ptr);
pub_.publish(msg_ptr);
}
};