ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

PCL outliers removal

asked 2014-03-19 05:12:45 -0500

chao gravatar image

Hi,

I am using hydro on ubuntu 12.04. I am trying to remove the point cloud outliers, but I can't get it right, can anyone help me take a look please? Thank you.

#include <ros/ros.h>
#include <iostream>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl/filters/statistical_outlier_removal.h>
#include <pcl_conversions/pcl_conversions.h>
#include <sensor_msgs/PointCloud2.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>


ros::Publisher pub;

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

  pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor;
  sor.setInputCloud (cloud);
  sor.setMeanK (50);
  sor.setStddevMulThresh (1.0);
  sor.filter (cloud_filtered);

  pcl::PCLPointCloud2 cloud_filtered2;
  pcl::toROSMsg (cloud_filtered, cloud_filtered2);

  // Publish the dataSize 
  pub.publish (cloud_filtered2);
}

int
main (int argc, char** argv)
{
  // Initialize ROS
  ros::init (argc, argv, "my_pcl_tutorial");
  ros::NodeHandle nh;

  // Create a ROS subscriber for the input point cloud
  ros::Subscriber sub = nh.subscribe ("/camera/depth_registered/points", 1, cloud_cb);

  // Create a ROS publisher for the output point cloud
  pub = nh.advertise<sensor_msgs::PointCloud2> ("/camera/depth_registered/points_voxel", 1);

  // Spin
  ros::spin ();
}
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2014-03-19 09:05:30 -0500

Try this for your callback:

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

    pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor;
    sor.setInputCloud (cloud);
    sor.setMeanK (50);
    sor.setStddevMulThresh (1.0);
    sor.filter (*cloud_filtered);

    sensor_msgs::PointCloud2::Ptr
        cloud_filtered2(new sensor_msgs::PointCloud2 ());
    pcl::toROSMsg (*cloud_filtered, *cloud_filtered2);

    // Publish the dataSize 
    pub.publish (cloud_filtered2);
}

Does that do what you want?

edit flag offensive delete link more

Comments

yes, it works. Thanks alot :)

chao gravatar image chao  ( 2014-03-20 17:38:40 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2014-03-19 05:12:45 -0500

Seen: 1,767 times

Last updated: Mar 19 '14