Skip to content

Commit

Permalink
Avoid copying data in fromROSMsg with PCL >= 1.13.1 (#402)
Browse files Browse the repository at this point in the history
mvieth authored Feb 14, 2023

Verified

This commit was created on GitHub.com and signed with GitHub’s verified signature. The key has expired.
1 parent de09161 commit 1868f51
Showing 1 changed file with 7 additions and 0 deletions.
7 changes: 7 additions & 0 deletions pcl_conversions/include/pcl_conversions/pcl_conversions.h
Original file line number Diff line number Diff line change
@@ -568,8 +568,15 @@ namespace pcl {
void fromROSMsg(const sensor_msgs::msg::PointCloud2 &cloud, pcl::PointCloud<T> &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<T> (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<typename T>

0 comments on commit 1868f51

Please sign in to comment.