Go to the documentation of this file.00001 #ifndef SEGMENTATION_H
00002 #define SEGMENTATION_H
00003 
00004 #include "typedefs.h"
00005 
00006 #include <pcl/ModelCoefficients.h>
00007 #include <pcl/sample_consensus/method_types.h>
00008 #include <pcl/sample_consensus/model_types.h>
00009 #include <pcl/segmentation/sac_segmentation.h>
00010 #include <pcl/filters/extract_indices.h>
00011 #include <pcl/segmentation/extract_clusters.h>
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 pcl::ModelCoefficients::Ptr
00027 fitPlane (const PointCloudPtr & input, float distance_threshold, float max_iterations)
00028 {
00029   
00030   pcl::SACSegmentation<PointT> seg;
00031   seg.setOptimizeCoefficients (true);
00032   seg.setModelType (pcl::SACMODEL_PLANE);
00033   seg.setMethodType (pcl::SAC_RANSAC);
00034   seg.setDistanceThreshold (distance_threshold);
00035   seg.setMaxIterations (max_iterations);
00036 
00037   seg.setInputCloud (input);
00038   pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients ());
00039   pcl::PointIndices::Ptr inliers (new pcl::PointIndices ());
00040   seg.segment (*inliers, *coefficients);  
00041 
00042   return (coefficients);
00043 }
00044 
00045 
00046 
00047 
00048 
00049 
00050 
00051 
00052 
00053 
00054 
00055 
00056 PointCloudPtr
00057 findAndSubtractPlane (const PointCloudPtr & input, float distance_threshold, float max_iterations)
00058 {
00059   
00060   pcl::SACSegmentation<PointT> seg;
00061   seg.setOptimizeCoefficients (false);
00062   seg.setModelType (pcl::SACMODEL_PLANE);
00063   seg.setMethodType (pcl::SAC_RANSAC);
00064   seg.setDistanceThreshold (distance_threshold);
00065   seg.setMaxIterations (max_iterations);
00066   seg.setInputCloud (input);
00067   pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients ());
00068   pcl::PointIndices::Ptr inliers (new pcl::PointIndices ());
00069   seg.segment (*inliers, *coefficients);  
00070 
00071   
00072   pcl::ExtractIndices<PointT> extract;
00073   extract.setInputCloud (input);
00074   extract.setIndices (inliers);
00075   extract.setNegative (true);
00076   PointCloudPtr output (new PointCloud);
00077   extract.filter (*output);
00078 
00079   return (output);
00080 }
00081 
00082 
00083 
00084 
00085 
00086 
00087 
00088 
00089 
00090 
00091 
00092 void
00093 clusterObjects (const PointCloudPtr & input, 
00094                 float cluster_tolerance, int min_cluster_size, int max_cluster_size,
00095                 std::vector<pcl::PointIndices> & cluster_indices_out)
00096 {  
00097   pcl::EuclideanClusterExtraction<PointT> ec;
00098   ec.setClusterTolerance (cluster_tolerance);
00099   ec.setMinClusterSize (min_cluster_size);
00100   ec.setMaxClusterSize (max_cluster_size);
00101 
00102   ec.setInputCloud (input);
00103   ec.extract (cluster_indices_out);
00104 }
00105 
00106 #endif