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 #ifndef PCL_RSD_H_
00039 #define PCL_RSD_H_
00040
00041 #include <pcl/features/feature.h>
00042
00043 namespace pcl
00044 {
00052 template <int N> void
00053 getFeaturePointCloud (const std::vector<Eigen::MatrixXf, Eigen::aligned_allocator<Eigen::MatrixXf> > &histograms2D, PointCloud<Histogram<N> > &histogramsPC)
00054 {
00055 histogramsPC.points.resize (histograms2D.size ());
00056 histogramsPC.width = histograms2D.size ();
00057 histogramsPC.height = 1;
00058 histogramsPC.is_dense = true;
00059
00060 const int rows = histograms2D.at(0).rows();
00061 const int cols = histograms2D.at(0).cols();
00062
00063 typename PointCloud<Histogram<N> >::VectorType::iterator it = histogramsPC.points.begin ();
00064 BOOST_FOREACH (Eigen::MatrixXf h, histograms2D)
00065 {
00066 Eigen::Map<Eigen::MatrixXf> histogram (&(it->histogram[0]), rows, cols);
00067 histogram = h;
00068 ++it;
00069 }
00070 }
00071
00083 template <typename PointInT, typename PointNT, typename PointOutT> Eigen::MatrixXf
00084 computeRSD (boost::shared_ptr<const pcl::PointCloud<PointInT> > &surface, boost::shared_ptr<const pcl::PointCloud<PointNT> > &normals,
00085 const std::vector<int> &indices, double max_dist,
00086 int nr_subdiv, double plane_radius, PointOutT &radii, bool compute_histogram = false);
00087
00099 template <typename PointNT, typename PointOutT> Eigen::MatrixXf
00100 computeRSD (boost::shared_ptr<const pcl::PointCloud<PointNT> > &normals,
00101 const std::vector<int> &indices, const std::vector<float> &sqr_dists, double max_dist,
00102 int nr_subdiv, double plane_radius, PointOutT &radii, bool compute_histogram = false);
00103
00126 template <typename PointInT, typename PointNT, typename PointOutT>
00127 class RSDEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
00128 {
00129 public:
00130 using Feature<PointInT, PointOutT>::feature_name_;
00131 using Feature<PointInT, PointOutT>::getClassName;
00132 using Feature<PointInT, PointOutT>::indices_;
00133 using Feature<PointInT, PointOutT>::search_radius_;
00134 using Feature<PointInT, PointOutT>::search_parameter_;
00135 using Feature<PointInT, PointOutT>::surface_;
00136 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00137
00138 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00139 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00140
00141 typedef typename boost::shared_ptr<RSDEstimation<PointInT, PointNT, PointOutT> > Ptr;
00142 typedef typename boost::shared_ptr<const RSDEstimation<PointInT, PointNT, PointOutT> > ConstPtr;
00143
00144
00146 RSDEstimation () : nr_subdiv_ (5), plane_radius_ (0.2), save_histograms_ (false)
00147 {
00148 feature_name_ = "RadiusSurfaceDescriptor";
00149 };
00150
00154 inline void
00155 setNrSubdivisions (int nr_subdiv) { nr_subdiv_ = nr_subdiv; }
00156
00158 inline int
00159 getNrSubdivisions () const { return (nr_subdiv_); }
00160
00166 inline void
00167 setPlaneRadius (double plane_radius) { plane_radius_ = plane_radius; }
00168
00170 inline double
00171 getPlaneRadius () const { return (plane_radius_); }
00172
00174 inline void
00175 setKSearch (int)
00176 {
00177 PCL_ERROR ("[pcl::%s::setKSearch] RSD does not work with k nearest neighbor search. Use setRadiusSearch() instead!\n", getClassName ().c_str ());
00178 }
00179
00184 inline void
00185 setSaveHistograms (bool save) { save_histograms_ = save; }
00186
00188 inline bool
00189 getSaveHistograms () const { return (save_histograms_); }
00190
00192 inline boost::shared_ptr<std::vector<Eigen::MatrixXf, Eigen::aligned_allocator<Eigen::MatrixXf> > >
00193 getHistograms () const { return (histograms_); }
00194
00195 protected:
00196
00202 void
00203 computeFeature (PointCloudOut &output);
00204
00206 boost::shared_ptr<std::vector<Eigen::MatrixXf, Eigen::aligned_allocator<Eigen::MatrixXf> > > histograms_;
00207
00208 private:
00210 int nr_subdiv_;
00211
00213 double plane_radius_;
00214
00216 bool save_histograms_;
00217
00221 void
00222 computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output) {}
00223 public:
00224 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00225 };
00226 }
00227
00228 #endif //#ifndef PCL_RSD_H_
00229
00230