statistical_multiscale_interest_region_extraction.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: statistical_multiscale_interest_region_extraction.hpp 5026 2012-03-12 02:51:44Z rusu $
00036  */
00037 
00038 #ifndef PCL_FEATURES_IMPL_STATISTICAL_MULTISCALE_INTEREST_REGION_EXTRACTION_H_
00039 #define PCL_FEATURES_IMPL_STATISTICAL_MULTISCALE_INTEREST_REGION_EXTRACTION_H_
00040 
00041 #include <pcl/features/statistical_multiscale_interest_region_extraction.h>
00042 #include <pcl/kdtree/kdtree_flann.h>
00043 #include <boost/graph/adjacency_list.hpp>
00044 #include <boost/property_map/property_map.hpp>
00045 #include <boost/graph/johnson_all_pairs_shortest.hpp>
00046 #include <pcl/common/distances.h>
00047 
00049 template <typename PointT> void
00050 pcl::StatisticalMultiscaleInterestRegionExtraction<PointT>::generateCloudGraph ()
00051 {
00052   // generate a K-NNG (K-nearest neighbors graph)
00053   pcl::KdTreeFLANN<PointT> kdtree;
00054   kdtree.setInputCloud (input_);
00055 
00056   using namespace boost;
00057   typedef property<edge_weight_t, float> Weight;
00058   typedef adjacency_list<vecS, vecS, undirectedS, no_property, Weight> Graph;
00059   Graph cloud_graph;
00060 
00061   for (size_t point_i = 0; point_i < input_->points.size (); ++point_i)
00062   {
00063     std::vector<int> k_indices (16);
00064     std::vector<float> k_distances (16);
00065     kdtree.nearestKSearch (static_cast<int> (point_i), 16, k_indices, k_distances);
00066 
00067     for (int k_i = 0; k_i < static_cast<int> (k_indices.size ()); ++k_i)
00068       add_edge (point_i, k_indices[k_i], Weight (sqrtf (k_distances[k_i])), cloud_graph);
00069   }
00070 
00071   const size_t E = num_edges (cloud_graph),
00072       V = num_vertices (cloud_graph);
00073   PCL_INFO ("The graph has %lu vertices and %lu edges.\n", V, E);
00074   geodesic_distances_.clear ();
00075   for (size_t i = 0; i < V; ++i)
00076   {
00077     std::vector<float> aux (V);
00078     geodesic_distances_.push_back (aux);
00079   }
00080   johnson_all_pairs_shortest_paths (cloud_graph, geodesic_distances_);
00081 
00082   PCL_INFO ("Done generating the graph\n");
00083 }
00084 
00085 
00087 template <typename PointT> bool
00088 pcl::StatisticalMultiscaleInterestRegionExtraction<PointT>::initCompute ()
00089 {
00090   if (!PCLBase<PointT>::initCompute ())
00091   {
00092     PCL_ERROR ("[pcl::StatisticalMultiscaleInterestRegionExtraction::initCompute] PCLBase::initCompute () failed - no input cloud was given.\n");
00093     return (false);
00094   }
00095   if (scale_values_.empty ())
00096   {
00097     PCL_ERROR ("[pcl::StatisticalMultiscaleInterestRegionExtraction::initCompute] No scale values were given\n");
00098     return (false);
00099   }
00100 
00101   return (true);
00102 }
00103 
00104 
00106 template <typename PointT> void
00107 pcl::StatisticalMultiscaleInterestRegionExtraction<PointT>::geodesicFixedRadiusSearch (size_t &query_index,
00108                                                                                        float &radius,
00109                                                                                        std::vector<int> &result_indices)
00110 {
00111   for (size_t i = 0; i < geodesic_distances_[query_index].size (); ++i)
00112     if (i != query_index && geodesic_distances_[query_index][i] < radius)
00113       result_indices.push_back (static_cast<int> (i));
00114 }
00115 
00116 
00118 template <typename PointT> void
00119 pcl::StatisticalMultiscaleInterestRegionExtraction<PointT>::computeRegionsOfInterest (std::list<IndicesPtr> &rois)
00120 {
00121   if (!initCompute ())
00122   {
00123     PCL_ERROR ("StatisticalMultiscaleInterestRegionExtraction: not completely initialized\n");
00124     return;
00125   }
00126 
00127   generateCloudGraph ();
00128 
00129   computeF ();
00130 
00131   extractExtrema (rois);
00132 }
00133 
00134 
00136 template <typename PointT> void
00137 pcl::StatisticalMultiscaleInterestRegionExtraction<PointT>::computeF ()
00138 {
00139   PCL_INFO ("Calculating statistical information\n");
00140 
00141   // declare and initialize data structure
00142   F_scales_.resize (scale_values_.size ());
00143   std::vector<float> point_density (input_->points.size ()),
00144           F (input_->points.size ());
00145   std::vector<std::vector<float> > phi (input_->points.size ());
00146   std::vector<float> phi_row (input_->points.size ());
00147 
00148   for (size_t scale_i = 0; scale_i < scale_values_.size (); ++scale_i)
00149   {
00150     float scale_squared = scale_values_[scale_i] * scale_values_[scale_i];
00151 
00152     // calculate point density for each point x_i
00153     for (size_t point_i = 0; point_i < input_->points.size (); ++point_i)
00154     {
00155       float point_density_i = 0.0;
00156       for (size_t point_j = 0; point_j < input_->points.size (); ++point_j)
00157       {
00158         float d_g = geodesic_distances_[point_i][point_j];
00159         float phi_i_j = 1.0f / sqrtf (2.0f * static_cast<float> (M_PI) * scale_squared) * expf ( (-1) * d_g*d_g / (2.0f * scale_squared));
00160 
00161         point_density_i += phi_i_j;
00162         phi_row[point_j] = phi_i_j;
00163       }
00164       point_density[point_i] = point_density_i;
00165       phi[point_i] = phi_row;
00166     }
00167 
00168     // compute weights for each pair (x_i, x_j), evaluate the operator A_hat
00169     for (size_t point_i = 0; point_i < input_->points.size (); ++point_i)
00170     {
00171       float A_hat_normalization = 0.0;
00172       PointT A_hat; A_hat.x = A_hat.y = A_hat.z = 0.0;
00173       for (size_t point_j = 0; point_j < input_->points.size (); ++point_j)
00174       {
00175         float phi_hat_i_j = phi[point_i][point_j] / (point_density[point_i] * point_density[point_j]);
00176         A_hat_normalization += phi_hat_i_j;
00177 
00178         PointT aux = input_->points[point_j];
00179         aux.x *= phi_hat_i_j; aux.y *= phi_hat_i_j; aux.z *= phi_hat_i_j;
00180 
00181         A_hat.x += aux.x; A_hat.y += aux.y; A_hat.z += aux.z;
00182       }
00183       A_hat.x /= A_hat_normalization; A_hat.y /= A_hat_normalization; A_hat.z /= A_hat_normalization;
00184 
00185       // compute the invariant F
00186       float aux = 2.0f / scale_values_[scale_i] * euclideanDistance<PointT, PointT> (A_hat, input_->points[point_i]);
00187       F[point_i] = aux * expf (-aux);
00188     }
00189 
00190     F_scales_[scale_i] = F;
00191   }
00192 }
00193 
00194 
00196 template <typename PointT> void
00197 pcl::StatisticalMultiscaleInterestRegionExtraction<PointT>::extractExtrema (std::list<IndicesPtr> &rois)
00198 {
00199   std::vector<std::vector<bool> > is_min (scale_values_.size ()),
00200       is_max (scale_values_.size ());
00201 
00202   // for each point, check if it is a local extrema on each scale
00203   for (size_t scale_i = 0; scale_i < scale_values_.size (); ++scale_i)
00204   {
00205     std::vector<bool> is_min_scale (input_->points.size ()),
00206         is_max_scale (input_->points.size ());
00207     for (size_t point_i = 0; point_i < input_->points.size (); ++point_i)
00208     {
00209       std::vector<int> nn_indices;
00210       geodesicFixedRadiusSearch (point_i, scale_values_[scale_i], nn_indices);
00211       bool is_max_point = true, is_min_point = true;
00212       for (std::vector<int>::iterator nn_it = nn_indices.begin (); nn_it != nn_indices.end (); ++nn_it)
00213         if (F_scales_[scale_i][point_i] < F_scales_[scale_i][*nn_it])
00214           is_max_point = false;
00215         else
00216           is_min_point = false;
00217 
00218       is_min_scale[point_i] = is_min_point;
00219       is_max_scale[point_i] = is_max_point;
00220     }
00221 
00222     is_min[scale_i] = is_min_scale;
00223     is_max[scale_i] = is_max_scale;
00224   }
00225 
00226   // look for points that are min/max over three consecutive scales
00227   for (size_t scale_i = 1; scale_i < scale_values_.size () - 1; ++scale_i)
00228   {
00229     for (size_t point_i = 0; point_i < input_->points.size (); ++point_i)
00230       if ((is_min[scale_i - 1][point_i] && is_min[scale_i][point_i] && is_min[scale_i + 1][point_i]) ||
00231           (is_max[scale_i - 1][point_i] && is_max[scale_i][point_i] && is_max[scale_i + 1][point_i]))
00232         {
00233         // add the point to the result vector
00234         IndicesPtr region (new std::vector<int>);
00235         region->push_back (static_cast<int> (point_i));
00236 
00237         // and also add its scale-sized geodesic neighborhood
00238         std::vector<int> nn_indices;
00239         geodesicFixedRadiusSearch (point_i, scale_values_[scale_i], nn_indices);
00240         region->insert (region->end (), nn_indices.begin (), nn_indices.end ());
00241         rois.push_back (region);
00242       }
00243   }
00244 }
00245 
00246 
00247 #define PCL_INSTANTIATE_StatisticalMultiscaleInterestRegionExtraction(T) template class PCL_EXPORTS pcl::StatisticalMultiscaleInterestRegionExtraction<T>;
00248 
00249 #endif /* PCL_FEATURES_IMPL_STATISTICAL_MULTISCALE_INTEREST_REGION_EXTRACTION_H_ */
00250 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:18:02