fast_edge_estimation_3d.h
Go to the documentation of this file.
00001 
00063 #ifndef __FAST_EDGE_ESTIMATION_3D_H__
00064 #define __FAST_EDGE_ESTIMATION_3D_H__
00065 
00066 #include "cob_3d_features/organized_features.h"
00067 
00068 namespace cob_3d_features
00069 {
00070   template <typename PointInT, typename PointNT, typename PointOutT>
00071     class FastEdgeEstimation3D : public OrganizedFeatures<PointInT, PointOutT>
00072   {
00073     public:
00074 
00075     using OrganizedFeatures<PointInT, PointOutT>::pixel_search_radius_;
00076     using OrganizedFeatures<PointInT, PointOutT>::mask_;
00077     using OrganizedFeatures<PointInT, PointOutT>::input_;
00078     using OrganizedFeatures<PointInT, PointOutT>::indices_;
00079     using OrganizedFeatures<PointInT, PointOutT>::surface_;
00080     using OrganizedFeatures<PointInT, PointOutT>::feature_name_;
00081 
00082     typedef pcl::PointCloud<PointInT> PointCloudIn;
00083     typedef typename PointCloudIn::Ptr PointCloudInPtr;
00084     typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00085 
00086     typedef pcl::PointCloud<PointNT> PointCloudN;
00087     typedef typename PointCloudN::Ptr PointCloudNPtr;
00088     typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;
00089 
00090     typedef pcl::PointCloud<PointOutT> PointCloudOut;
00091 
00092     public:
00094     FastEdgeEstimation3D ()
00095       {
00096         feature_name_ = "FastEdgeEstimation3D";
00097       };
00098 
00099       inline void
00100         setInputNormals(PointCloudNConstPtr cloud) { normals_ = cloud; }
00101 
00102       void
00103         isEdgePoint (
00104           const pcl::PointCloud<PointInT> &cloud,
00105           const PointInT &q_point,
00106           const std::vector<int> &indices,
00107           const Eigen::Vector3f &n,
00108           float &strength);
00109 
00110     protected:
00111 
00112       void
00113         computeFeature (PointCloudOut &output);
00114 
00115       PointCloudNConstPtr normals_;
00116   };
00117 }
00118 
00119 #endif  //#ifndef __FAST_EDGE_ESTIMATION_3D_H__


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