Go to the documentation of this file.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 #include "pcl/point_types.h"
00041 #include "pcl/impl/instantiate.hpp"
00042 #include "pcl/recognition/cg/hough_3d.h"
00043 #include "pcl/recognition/impl/cg/hough_3d.hpp"
00044 
00045 PCL_INSTANTIATE_PRODUCT(Hough3DGrouping, ((pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGB)(pcl::PointXYZRGBA))
00046                                          ((pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGB)(pcl::PointXYZRGBA))
00047                                          ((pcl::ReferenceFrame))((pcl::ReferenceFrame)))
00048 
00049 
00050 pcl::recognition::HoughSpace3D::HoughSpace3D (const Eigen::Vector3d &min_coord, const Eigen::Vector3d &bin_size, const Eigen::Vector3d &max_coord)
00051 {
00052   min_coord_ = min_coord;
00053   bin_size_ = bin_size;
00054 
00055   for (int i = 0; i < 3; ++i)
00056   {
00057     bin_count_[i] = static_cast<int> (ceil ((max_coord[i] - min_coord_[i]) / bin_size_[i]));
00058   }
00059 
00060   partial_bin_products_[0] = 1;
00061   for (int i=1; i<=3; ++i)
00062     partial_bin_products_[i] = bin_count_[i-1]*partial_bin_products_[i-1];
00063 
00064   total_bins_count_ = partial_bin_products_[3];
00065 
00066   hough_space_.clear ();
00067   hough_space_.resize (total_bins_count_, 0.0);
00068 }
00069 
00071 void
00072 pcl::recognition::HoughSpace3D::reset ()
00073 {
00074   hough_space_.clear ();
00075   hough_space_.resize (total_bins_count_, 0.0);
00076 
00077   voter_ids_.clear ();
00078 }
00079 
00081 int
00082 pcl::recognition::HoughSpace3D::vote (const Eigen::Vector3d &single_vote_coord, double weight, int voter_id)
00083 {
00084   int index = 0;
00085 
00086   for (int i=0; i<3; ++i)
00087   {
00088     int currentBin = static_cast<int> (floor ((single_vote_coord[i] - min_coord_[i])/bin_size_[i]));
00089     if (currentBin < 0 || currentBin >= bin_count_[i])
00090     {
00091       
00092       
00093       return -1;
00094     }
00095 
00096     index += partial_bin_products_[i] * currentBin;
00097   }
00098 
00099   hough_space_[index] += weight;
00100   voter_ids_[index].push_back (voter_id);
00101 
00102   return (index);
00103 }
00104 
00106 int
00107 pcl::recognition::HoughSpace3D::voteInt (const Eigen::Vector3d &single_vote_coord, double weight, int voter_id)
00108 {
00109   int central_bin_index = 0;
00110 
00111   const int n_neigh = 27; 
00112 
00113   Eigen::Vector3i central_bin_coord;
00114   Eigen::Vector3f bin_centroid;
00115   Eigen::Vector3f central_bin_weight;
00116   Eigen::Vector3i interp_bin;
00117   std::vector<float> interp_weight (n_neigh);
00118 
00119   for (int n = 0; n < n_neigh; ++n)
00120     interp_weight[n] = 1.0;
00121 
00122   for (int d = 0; d < 3; ++d)
00123   {
00124     
00125     central_bin_coord[d] = static_cast<int> (floor ((single_vote_coord[d] - min_coord_[d]) / bin_size_[d]));
00126     if (central_bin_coord[d] < 0 || central_bin_coord[d] >= bin_count_[d])
00127     {
00128       
00129       
00130       return -1;
00131     }
00132 
00133     central_bin_index += partial_bin_products_[d] * central_bin_coord[d];
00134 
00135     
00136     bin_centroid[d] = static_cast<float> ((2 * static_cast<double> (central_bin_coord[d]) * bin_size_[d] + bin_size_[d]) / 2.0 );
00137 
00138     
00139     central_bin_weight[d] = static_cast<float> (1 - (fabs (single_vote_coord[d] - min_coord_[d] - bin_centroid[d]) / bin_size_[d] ) );
00140 
00141     
00142     if ((single_vote_coord[d] - min_coord_[d]) < bin_centroid[d])
00143     {
00144       interp_bin[d] = central_bin_coord[d] - 1;
00145     }
00146     else if ((single_vote_coord[d] - min_coord_[d]) > bin_centroid[d])
00147     {
00148       interp_bin[d] = central_bin_coord[d] + 1;
00149     }
00150     else
00151     {
00152       interp_bin[d] = central_bin_coord[d]; 
00153     }
00154   }
00155 
00156   
00157   
00158   for (int n = 0; n < n_neigh; ++n)
00159   {
00160     int final_bin_index = 0;
00161     int exp = 1;
00162     int curr_neigh_index = 0;
00163     bool invalid = false;
00164 
00165     for (int d = 0; d < 3; ++d)
00166     {
00167       curr_neigh_index = central_bin_coord[d] + ( n % (exp*3) ) / exp - 1; 
00168       if (curr_neigh_index >= 0 && curr_neigh_index <= bin_count_[d]-1)
00169       {
00170         
00171         if(curr_neigh_index == interp_bin[d])
00172         {
00173           interp_weight[n] *= 1-central_bin_weight[d];
00174         }
00175         else if(curr_neigh_index == central_bin_coord[d])
00176         {
00177           interp_weight[n] *= central_bin_weight[d];
00178         }
00179         else
00180         {
00181           invalid = true;
00182           break;
00183         }
00184 
00185         final_bin_index += curr_neigh_index * partial_bin_products_[d];
00186       }
00187       else
00188       {
00189         invalid = true;
00190         break;
00191       }
00192       exp *= 3;
00193     }
00194 
00195     if (!invalid)
00196     {
00197       hough_space_[final_bin_index] += weight * interp_weight[n];
00198       voter_ids_[final_bin_index].push_back (voter_id);
00199     }
00200   }
00201 
00202   return (central_bin_index);
00203 }
00204 
00206 double
00207 pcl::recognition::HoughSpace3D::findMaxima (double min_threshold, std::vector<double> &maxima_values, std::vector<std::vector<int> > &maxima_voter_ids)
00208 {
00209   
00210   if (min_threshold < 0)
00211   {
00212     double hough_maximum = std::numeric_limits<double>::min ();
00213     for (int i = 0; i < total_bins_count_; ++i)
00214     {
00215       if (hough_space_[i] > hough_maximum)
00216       {
00217         hough_maximum = hough_space_[i];
00218       }
00219     }
00220 
00221     min_threshold = min_threshold >= -1 ? -min_threshold * hough_maximum : hough_maximum;
00222   }
00223 
00224   maxima_voter_ids.clear ();
00225   maxima_values.clear ();
00226 
00227   double indexes[3];
00228 
00229   
00230 
00231   for (int i=0; i < total_bins_count_; ++i)
00232   {
00233     
00234     
00235     
00236     
00237     if (hough_space_[i] < min_threshold)
00238       continue;
00239 
00240     
00241     bool is_maximum = true;
00242     int moduled_index = i;
00243 
00244     for (int k = 2; k >= 0; --k){
00245 
00246       moduled_index = moduled_index % partial_bin_products_[k+1];
00247       indexes[k] = moduled_index / partial_bin_products_[k];
00248 
00249       if (indexes[k] > 0 && hough_space_[i] < hough_space_[i-partial_bin_products_[k]])
00250       {
00251         is_maximum = false;
00252         break;
00253       }
00254       if (indexes[k] < bin_count_[k]-1 && hough_space_[i] < hough_space_[i+partial_bin_products_[k]])
00255       {
00256         is_maximum = false;
00257         break;
00258       }
00259     }
00260 
00261     if (is_maximum)
00262     {
00263       maxima_values.push_back (hough_space_[i]);
00264       maxima_voter_ids.push_back ( voter_ids_[i] );
00265     }
00266   }
00267 
00268   return (min_threshold);
00269 }