Skip to content

Commit

Permalink
set point cloud info for initialization
Browse files Browse the repository at this point in the history
  • Loading branch information
gitai-dev01 authored and knorth55 committed Dec 4, 2024
1 parent 3cbed5e commit 1aaa3b0
Showing 1 changed file with 13 additions and 3 deletions.
16 changes: 13 additions & 3 deletions jsk_pcl_ros/src/organized_statistical_outlier_removal_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -273,9 +273,19 @@ namespace jsk_pcl_ros
pcl::PCLPointCloud2::Ptr pcl_cloud (new pcl::PCLPointCloud2);
pcl::PCLPointCloud2::Ptr pcl_cloud_filtered (new pcl::PCLPointCloud2);
pcl_conversions::toPCL(*msg, *pcl_cloud);
// fill nan in pcl_cloud_filtered
pcl_cloud_filtered->data.resize(pcl_cloud->data.size());
std::fill(pcl_cloud_filtered->data.begin(), pcl_cloud_filtered->data.end(), 0);

// fill data
pcl_cloud_filtered->fields = pcl_cloud->fields;
pcl_cloud_filtered->is_bigendian = pcl_cloud->is_bigendian;
pcl_cloud_filtered->point_step = pcl_cloud->point_step;
pcl_cloud_filtered->is_dense = !keep_organized;
if (keep_organized)
{
// fill nan in pcl_cloud_filtered
pcl_cloud_filtered->data.resize(pcl_cloud->data.size());
std::fill(pcl_cloud_filtered->data.begin(), pcl_cloud_filtered->data.end(), 0);
}


pcl::ExtractIndices<pcl::PCLPointCloud2> ex;
ex.setInputCloud(pcl_cloud);
Expand Down

0 comments on commit 1aaa3b0

Please sign in to comment.