diff --git a/pcl_conversions/include/pcl_conversions/pcl_conversions.h b/pcl_conversions/include/pcl_conversions/pcl_conversions.h index 5ac0a41a8..635ee4cd8 100644 --- a/pcl_conversions/include/pcl_conversions/pcl_conversions.h +++ b/pcl_conversions/include/pcl_conversions/pcl_conversions.h @@ -561,8 +561,15 @@ namespace pcl { void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud &pcl_cloud) { pcl::PCLPointCloud2 pcl_pc2; +#if PCL_VERSION_COMPARE(>=, 1, 13, 1) + pcl_conversions::copyPointCloud2MetaData(cloud, pcl_pc2); // Like pcl_conversions::toPCL, but does not copy the binary data + pcl::MsgFieldMap field_map; + pcl::createMapping (pcl_pc2.fields, field_map); + pcl::fromPCLPointCloud2(pcl_pc2, pcl_cloud, field_map, &cloud.data[0]); +#else pcl_conversions::toPCL(cloud, pcl_pc2); pcl::fromPCLPointCloud2(pcl_pc2, pcl_cloud); +#endif } template