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
00041
00042 #ifndef PCL_FILTERS_COVARIANCE_SAMPLING_H_
00043 #define PCL_FILTERS_COVARIANCE_SAMPLING_H_
00044
00045 #include <pcl/filters/filter_indices.h>
00046
00047 namespace pcl
00048 {
00061 template <typename PointT, typename PointNT>
00062 class CovarianceSampling : public FilterIndices<PointT>
00063 {
00064 using FilterIndices<PointT>::filter_name_;
00065 using FilterIndices<PointT>::getClassName;
00066 using FilterIndices<PointT>::indices_;
00067 using FilterIndices<PointT>::input_;
00068 using FilterIndices<PointT>::initCompute;
00069
00070 typedef typename FilterIndices<PointT>::PointCloud Cloud;
00071 typedef typename Cloud::Ptr CloudPtr;
00072 typedef typename Cloud::ConstPtr CloudConstPtr;
00073 typedef typename pcl::PointCloud<PointNT>::ConstPtr NormalsConstPtr;
00074
00075 public:
00076 typedef boost::shared_ptr< CovarianceSampling<PointT, PointNT> > Ptr;
00077 typedef boost::shared_ptr< const CovarianceSampling<PointT, PointNT> > ConstPtr;
00078
00080 CovarianceSampling ()
00081 { filter_name_ = "CovarianceSampling"; }
00082
00086 inline void
00087 setNumberOfSamples (unsigned int samples)
00088 { num_samples_ = samples; }
00089
00091 inline unsigned int
00092 getNumberOfSamples () const
00093 { return (num_samples_); }
00094
00098 inline void
00099 setNormals (const NormalsConstPtr &normals)
00100 { input_normals_ = normals; }
00101
00103 inline NormalsConstPtr
00104 getNormals () const
00105 { return (input_normals_); }
00106
00107
00108
00114 double
00115 computeConditionNumber ();
00116
00123 static double
00124 computeConditionNumber (const Eigen::Matrix<double, 6, 6> &covariance_matrix);
00125
00130 bool
00131 computeCovarianceMatrix (Eigen::Matrix<double, 6, 6> &covariance_matrix);
00132
00133 protected:
00135 unsigned int num_samples_;
00136
00138 NormalsConstPtr input_normals_;
00139
00140 std::vector<Eigen::Vector3f> scaled_points_;
00141
00142 bool
00143 initCompute ();
00144
00148 void
00149 applyFilter (Cloud &output);
00150
00154 void
00155 applyFilter (std::vector<int> &indices);
00156
00157 static bool
00158 sort_dot_list_function (std::pair<int, double> a,
00159 std::pair<int, double> b)
00160 { return (a.second > b.second); }
00161
00162 public:
00163 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00164 };
00165 }
00166
00167 #ifdef PCL_NO_PRECOMPILE
00168 #include <pcl/filters/impl/covariance_sampling.hpp>
00169 #endif
00170
00171
00172 #endif