multiscale_feature_persistence.hpp
Go to the documentation of this file.
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.hpp 5026 2012-03-12 02:51:44Z rusu $
00036  */
00037 
00038 #ifndef PCL_FEATURES_IMPL_MULTISCALE_FEATURE_PERSISTENCE_H_
00039 #define PCL_FEATURES_IMPL_MULTISCALE_FEATURE_PERSISTENCE_H_
00040 
00041 #include <pcl/features/multiscale_feature_persistence.h>
00042 
00044 template <typename PointSource, typename PointFeature>
00045 pcl::MultiscaleFeaturePersistence<PointSource, PointFeature>::MultiscaleFeaturePersistence () : 
00046   scale_values_ (), 
00047   alpha_ (0), 
00048   distance_metric_ (L1),
00049   feature_estimator_ (),
00050   features_at_scale_ (),
00051   features_at_scale_vectorized_ (),
00052   mean_feature_ (),
00053   feature_representation_ (),
00054   unique_features_indices_ (),
00055   unique_features_table_ ()
00056 {
00057   feature_representation_.reset (new DefaultPointRepresentation<PointFeature>);
00058   // No input is needed, hack around the initCompute () check from PCLBase
00059   input_.reset (new pcl::PointCloud<PointSource> ());
00060 }
00061 
00062 
00064 template <typename PointSource, typename PointFeature> bool
00065 pcl::MultiscaleFeaturePersistence<PointSource, PointFeature>::initCompute ()
00066 {
00067   if (!PCLBase<PointSource>::initCompute ())
00068   {
00069     PCL_ERROR ("[pcl::MultiscaleFeaturePersistence::initCompute] PCLBase::initCompute () failed - no input cloud was given.\n");
00070     return false;
00071   }
00072   if (!feature_estimator_)
00073   {
00074     PCL_ERROR ("[pcl::MultiscaleFeaturePersistence::initCompute] No feature estimator was set\n");
00075     return false;
00076   }
00077   if (scale_values_.empty ())
00078   {
00079     PCL_ERROR ("[pcl::MultiscaleFeaturePersistence::initCompute] No scale values were given\n");
00080     return false;
00081   }
00082 
00083   mean_feature_.resize (feature_representation_->getNumberOfDimensions ());
00084 
00085   return true;
00086 }
00087 
00088 
00090 template <typename PointSource, typename PointFeature> void
00091 pcl::MultiscaleFeaturePersistence<PointSource, PointFeature>::computeFeaturesAtAllScales ()
00092 {
00093   features_at_scale_.resize (scale_values_.size ());
00094   features_at_scale_vectorized_.resize (scale_values_.size ());
00095   for (size_t scale_i = 0; scale_i < scale_values_.size (); ++scale_i)
00096   {
00097     FeatureCloudPtr feature_cloud (new FeatureCloud ());
00098     computeFeatureAtScale (scale_values_[scale_i], feature_cloud);
00099     features_at_scale_[scale_i] = feature_cloud;
00100 
00101     // Vectorize each feature and insert it into the vectorized feature storage
00102     std::vector<std::vector<float> > feature_cloud_vectorized (feature_cloud->points.size ());
00103     for (size_t feature_i = 0; feature_i < feature_cloud->points.size (); ++feature_i)
00104     {
00105       std::vector<float> feature_vectorized (feature_representation_->getNumberOfDimensions ());
00106       feature_representation_->vectorize (feature_cloud->points[feature_i], feature_vectorized);
00107       feature_cloud_vectorized[feature_i] = feature_vectorized;
00108     }
00109     features_at_scale_vectorized_[scale_i] = feature_cloud_vectorized;
00110   }
00111 }
00112 
00113 
00115 template <typename PointSource, typename PointFeature> void
00116 pcl::MultiscaleFeaturePersistence<PointSource, PointFeature>::computeFeatureAtScale (float &scale,
00117                                                                                      FeatureCloudPtr &features)
00118 {
00119    feature_estimator_->setRadiusSearch (scale);
00120    feature_estimator_->compute (*features);
00121 }
00122 
00123 
00125 template <typename PointSource, typename PointFeature> float
00126 pcl::MultiscaleFeaturePersistence<PointSource, PointFeature>::distanceBetweenFeatures (const std::vector<float> &a,
00127                                                                                        const std::vector<float> &b)
00128 {
00129   return (pcl::selectNorm<std::vector<float> > (a, b, static_cast<int> (a.size ()), distance_metric_));
00130 }
00131 
00132 
00134 template <typename PointSource, typename PointFeature> void
00135 pcl::MultiscaleFeaturePersistence<PointSource, PointFeature>::calculateMeanFeature ()
00136 {
00137   // Reset mean feature
00138   for (int i = 0; i < feature_representation_->getNumberOfDimensions (); ++i)
00139     mean_feature_[i] = 0.0f;
00140 
00141   float normalization_factor = 0.0f;
00142   for (std::vector<std::vector<std::vector<float> > >::iterator scale_it = features_at_scale_vectorized_.begin (); scale_it != features_at_scale_vectorized_.end(); ++scale_it) {
00143     normalization_factor += static_cast<float> (scale_it->size ());
00144     for (std::vector<std::vector<float> >::iterator feature_it = scale_it->begin (); feature_it != scale_it->end (); ++feature_it)
00145       for (int dim_i = 0; dim_i < feature_representation_->getNumberOfDimensions (); ++dim_i)
00146         mean_feature_[dim_i] += (*feature_it)[dim_i];
00147   }
00148 
00149   for (int dim_i = 0; dim_i < feature_representation_->getNumberOfDimensions (); ++dim_i)
00150     mean_feature_[dim_i] /= normalization_factor;
00151 }
00152 
00153 
00155 template <typename PointSource, typename PointFeature> void
00156 pcl::MultiscaleFeaturePersistence<PointSource, PointFeature>::extractUniqueFeatures ()
00157 {
00158   unique_features_indices_.resize (scale_values_.size ());
00159   unique_features_table_.resize (scale_values_.size ());
00160   for (size_t scale_i = 0; scale_i < features_at_scale_vectorized_.size (); ++scale_i)
00161   {
00162     // Calculate standard deviation within the scale
00163     float standard_dev = 0.0;
00164     std::vector<float> diff_vector (features_at_scale_vectorized_[scale_i].size ());
00165     for (size_t point_i = 0; point_i < features_at_scale_vectorized_[scale_i].size (); ++point_i)
00166     {
00167       float diff = distanceBetweenFeatures (features_at_scale_vectorized_[scale_i][point_i], mean_feature_);
00168       standard_dev += diff * diff;
00169       diff_vector[point_i] = diff;
00170     }
00171     standard_dev = sqrtf (standard_dev / static_cast<float> (features_at_scale_vectorized_[scale_i].size ()));
00172     PCL_DEBUG ("[pcl::MultiscaleFeaturePersistence::extractUniqueFeatures] Standard deviation for scale %f is %f\n", scale_values_[scale_i], standard_dev);
00173 
00174     // Select only points outside (mean +/- alpha * standard_dev)
00175     std::list<size_t> indices_per_scale;
00176     std::vector<bool> indices_table_per_scale (features_at_scale_[scale_i]->points.size (), false);
00177     for (size_t point_i = 0; point_i < features_at_scale_[scale_i]->points.size (); ++point_i)
00178     {
00179       if (diff_vector[point_i] > alpha_ * standard_dev)
00180       {
00181         indices_per_scale.push_back (point_i);
00182         indices_table_per_scale[point_i] = true;
00183       }
00184     }
00185     unique_features_indices_[scale_i] = indices_per_scale;
00186     unique_features_table_[scale_i] = indices_table_per_scale;
00187   }
00188 }
00189 
00190 
00192 template <typename PointSource, typename PointFeature> void
00193 pcl::MultiscaleFeaturePersistence<PointSource, PointFeature>::determinePersistentFeatures (FeatureCloud &output_features,
00194                                                                                            boost::shared_ptr<std::vector<int> > &output_indices)
00195 {
00196   if (!initCompute ())
00197     return;
00198 
00199   // Compute the features for all scales with the given feature estimator
00200   PCL_DEBUG ("[pcl::MultiscaleFeaturePersistence::determinePersistentFeatures] Computing features ...\n");
00201   computeFeaturesAtAllScales ();
00202 
00203   // Compute mean feature
00204   PCL_DEBUG ("[pcl::MultiscaleFeaturePersistence::determinePersistentFeatures] Calculating mean feature ...\n");
00205   calculateMeanFeature ();
00206 
00207   // Get the 'unique' features at each scale
00208   PCL_DEBUG ("[pcl::MultiscaleFeaturePersistence::determinePersistentFeatures] Extracting unique features ...\n");
00209   extractUniqueFeatures ();
00210 
00211   PCL_DEBUG ("[pcl::MultiscaleFeaturePersistence::determinePersistentFeatures] Determining persistent features between scales ...\n");
00212   // Determine persistent features between scales
00213 
00214 /*
00215   // Method 1: a feature is considered persistent if it is 'unique' in at least 2 different scales
00216   for (size_t scale_i = 0; scale_i < features_at_scale_vectorized_.size () - 1; ++scale_i)
00217     for (std::list<size_t>::iterator feature_it = unique_features_indices_[scale_i].begin (); feature_it != unique_features_indices_[scale_i].end (); ++feature_it)
00218     {
00219       if (unique_features_table_[scale_i][*feature_it] == true)
00220       {
00221         output_features.points.push_back (features_at_scale[scale_i]->points[*feature_it]);
00222         output_indices->push_back (feature_estimator_->getIndices ()->at (*feature_it));
00223       }
00224     }
00225 */
00226   // Method 2: a feature is considered persistent if it is 'unique' in all the scales
00227   for (std::list<size_t>::iterator feature_it = unique_features_indices_.front ().begin (); feature_it != unique_features_indices_.front ().end (); ++feature_it)
00228   {
00229     bool present_in_all = true;
00230     for (size_t scale_i = 0; scale_i < features_at_scale_.size (); ++scale_i)
00231       present_in_all = present_in_all && unique_features_table_[scale_i][*feature_it];
00232 
00233     if (present_in_all)
00234     {
00235       output_features.points.push_back (features_at_scale_.front ()->points[*feature_it]);
00236       output_indices->push_back (feature_estimator_->getIndices ()->at (*feature_it));
00237     }
00238   }
00239 
00240   // Consider that output cloud is unorganized
00241   output_features.header = feature_estimator_->getInputCloud ()->header;
00242   output_features.is_dense = feature_estimator_->getInputCloud ()->is_dense;
00243   output_features.width = static_cast<uint32_t> (output_features.points.size ());
00244   output_features.height = 1;
00245 }
00246 
00247 
00248 #define PCL_INSTANTIATE_MultiscaleFeaturePersistence(InT, Feature) template class PCL_EXPORTS pcl::MultiscaleFeaturePersistence<InT, Feature>;
00249 
00250 #endif /* PCL_FEATURES_IMPL_MULTISCALE_FEATURE_PERSISTENCE_H_ */


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:45