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 #ifndef PCL_RSD_H_
00042 #define PCL_RSD_H_
00043
00044 #include <pcl/features/feature.h>
00045
00046 namespace pcl
00047 {
00055 template <int N> void
00056 getFeaturePointCloud (const std::vector<Eigen::MatrixXf, Eigen::aligned_allocator<Eigen::MatrixXf> > &histograms2D, PointCloud<Histogram<N> > &histogramsPC)
00057 {
00058 histogramsPC.points.resize (histograms2D.size ());
00059 histogramsPC.width = histograms2D.size ();
00060 histogramsPC.height = 1;
00061 histogramsPC.is_dense = true;
00062
00063 const int rows = histograms2D.at(0).rows();
00064 const int cols = histograms2D.at(0).cols();
00065
00066 typename PointCloud<Histogram<N> >::VectorType::iterator it = histogramsPC.points.begin ();
00067 BOOST_FOREACH (Eigen::MatrixXf h, histograms2D)
00068 {
00069 Eigen::Map<Eigen::MatrixXf> histogram (&(it->histogram[0]), rows, cols);
00070 histogram = h;
00071 ++it;
00072 }
00073 }
00074
00086 template <typename PointInT, typename PointNT, typename PointOutT> Eigen::MatrixXf
00087 computeRSD (boost::shared_ptr<const pcl::PointCloud<PointInT> > &surface, boost::shared_ptr<const pcl::PointCloud<PointNT> > &normals,
00088 const std::vector<int> &indices, double max_dist,
00089 int nr_subdiv, double plane_radius, PointOutT &radii, bool compute_histogram = false);
00090
00102 template <typename PointNT, typename PointOutT> Eigen::MatrixXf
00103 computeRSD (boost::shared_ptr<const pcl::PointCloud<PointNT> > &normals,
00104 const std::vector<int> &indices, const std::vector<float> &sqr_dists, double max_dist,
00105 int nr_subdiv, double plane_radius, PointOutT &radii, bool compute_histogram = false);
00106
00129 template <typename PointInT, typename PointNT, typename PointOutT>
00130 class RSDEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
00131 {
00132 public:
00133 using Feature<PointInT, PointOutT>::feature_name_;
00134 using Feature<PointInT, PointOutT>::getClassName;
00135 using Feature<PointInT, PointOutT>::indices_;
00136 using Feature<PointInT, PointOutT>::search_radius_;
00137 using Feature<PointInT, PointOutT>::search_parameter_;
00138 using Feature<PointInT, PointOutT>::surface_;
00139 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00140
00141 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00142 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00143
00144 typedef typename boost::shared_ptr<RSDEstimation<PointInT, PointNT, PointOutT> > Ptr;
00145 typedef typename boost::shared_ptr<const RSDEstimation<PointInT, PointNT, PointOutT> > ConstPtr;
00146
00147
00149 RSDEstimation () : nr_subdiv_ (5), plane_radius_ (0.2), save_histograms_ (false)
00150 {
00151 feature_name_ = "RadiusSurfaceDescriptor";
00152 };
00153
00157 inline void
00158 setNrSubdivisions (int nr_subdiv) { nr_subdiv_ = nr_subdiv; }
00159
00161 inline int
00162 getNrSubdivisions () const { return (nr_subdiv_); }
00163
00169 inline void
00170 setPlaneRadius (double plane_radius) { plane_radius_ = plane_radius; }
00171
00173 inline double
00174 getPlaneRadius () const { return (plane_radius_); }
00175
00177 inline void
00178 setKSearch (int)
00179 {
00180 PCL_ERROR ("[pcl::%s::setKSearch] RSD does not work with k nearest neighbor search. Use setRadiusSearch() instead!\n", getClassName ().c_str ());
00181 }
00182
00187 inline void
00188 setSaveHistograms (bool save) { save_histograms_ = save; }
00189
00191 inline bool
00192 getSaveHistograms () const { return (save_histograms_); }
00193
00195 inline boost::shared_ptr<std::vector<Eigen::MatrixXf, Eigen::aligned_allocator<Eigen::MatrixXf> > >
00196 getHistograms () const { return (histograms_); }
00197
00198 protected:
00199
00205 void
00206 computeFeature (PointCloudOut &output);
00207
00209 boost::shared_ptr<std::vector<Eigen::MatrixXf, Eigen::aligned_allocator<Eigen::MatrixXf> > > histograms_;
00210
00211 private:
00213 int nr_subdiv_;
00214
00216 double plane_radius_;
00217
00219 bool save_histograms_;
00220
00221 public:
00222 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00223 };
00224 }
00225
00226 #ifdef PCL_NO_PRECOMPILE
00227 #include <pcl/features/impl/rsd.hpp>
00228 #endif
00229
00230 #endif //#ifndef PCL_RSD_H_