From 77424943e17202440203a63f232eed84eea007c9 Mon Sep 17 00:00:00 2001 From: Unknown Date: Thu, 28 Jun 2018 18:29:58 +0200 Subject: [PATCH] Extraction de l'objet (outliners) --- my_pcl_tutorial/src/plannar_segmentation.cpp | 21 ++++++++++++++++---- 1 file changed, 17 insertions(+), 4 deletions(-) diff --git a/my_pcl_tutorial/src/plannar_segmentation.cpp b/my_pcl_tutorial/src/plannar_segmentation.cpp index 32f62cd..4a162c3 100644 --- a/my_pcl_tutorial/src/plannar_segmentation.cpp +++ b/my_pcl_tutorial/src/plannar_segmentation.cpp @@ -9,6 +9,7 @@ #include #include +#include ros::Publisher pub; @@ -44,10 +45,22 @@ cloud_cb (const sensor_msgs::PointCloud2ConstPtr& input) //Créations de l'output pcl::PointCloud::Ptr pcl_output(new pcl::PointCloud); - for (size_t i = 0; i < inliers->indices.size (); ++i) - { - pcl_output->points.push_back( cloud->points[inliers->indices[i]]); - } + //Extraction du plan (inliners) + // for (size_t i = 0; i < inliers->indices.size (); ++i) + // { + // pcl_output->points.push_back( cloud->points[inliers->indices[i]]); + + // } + + //Extraction de l'objet (outliners) + //Attention bruit ! + pcl::ExtractIndices extract; + extract.setInputCloud(cloud); + extract.setIndices(inliers); + extract.setNegative(true); + extract.filter(*pcl_output); + + pcl::toPCLPointCloud2(*pcl_output,pcl_pc2); pcl_conversions::fromPCL(pcl_pc2, output);