@@ -44,17 +44,26 @@ void callback(const sensor_msgs::PointCloud2ConstPtr& input)
4444{
4545 // Convert the sensor_msgs/PointCloud2 data to pcl/PointCloud
4646 pcl::PCLPointCloud2::Ptr cloud_ptr (new pcl::PCLPointCloud2);
47+ pcl::PCLPointCloud2::Ptr cloud_filtered_ptr_z (new pcl::PCLPointCloud2);
4748 pcl::PCLPointCloud2::Ptr cloud_filtered_ptr (new pcl::PCLPointCloud2);
4849 pcl_conversions::toPCL (*input, *cloud_ptr);
4950 if (debug) std::cerr << " PointCloud before filtering: " << cloud_ptr->width << " " << cloud_ptr->height << " data points." << std::endl;
5051
5152 // Filter the points in z-axis
53+ pcl::PassThrough<pcl::PCLPointCloud2> pass_z;
54+ pass_z.setInputCloud (cloud_ptr);
55+ pass_z.setFilterFieldName (" z" );
56+ pass_z.setFilterLimits (0.0 , 0.9 );
57+ pass_z.filter (*cloud_filtered_ptr_z);
58+ if (debug) std::cerr << " PointCloud after filtering: " << cloud_filtered_ptr_z->width << " " << cloud_filtered_ptr->height << " data points." << std::endl;
59+
60+ // Filter the points in y-axis
5261 pcl::PassThrough<pcl::PCLPointCloud2> pass;
53- pass.setInputCloud (cloud_ptr );
54- pass.setFilterFieldName (" z " );
55- pass.setFilterLimits (0.0 , 0.9 );
62+ pass.setInputCloud (cloud_filtered_ptr_z );
63+ pass.setFilterFieldName (" x " );
64+ pass.setFilterLimits (- 0.2 , 0.2 );
5665 pass.filter (*cloud_filtered_ptr);
57- if (debug) std::cerr << " PointCloud after filtering: " << cloud_filtered_ptr->width << " " << cloud_filtered_ptr->height << " data points." << std::endl;
66+ if (debug) std::cerr << " PointCloud after filtering in x-axis : " << cloud_filtered_ptr->width << " " << cloud_filtered_ptr->height << " data points." << std::endl;
5867
5968 // Downsample the points
6069 pcl::PCLPointCloud2::Ptr voxel_ptr (new pcl::PCLPointCloud2);
0 commit comments