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
00039
00040 #ifndef PCL_GAUSSIAN_KERNEL
00041 #define PCL_GAUSSIAN_KERNEL
00042
00043 #include <sstream>
00044 #include <pcl/common/eigen.h>
00045 #include <pcl/point_cloud.h>
00046 #include <boost/function.hpp>
00047
00048 namespace pcl
00049 {
00057 class PCL_EXPORTS GaussianKernel
00058 {
00059 public:
00060
00061 GaussianKernel () {}
00062
00063 static const unsigned MAX_KERNEL_WIDTH = 71;
00071 void
00072 compute (float sigma,
00073 Eigen::VectorXf &kernel,
00074 unsigned kernel_width = MAX_KERNEL_WIDTH) const;
00075
00084 void
00085 compute (float sigma,
00086 Eigen::VectorXf &kernel,
00087 Eigen::VectorXf &derivative,
00088 unsigned kernel_width = MAX_KERNEL_WIDTH) const;
00089
00097 void
00098 convolveRows (const pcl::PointCloud<float> &input,
00099 const Eigen::VectorXf &kernel,
00100 pcl::PointCloud<float> &output) const;
00101
00110 template <typename PointT> void
00111 convolveRows (const pcl::PointCloud<PointT> &input,
00112 boost::function <float (const PointT& p)> field_accessor,
00113 const Eigen::VectorXf &kernel,
00114 pcl::PointCloud<float> &output) const;
00115
00123 void
00124 convolveCols (const pcl::PointCloud<float> &input,
00125 const Eigen::VectorXf &kernel,
00126 pcl::PointCloud<float> &output) const;
00127
00136 template <typename PointT> void
00137 convolveCols (const pcl::PointCloud<PointT> &input,
00138 boost::function <float (const PointT& p)> field_accessor,
00139 const Eigen::VectorXf &kernel,
00140 pcl::PointCloud<float> &output) const;
00141
00150 inline void
00151 convolve (const pcl::PointCloud<float> &input,
00152 const Eigen::VectorXf &horiz_kernel,
00153 const Eigen::VectorXf &vert_kernel,
00154 pcl::PointCloud<float> &output) const
00155 {
00156 std::cout << ">>> convolve cpp" << std::endl;
00157 pcl::PointCloud<float> tmp (input.width, input.height) ;
00158 convolveRows (input, horiz_kernel, tmp);
00159 convolveCols (tmp, vert_kernel, output);
00160 std::cout << "<<< convolve cpp" << std::endl;
00161 }
00162
00172 template <typename PointT> inline void
00173 convolve (const pcl::PointCloud<PointT> &input,
00174 boost::function <float (const PointT& p)> field_accessor,
00175 const Eigen::VectorXf &horiz_kernel,
00176 const Eigen::VectorXf &vert_kernel,
00177 pcl::PointCloud<float> &output) const
00178 {
00179 std::cout << ">>> convolve hpp" << std::endl;
00180 pcl::PointCloud<float> tmp (input.width, input.height);
00181 convolveRows<PointT>(input, field_accessor, horiz_kernel, tmp);
00182 convolveCols(tmp, vert_kernel, output);
00183 std::cout << "<<< convolve hpp" << std::endl;
00184 }
00185
00196 inline void
00197 computeGradients (const pcl::PointCloud<float> &input,
00198 const Eigen::VectorXf &gaussian_kernel,
00199 const Eigen::VectorXf &gaussian_kernel_derivative,
00200 pcl::PointCloud<float> &grad_x,
00201 pcl::PointCloud<float> &grad_y) const
00202 {
00203 convolve (input, gaussian_kernel_derivative, gaussian_kernel, grad_x);
00204 convolve (input, gaussian_kernel, gaussian_kernel_derivative, grad_y);
00205 }
00206
00218 template <typename PointT> inline void
00219 computeGradients (const pcl::PointCloud<PointT> &input,
00220 boost::function <float (const PointT& p)> field_accessor,
00221 const Eigen::VectorXf &gaussian_kernel,
00222 const Eigen::VectorXf &gaussian_kernel_derivative,
00223 pcl::PointCloud<float> &grad_x,
00224 pcl::PointCloud<float> &grad_y) const
00225 {
00226 convolve<PointT> (input, field_accessor, gaussian_kernel_derivative, gaussian_kernel, grad_x);
00227 convolve<PointT> (input, field_accessor, gaussian_kernel, gaussian_kernel_derivative, grad_y);
00228 }
00229
00237 inline void
00238 smooth (const pcl::PointCloud<float> &input,
00239 const Eigen::VectorXf &gaussian_kernel,
00240 pcl::PointCloud<float> &output) const
00241 {
00242 convolve (input, gaussian_kernel, gaussian_kernel, output);
00243 }
00244
00253 template <typename PointT> inline void
00254 smooth (const pcl::PointCloud<PointT> &input,
00255 boost::function <float (const PointT& p)> field_accessor,
00256 const Eigen::VectorXf &gaussian_kernel,
00257 pcl::PointCloud<float> &output) const
00258 {
00259 convolve<PointT> (input, field_accessor, gaussian_kernel, gaussian_kernel, output);
00260 }
00261 };
00262 }
00263
00264 #include <pcl/common/impl/gaussian.hpp>
00265
00266 #endif // PCL_GAUSSIAN_KERNEL