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 #ifndef PCL_FILTERS_DON_IMPL_H_
00038 #define PCL_FILTERS_DON_IMPL_H_
00039 
00040 #include <pcl/features/don.h>
00041 
00043 template <typename PointInT, typename PointNT, typename PointOutT> bool
00044 pcl::DifferenceOfNormalsEstimation<PointInT, PointNT, PointOutT>::initCompute ()
00045 {
00046   
00047   if (!input_normals_small_)
00048   {
00049     PCL_ERROR ("[pcl::%s::initCompute] No input dataset containing small support radius normals was given!\n", getClassName().c_str ());
00050     Feature<PointInT, PointOutT>::deinitCompute();
00051     return (false);
00052   }
00053 
00054   if (!input_normals_large_)
00055   {
00056     PCL_ERROR ("[pcl::%s::initCompute] No input dataset containing large support radius normals was given!\n", getClassName().c_str ());
00057     Feature<PointInT, PointOutT>::deinitCompute();
00058     return (false);
00059   }
00060 
00061   
00062   if (input_normals_small_->points.size () != input_->points.size ())
00063   {
00064     PCL_ERROR ("[pcl::%s::initCompute] ", getClassName().c_str ());
00065     PCL_ERROR ("The number of points in the input dataset differs from ");
00066     PCL_ERROR ("the number of points in the dataset containing the small support radius normals!\n");
00067     Feature<PointInT, PointOutT>::deinitCompute ();
00068     return (false);
00069   }
00070 
00071   if (input_normals_large_->points.size () != input_->points.size ())
00072   {
00073     PCL_ERROR ("[pcl::%s::initCompute] ", getClassName().c_str ());
00074     PCL_ERROR ("The number of points in the input dataset differs from ");
00075     PCL_ERROR ("the number of points in the dataset containing the large support radius normals!\n");
00076     Feature<PointInT, PointOutT>::deinitCompute ();
00077     return (false);
00078   }
00079 
00080   return (true);
00081 }
00082 
00084 template <typename PointInT, typename PointNT, typename PointOutT> void
00085 pcl::DifferenceOfNormalsEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut &output)
00086 {
00087   
00088   for (size_t point_id = 0; point_id < input_->points.size (); ++point_id)
00089   {
00090     output.points[point_id].getNormalVector3fMap () =  (input_normals_small_->points[point_id].getNormalVector3fMap ()
00091                 - input_normals_large_->points[point_id].getNormalVector3fMap ()) / 2.0;
00092     if(!pcl_isfinite (output.points[point_id].normal_x) ||
00093         !pcl_isfinite (output.points[point_id].normal_y) ||
00094         !pcl_isfinite (output.points[point_id].normal_z)){
00095       output.points[point_id].getNormalVector3fMap () = Eigen::Vector3f(0,0,0);
00096     }
00097     output.points[point_id].curvature = output.points[point_id].getNormalVector3fMap ().norm();
00098   }
00099 }
00100 
00101 
00102 #define PCL_INSTANTIATE_DifferenceOfNormalsEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::DifferenceOfNormalsEstimation<T,NT,OutT>;
00103 
00104 #endif // PCL_FILTERS_DON_H_