edge_estimation_2d.h
Go to the documentation of this file.
00001 
00063 #ifndef __EDGE_ESTIMATION_2D_H__
00064 #define __EDGE_ESTIMATION_2D_H__
00065 
00066 #include <pcl/point_cloud.h>
00067 #include <pcl/point_types.h>
00068 #include <cv.h>
00069 
00070 namespace cob_3d_features
00071 {
00072   template <typename PointInT, typename PointOutT> 
00073   class EdgeEstimation2D
00074   {
00075   public:
00076     EdgeEstimation2D () { };
00077     ~EdgeEstimation2D () { };
00078 
00079     typedef pcl::PointCloud<PointInT> PointCloudIn;
00080     typedef boost::shared_ptr<PointCloudIn> PointCloudInPtr;
00081     typedef boost::shared_ptr<const PointCloudIn> PointCloudInConstPtr;
00082     typedef pcl::PointCloud<PointOutT> PointCloudOut;
00083 
00089     void
00090     setInputCloud (const PointCloudInConstPtr &cloud)
00091     {
00092       input_ = cloud;
00093     }
00094 
00100     void
00101     getColorImage(cv::Mat& color_image);
00102 
00110     void
00111     getRangeImage(cv::Mat& range_image, const float &th_min, const float &th_max);
00118     void
00119     extractEdgesSobel(cv::Mat &input_image, cv::Mat& sobel_image);
00126     void
00127     extractEdgesLaPlace(cv::Mat &input_image, cv::Mat& laplace_image);
00133     void
00134     computeEdges(PointCloudOut &output);
00142     void
00143     computeEdges(cv::Mat &sobel_out, cv::Mat &laplace_out, cv::Mat &combined_out);
00149     void
00150     computeEdgesFromRange(PointCloudOut &output);
00158     void
00159     computeEdgesFromRange(cv::Mat &sobel_out, cv::Mat &laplace_out, cv::Mat &combined_out);
00160 
00161   protected:
00162     PointCloudInConstPtr input_;
00163 
00164   };
00165 }
00166 
00167 #endif //__EDGE_ESTIMATION_2D_H__


cob_3d_features
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:02:26