PCL passthrough filter and data types are not working..

asked 2020-05-16 04:57:12 -0500

Kim3957 gravatar image

Hi all, I m currently making human tracking program using velodyne sensor.

However, I m missing something between PCL pointcloud and ROS message types

I have tried many combination of data types of pointcloud and ptr.

when I try to compie my code, it gives me error like this

home/p3at/catkin_ws/src/my_pcl_tutorial/src/velodyne_Euclid.cpp:44:28: error: no matching function for call to ‘pcl::PassThrough<pcl::PointXYZ>::setInputCloud(pcl::PointCloud<pcl::PointXYZ>&)’
   pass.setInputCloud (cloud);

I'm completely stucked..

I maybe something missing around

      // Convert the sensor_msgs/PointCloud2 data to pcl/PointCloud
  pcl::PointCloud<pcl::PointXYZ> cloud;
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloudv (new pcl::PointCloud<pcl::PointXYZ>);
  pcl::fromROSMsg (*input, cloud);

  //remove bottom                                          
  pcl::PassThrough<pcl::PointXYZ> pass;
  pass.setInputCloud (cloud);
  pass.setFilterFieldName ("z");
  pass.setFilterLimits (0.10, 2.0);
  //pass.setFilterLimitsNegative (true);
  pass.filter (cloudv);

Please help

#include <ros/ros.h>
#include <iostream>
#include <pcl/io/pcd_io.h>
// PCL specific includes
#include <sensor_msgs/PointCloud2.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/ModelCoefficients.h>
#include <pcl/io/pcd_io.h>
#include <pcl/filters/extract_indices.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/features/normal_3d.h>
#include <pcl/kdtree/kdtree.h>
#include <pcl/sample_consensus/method_types.h>
#include <pcl/sample_consensus/model_types.h>
#include <pcl/segmentation/sac_segmentation.h>
#include <pcl/segmentation/extract_clusters.h>
#include <nodelet/nodelet.h>
#include <pluginlib/class_list_macros.h>
#include <pcl/filters/passthrough.h>
double downsample_resolution;
double setClusterTolerance;
ros::Publisher pub;
typedef pcl::PointXYZ PointT;

void
initialize_params(){
  //  nh = getNodeHandle();
  // prv_nh = getPrivateNodeHandle();
  // downsample_resolution = prv_nh.param<double>("downsample_resolution",0.1);
}

void
cloud_cb (const sensor_msgs::PointCloud2ConstPtr& input)
{
  // Convert the sensor_msgs/PointCloud2 data to pcl/PointCloud
  pcl::PointCloud<pcl::PointXYZ> cloud;
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloudv (new pcl::PointCloud<pcl::PointXYZ>);
  pcl::fromROSMsg (*input, cloud);

  //remove bottom                                          
  pcl::PassThrough<pcl::PointXYZ> pass;
  pass.setInputCloud (cloud);
  pass.setFilterFieldName ("z");
  pass.setFilterLimits (0.10, 2.0);
  //pass.setFilterLimitsNegative (true);
  pass.filter (cloudv);                 

  // Data containers used
  // Create the filtering object: downsample the dataset using a leaf size of 1cm
  pcl::VoxelGrid<pcl::PointXYZ> vg;
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered (new pcl::PointCloud<pcl::PointXYZ>);

  //initialize_params();
  vg.setInputCloud (cloudv.makeShared());
  vg.setLeafSize (downsample_resolution, downsample_resolution, downsample_resolution);
  vg.filter (*cloud_filtered);

  //Creating the KdTree object for the search method of the extraction
  pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
  tree->setInputCloud (cloud_filtered);
  std::vector<pcl::PointIndices> cluster_indices;
  pcl::EuclideanClusterExtraction<pcl::PointXYZ> ec;

  ec.setClusterTolerance (setClusterTolerance); // 2cm
  ec.setMinClusterSize (10);
  ec.setMaxClusterSize (500);
  ec.setSearchMethod (tree);
  ec.setInputCloud (cloud_filtered);
  ec.extract (cluster_indices);


  std::cout << "Number of clusters is equal to " << cluster_indices.size () << std::endl;

  pcl::PointCloud<pcl::PointXYZI> TotalCloud; 
  int j = 0;
  for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it)
  {
    for (std::vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); ++pit)
    {
        pcl::PointXYZ pt = cloud_filtered->points[*pit];
            pcl::PointXYZI pt2;
            pt2.x = pt.x, pt2.y = pt.y, pt2.z = pt.z;
            pt2.intensity = (float)(j + 1);

            TotalCloud.push_back(pt2);
    }
    j++;
  }

    // Convert To ROS data type 
  pcl::PCLPointCloud2 cloud_p;
  pcl::toPCLPointCloud2(TotalCloud, cloud_p);

  sensor_msgs::PointCloud2 output; 
  pcl_conversions::fromPCL(cloud_p, output);
  output.header.frame_id = "velodyne";  
  pub.publish(output); 

  ROS_INFO ...
(more)
edit retag flag offensive close merge delete

Comments

Having same problem on ROS Melodic and pcl_ros 1.8.1

juanlu gravatar image juanlu  ( 2023-04-21 03:17:22 -0500 )edit