Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 #ifndef PCL_SEGMENTATION_IMPL_SEGMENT_DIFFERENCES_H_
00039 #define PCL_SEGMENTATION_IMPL_SEGMENT_DIFFERENCES_H_
00040 
00041 #include <pcl/segmentation/segment_differences.h>
00042 #include <pcl/common/concatenate.h>
00043 
00045 template <typename PointT> void
00046 pcl::getPointCloudDifference (
00047     const pcl::PointCloud<PointT> &src, 
00048     const pcl::PointCloud<PointT> &, 
00049     double threshold, const boost::shared_ptr<pcl::search::Search<PointT> > &tree,
00050     pcl::PointCloud<PointT> &output)
00051 {
00052   
00053   std::vector<int> nn_indices (1);
00054   std::vector<float> nn_distances (1);
00055 
00056   
00057   std::vector<int> src_indices;
00058 
00059   
00060   for (int i = 0; i < static_cast<int> (src.points.size ()); ++i)
00061   {
00062     if (!isFinite (src.points[i]))
00063       continue;
00064     
00065     if (!tree->nearestKSearch (src.points[i], 1, nn_indices, nn_distances))
00066     {
00067       PCL_WARN ("No neighbor found for point %zu (%f %f %f)!\n", i, src.points[i].x, src.points[i].y, src.points[i].z);
00068       continue;
00069     }
00070 
00071     if (nn_distances[0] > threshold)
00072       src_indices.push_back (i);
00073   }
00074  
00075   
00076   output.points.resize (src_indices.size ());
00077   output.header   = src.header;
00078   output.width    = static_cast<uint32_t> (src_indices.size ());
00079   output.height   = 1;
00080   
00081     output.is_dense = true;
00082   
00083     
00084     
00085     
00086 
00087   
00088   typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00089   
00090   for (size_t i = 0; i < src_indices.size (); ++i)
00091     
00092     pcl::for_each_type <FieldList> (NdConcatenateFunctor <PointT, PointT> (src.points[src_indices[i]], output.points[i]));
00093 }
00094 
00098 template <typename PointT> void 
00099 pcl::SegmentDifferences<PointT>::segment (PointCloud &output)
00100 {
00101   output.header = input_->header;
00102 
00103   if (!initCompute ()) 
00104   {
00105     output.width = output.height = 0;
00106     output.points.clear ();
00107     return;
00108   }
00109 
00110   
00111   if (target_->points.empty ())
00112   {
00113     output = *input_;
00114     return;
00115   }
00116 
00117   
00118   if (!tree_)
00119   {
00120     if (target_->isOrganized ())
00121       tree_.reset (new pcl::search::OrganizedNeighbor<PointT> ());
00122     else
00123       tree_.reset (new pcl::search::KdTree<PointT> (false));
00124   }
00125   
00126   tree_->setInputCloud (target_);
00127 
00128   getPointCloudDifference (*input_, *target_, distance_threshold_, tree_, output);
00129 
00130   deinitCompute ();
00131 }
00132 
00133 #define PCL_INSTANTIATE_SegmentDifferences(T) template class PCL_EXPORTS pcl::SegmentDifferences<T>;
00134 #define PCL_INSTANTIATE_getPointCloudDifference(T) template PCL_EXPORTS void pcl::getPointCloudDifference<T>(const pcl::PointCloud<T> &, const pcl::PointCloud<T> &, double, const boost::shared_ptr<pcl::search::Search<T> > &, pcl::PointCloud<T> &);
00135 
00136 #endif        // PCL_SEGMENTATION_IMPL_SEGMENT_DIFFERENCES_H_
00137