jump_edge_filter.h
Go to the documentation of this file.
00001 
00060 #ifndef JUMP_EDGE_FILTER_H_
00061 #define JUMP_EDGE_FILTER_H_
00062 
00063 //##################
00064 //#### includes ####
00065 
00066 // PCL includes
00067 #include <pcl/pcl_base.h>
00068 #include <pcl/point_types.h>
00069 #include <pcl/filters/filter.h>
00070 
00071 namespace cob_3d_mapping_filters
00072 {
00078   template<typename PointT>
00079     class JumpEdgeFilter : public pcl::Filter<PointT>
00080     {
00081       using pcl::Filter<PointT>::input_;
00082 
00083     public:
00084       typedef typename pcl::Filter<PointT>::PointCloud PointCloud;
00085       typedef typename PointCloud::Ptr PointCloudPtr;
00086       typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00087 
00089       JumpEdgeFilter () :
00090           angle_deg_ (170.0)
00091       {
00092       }
00093       ;
00094 
00095       //virtual ~JumpEdgeFilter();
00096 
00102       inline void
00103       setAngleThreshold (double angle)
00104       {
00105         angle_deg_ = angle;
00106       }
00107 
00113       inline double
00114       getAngleThreshold ()
00115       {
00116         return angle_deg_;
00117       }
00118 
00119     protected:
00120 
00126       void
00127       applyFilter (PointCloud &output);
00128 
00130       double angle_deg_;
00131     };
00132 
00133 } // end namespace cob_3d_mapping_filters
00134 
00135 #endif /* JUMP_EDGE_FILTER_H_ */


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