|
Point Cloud Library (PCL)
1.4.0
|
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2009, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage, Inc. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 * 00034 * $Id: rsd.h 3755 2011-12-31 23:45:30Z rusu $ 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 { 00054 inline int 00055 getSimpleType (float min_radius, float max_radius, 00056 double min_radius_plane = 0.100, 00057 double max_radius_noise = 0.015, 00058 double min_radius_cylinder = 0.175, 00059 double max_min_radius_diff = 0.050) 00060 { 00061 if (min_radius > min_radius_plane) 00062 return 1; // plane 00063 else if (max_radius > min_radius_cylinder) 00064 return 2; // cylinder (rim) 00065 else if (min_radius < max_radius_noise) 00066 return 0; // noise/corner 00067 else if (max_radius - min_radius < max_min_radius_diff) 00068 return 3; // sphere/corner 00069 else 00070 return 4; // edge 00071 } 00072 00080 template <int N> void 00081 getFeaturePointCloud (const std::vector<Eigen::MatrixXf> &histograms2D, PointCloud<Histogram<N> > &histogramsPC) 00082 { 00083 histogramsPC.points.resize (histograms2D.size ()); 00084 histogramsPC.width = histograms2D.size (); 00085 histogramsPC.height = 1; 00086 histogramsPC.is_dense = true; 00087 00088 const int rows = histograms2D.at(0).rows(); 00089 const int cols = histograms2D.at(0).cols(); 00090 00091 typename PointCloud<Histogram<N> >::VectorType::iterator it = histogramsPC.points.begin (); 00092 BOOST_FOREACH (Eigen::MatrixXf h, histograms2D) 00093 { 00094 Eigen::Map<Eigen::MatrixXf> histogram (&(it->histogram[0]), rows, cols); 00095 histogram = h; 00096 ++it; 00097 } 00098 } 00099 00111 template <typename PointInT, typename PointNT, typename PointOutT> void 00112 computeRSD (const PointCloud<PointInT> &surface, const PointCloud<PointNT> &normals, 00113 const std::vector<int> &indices, double max_dist, 00114 int nr_subdiv, double plane_radius, PointOutT &radii, Eigen::MatrixXf *histogram = NULL); 00115 00138 template <typename PointInT, typename PointNT, typename PointOutT> 00139 class RSDEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT> 00140 { 00141 public: 00142 using Feature<PointInT, PointOutT>::feature_name_; 00143 using Feature<PointInT, PointOutT>::getClassName; 00144 using Feature<PointInT, PointOutT>::indices_; 00145 using Feature<PointInT, PointOutT>::search_radius_; 00146 using Feature<PointInT, PointOutT>::search_parameter_; 00147 using Feature<PointInT, PointOutT>::surface_; 00148 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_; 00149 00150 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut; 00151 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn; 00152 00154 RSDEstimation () : nr_subdiv_ (5), plane_radius_ (0.2), save_histograms_ (false) 00155 { 00156 feature_name_ = "RadiusSurfaceDescriptor"; 00157 }; 00158 00162 inline void 00163 setNrSubdivisions (int nr_subdiv) { nr_subdiv_ = nr_subdiv; } 00164 00166 inline int 00167 getNrSubdivisions () { return (nr_subdiv_); } 00168 00174 inline void 00175 setPlaneRadius (double plane_radius) { plane_radius_ = plane_radius; } 00176 00178 inline double 00179 getPlaneRadius () { return (plane_radius_); } 00180 00182 inline void 00183 setKSearch (int) 00184 { 00185 PCL_ERROR ("[pcl::%s::setKSearch] RSD does not work with k nearest neighbor search. Use setRadiusSearch() instead!\n", getClassName ().c_str ()); 00186 } 00187 00192 inline void 00193 setSaveHistograms (bool save) { save_histograms_ = save; } 00194 00196 inline bool 00197 getSaveHistograms () { return save_histograms_; } 00198 00200 inline std::vector<Eigen::MatrixXf>* 00201 getHistograms () { return &histograms_; } 00202 00203 protected: 00204 00210 void 00211 computeFeature (PointCloudOut &output); 00212 00214 std::vector<Eigen::MatrixXf> histograms_; 00215 00216 private: 00218 // TODO double max_dist_; 00219 00221 int nr_subdiv_; 00222 00224 double plane_radius_; 00225 00227 bool save_histograms_; 00228 00232 void 00233 computeFeature (pcl::PointCloud<Eigen::MatrixXf> &output) {} 00234 }; 00235 } 00236 00237 #endif //#ifndef PCL_RSD_H_ 00238 00239
1.7.6.1