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 
00038 
00039 
00040 #ifndef PCL_SPIN_IMAGE_H_
00041 #define PCL_SPIN_IMAGE_H_
00042 
00043 #include <pcl/point_types.h>
00044 #include <pcl/features/feature.h>
00045 
00046 namespace pcl
00047 {
00087   template <typename PointInT, typename PointNT, typename PointOutT>
00088   class SpinImageEstimation : public Feature<PointInT, PointOutT>
00089   {
00090     public:
00091       typedef boost::shared_ptr<SpinImageEstimation<PointInT, PointNT, PointOutT> > Ptr;
00092       typedef boost::shared_ptr<const SpinImageEstimation<PointInT, PointNT, PointOutT> > ConstPtr;
00093       using Feature<PointInT, PointOutT>::feature_name_;
00094       using Feature<PointInT, PointOutT>::getClassName;
00095       using Feature<PointInT, PointOutT>::indices_;
00096       using Feature<PointInT, PointOutT>::search_radius_;
00097       using Feature<PointInT, PointOutT>::k_;
00098       using Feature<PointInT, PointOutT>::surface_;
00099       using Feature<PointInT, PointOutT>::fake_surface_;
00100       using PCLBase<PointInT>::input_;
00101 
00102       typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00103 
00104       typedef typename pcl::PointCloud<PointNT> PointCloudN;
00105       typedef typename PointCloudN::Ptr PointCloudNPtr;
00106       typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;
00107 
00108       typedef typename pcl::PointCloud<PointInT> PointCloudIn;
00109       typedef typename PointCloudIn::Ptr PointCloudInPtr;
00110       typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00111       
00121       SpinImageEstimation (unsigned int image_width = 8,
00122                            double support_angle_cos = 0.0,   
00123                            unsigned int min_pts_neighb = 0);
00124       
00126       virtual ~SpinImageEstimation () {}
00127 
00132       void 
00133       setImageWidth (unsigned int bin_count)
00134       {
00135         image_width_ = bin_count;
00136       }
00137 
00144       void 
00145       setSupportAngle (double support_angle_cos)
00146       {
00147         if (0.0 > support_angle_cos || support_angle_cos > 1.0)  
00148         {
00149           throw PCLException ("Cosine of support angle should be between 0 and 1",
00150             "spin_image.h", "setSupportAngle");
00151         }
00152 
00153         support_angle_cos_ = support_angle_cos;
00154       }
00155 
00161       void 
00162       setMinPointCountInNeighbourhood (unsigned int min_pts_neighb)
00163       {
00164         min_pts_neighb_ = min_pts_neighb;
00165       }
00166 
00177       inline void 
00178       setInputNormals (const PointCloudNConstPtr &normals)
00179       { 
00180         input_normals_ = normals; 
00181       }
00182 
00188       void 
00189       setRotationAxis (const PointNT& axis)
00190       {
00191         rotation_axis_ = axis;
00192         use_custom_axis_ = true;
00193         use_custom_axes_cloud_ = false;
00194       }
00195 
00202       void 
00203       setInputRotationAxes (const PointCloudNConstPtr& axes)
00204       {
00205         rotation_axes_cloud_ = axes;
00206 
00207         use_custom_axes_cloud_ = true;
00208         use_custom_axis_ = false;
00209       }
00210 
00212       void 
00213       useNormalsAsRotationAxis () 
00214       { 
00215         use_custom_axis_ = false; 
00216         use_custom_axes_cloud_ = false;
00217       }
00218 
00230       void 
00231       setAngularDomain (bool is_angular = true) { is_angular_ = is_angular; }
00232 
00240       void 
00241       setRadialStructure (bool is_radial = true) { is_radial_ = is_radial; }
00242 
00243     protected:
00248       virtual void 
00249       computeFeature (PointCloudOut &output); 
00250 
00255       virtual bool
00256       initCompute ();
00257 
00262       Eigen::ArrayXXd 
00263       computeSiForPoint (int index) const;
00264 
00265     private:
00266       PointCloudNConstPtr input_normals_;
00267       PointCloudNConstPtr rotation_axes_cloud_;
00268       
00269       bool is_angular_;
00270 
00271       PointNT rotation_axis_;
00272       bool use_custom_axis_;
00273       bool use_custom_axes_cloud_;
00274 
00275       bool is_radial_;
00276 
00277       unsigned int image_width_;
00278       double support_angle_cos_;
00279       unsigned int min_pts_neighb_;
00280   };
00281 }
00282 
00283 #ifdef PCL_NO_PRECOMPILE
00284 #include <pcl/features/impl/spin_image.hpp>
00285 #endif
00286 
00287 #endif  //#ifndef PCL_SPIN_IMAGE_H_
00288