00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2011, Alexandru-Eugen Ichim 00005 * Willow Garage, Inc 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of Willow Garage, Inc. nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 * 00035 * $Id: multiscale_feature_persistence.h 4864 2012-03-01 01:11:22Z rusu $ 00036 */ 00037 00038 #ifndef PCL_MULTISCALE_FEATURE_PERSISTENCE_H_ 00039 #define PCL_MULTISCALE_FEATURE_PERSISTENCE_H_ 00040 00041 #include <pcl/pcl_base.h> 00042 #include <pcl/features/feature.h> 00043 #include <pcl/point_representation.h> 00044 #include <pcl/common/norms.h> 00045 #include <list> 00046 00047 namespace pcl 00048 { 00061 template <typename PointSource, typename PointFeature> 00062 class MultiscaleFeaturePersistence : public PCLBase<PointSource> 00063 { 00064 public: 00065 typedef pcl::PointCloud<PointFeature> FeatureCloud; 00066 typedef typename pcl::PointCloud<PointFeature>::Ptr FeatureCloudPtr; 00067 typedef typename pcl::Feature<PointSource, PointFeature>::Ptr FeatureEstimatorPtr; 00068 typedef boost::shared_ptr<const pcl::PointRepresentation <PointFeature> > FeatureRepresentationConstPtr; 00069 00070 using pcl::PCLBase<PointSource>::input_; 00071 00073 MultiscaleFeaturePersistence (); 00074 00076 void 00077 computeFeaturesAtAllScales (); 00078 00084 void 00085 determinePersistentFeatures (FeatureCloud &output_features, 00086 boost::shared_ptr<std::vector<int> > &output_indices); 00087 00091 inline void 00092 setScalesVector (std::vector<float> &scale_values) { scale_values_ = scale_values; } 00093 00095 inline std::vector<float> 00096 getScalesVector () { return scale_values_; } 00097 00103 inline void 00104 setFeatureEstimator (FeatureEstimatorPtr feature_estimator) { feature_estimator_ = feature_estimator; }; 00105 00107 inline FeatureEstimatorPtr 00108 getFeatureEstimator () { return feature_estimator_; } 00109 00113 inline void 00114 setPointRepresentation (const FeatureRepresentationConstPtr& feature_representation) { feature_representation_ = feature_representation; } 00115 00117 inline FeatureRepresentationConstPtr const 00118 getPointRepresentation () { return feature_representation_; } 00119 00123 inline void 00124 setAlpha (float alpha) { alpha_ = alpha; } 00125 00127 inline float 00128 getAlpha () { return alpha_; } 00129 00133 inline void 00134 setDistanceMetric (NormType distance_metric) { distance_metric_ = distance_metric; } 00135 00137 inline NormType 00138 getDistanceMetric () { return distance_metric_; } 00139 00140 00141 private: 00143 bool 00144 initCompute (); 00145 00146 00148 virtual void 00149 computeFeatureAtScale (float &scale, 00150 FeatureCloudPtr &features); 00151 00152 00156 float 00157 distanceBetweenFeatures (const std::vector<float> &a, 00158 const std::vector<float> &b); 00159 00163 void 00164 calculateMeanFeature (); 00165 00169 void 00170 extractUniqueFeatures (); 00171 00172 00174 std::vector<float> scale_values_; 00175 00177 float alpha_; 00178 00180 NormType distance_metric_; 00181 00183 FeatureEstimatorPtr feature_estimator_; 00184 00185 std::vector<FeatureCloudPtr> features_at_scale_; 00186 std::vector<std::vector<std::vector<float> > > features_at_scale_vectorized_; 00187 std::vector<float> mean_feature_; 00188 FeatureRepresentationConstPtr feature_representation_; 00189 00193 std::vector<std::list<size_t> > unique_features_indices_; 00194 std::vector<std::vector<bool> > unique_features_table_; 00195 }; 00196 } 00197 00198 00199 #endif /* PCL_MULTISCALE_FEATURE_PERSISTENCE_H_ */