Skip to content

Commit c699b35

Browse files
gitai-dev01knorth55
authored andcommitted
set point cloud info for initialization
1 parent 3cbed5e commit c699b35

File tree

1 file changed

+17
-3
lines changed

1 file changed

+17
-3
lines changed

jsk_pcl_ros/src/organized_statistical_outlier_removal_nodelet.cpp

+17-3
Original file line numberDiff line numberDiff line change
@@ -273,9 +273,23 @@ namespace jsk_pcl_ros
273273
pcl::PCLPointCloud2::Ptr pcl_cloud (new pcl::PCLPointCloud2);
274274
pcl::PCLPointCloud2::Ptr pcl_cloud_filtered (new pcl::PCLPointCloud2);
275275
pcl_conversions::toPCL(*msg, *pcl_cloud);
276-
// fill nan in pcl_cloud_filtered
277-
pcl_cloud_filtered->data.resize(pcl_cloud->data.size());
278-
std::fill(pcl_cloud_filtered->data.begin(), pcl_cloud_filtered->data.end(), 0);
276+
277+
// fill data
278+
pcl_cloud_filtered->fields = pcl_cloud->fields;
279+
pcl_cloud_filtered->is_bigendian = pcl_cloud->is_bigendian;
280+
pcl_cloud_filtered->point_step = pcl_cloud->point_step;
281+
pcl_cloud_filtered->is_dense = !keep_organized;
282+
if (keep_organized)
283+
{
284+
// fill data
285+
pcl_cloud_filtered->height = pcl_cloud->height;
286+
pcl_cloud_filtered->width = pcl_cloud->width;
287+
pcl_cloud_filtered->row_step = pcl_cloud->row_step;
288+
// fill nan in pcl_cloud_filtered
289+
pcl_cloud_filtered->data.resize(pcl_cloud->data.size());
290+
std::fill(pcl_cloud_filtered->data.begin(), pcl_cloud_filtered->data.end(), 0);
291+
}
292+
279293

280294
pcl::ExtractIndices<pcl::PCLPointCloud2> ex;
281295
ex.setInputCloud(pcl_cloud);

0 commit comments

Comments
 (0)