Point Cloud Library (PCL)  1.4.0
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines
3dsc.hpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2011, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  *  $Id: 3dsc.hpp 3755 2011-12-31 23:45:30Z rusu $
00037  *
00038  */
00039 
00040 #ifndef PCL_FEATURES_IMPL_3DSC_HPP_
00041 #define PCL_FEATURES_IMPL_3DSC_HPP_
00042 
00043 #include <cmath>
00044 #include <pcl/features/3dsc.h>
00045 #include <pcl/common/utils.h>
00046 #include <pcl/common/geometry.h>
00047 #include <pcl/common/angles.h>
00048 
00050 template <typename PointInT, typename PointNT, typename PointOutT> bool
00051 pcl::ShapeContext3DEstimation<PointInT, PointNT, PointOutT>::initCompute ()
00052 {
00053   if (!FeatureFromNormals<PointInT, PointNT, PointOutT>::initCompute ())
00054   {
00055     PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ());
00056     return (false);
00057   }
00058 
00059   if (search_radius_< min_radius_)
00060   {
00061     PCL_ERROR ("[pcl::%s::initCompute] search_radius_ must be GREATER than min_radius_.\n", getClassName ().c_str ());
00062     return (false);
00063   }
00064 
00065   // Update descriptor length
00066   descriptor_length_ = elevation_bins_ * azimuth_bins_ * radius_bins_;
00067 
00068   // Compute radial, elevation and azimuth divisions
00069   float azimuth_interval = (float) 360 / azimuth_bins_;
00070   float elevation_interval = (float) 180 / elevation_bins_;
00071 
00072   // Reallocate divisions and volume lut
00073   radii_interval_.clear ();
00074   phi_divisions_.clear ();
00075   theta_divisions_.clear ();
00076   volume_lut_.clear ();
00077 
00078   // Fills radii interval based on formula (1) in section 2.1 of Frome's paper
00079   radii_interval_.resize (radius_bins_ + 1);
00080   for (size_t j = 0; j < radius_bins_ + 1; j++)
00081     radii_interval_[j] = exp (log (min_radius_) + (((float) j / (radius_bins_)) * log (search_radius_ / min_radius_)));
00082 
00083   // Fill theta divisions of elevation
00084   theta_divisions_.resize (elevation_bins_ + 1);
00085   for (size_t k = 0; k < elevation_bins_ + 1; k++)
00086     theta_divisions_[k] = k * elevation_interval;
00087 
00088   // Fill phi didvisions of elevation
00089   phi_divisions_.resize (azimuth_bins_ + 1);
00090   for (size_t l = 0; l < azimuth_bins_ + 1; l++)
00091     phi_divisions_[l] = l * azimuth_interval;
00092 
00093   // LookUp Table that contains the volume of all the bins
00094   // "phi" term of the volume integral
00095   // "integr_phi" has always the same value so we compute it only one time
00096   float integr_phi  = pcl::deg2rad (phi_divisions_[1]) - pcl::deg2rad (phi_divisions_[0]);
00097   // exponential to compute the cube root using pow
00098   float e = 1.0 / 3.0;
00099   // Resize volume look up table
00100   volume_lut_.resize (radius_bins_ * elevation_bins_ * azimuth_bins_);
00101   // Fill volumes look up table
00102   for (size_t j = 0; j < radius_bins_; j++)
00103   {
00104     // "r" term of the volume integral
00105     float integr_r = (radii_interval_[j+1] * radii_interval_[j+1] * radii_interval_[j+1] / 3.0) - (radii_interval_[j] * radii_interval_[j] * radii_interval_[j] / 3.0);
00106     
00107     for (size_t k = 0; k < elevation_bins_; k++)
00108     {
00109       // "theta" term of the volume integral
00110       float integr_theta = cos (pcl::deg2rad (theta_divisions_[k])) - cos (pcl::deg2rad (theta_divisions_[k+1]));
00111       // Volume
00112       float V = integr_phi * integr_theta * integr_r;
00113       // Compute cube root of the computed volume commented for performance but left 
00114       // here for clarity
00115       // float cbrt = pow(V, e);
00116       // cbrt = 1 / cbrt;
00117       
00118       for (size_t l = 0; l < azimuth_bins_; l++)
00119       {
00120         // Store in lut 1/cbrt
00121         //volume_lut_[ (l*elevation_bins_*radius_bins_) + k*radius_bins_ + j ] = cbrt;
00122         volume_lut_[(l*elevation_bins_*radius_bins_) + k*radius_bins_ + j] = 1.0 / pow (V, e);
00123       }
00124     }
00125   }
00126   return (true);
00127 }
00128 
00130 template <typename PointInT, typename PointNT, typename PointOutT> bool
00131 pcl::ShapeContext3DEstimation<PointInT, PointNT, PointOutT>::computePoint (
00132     size_t index, const pcl::PointCloud<PointNT> &normals, float rf[9], std::vector<float> &desc)
00133 {
00134   // The RF is formed as this x_axis | y_axis | normal
00135   Eigen::Map<Eigen::Vector3f> x_axis (rf);
00136   Eigen::Map<Eigen::Vector3f> y_axis (rf + 3);
00137   Eigen::Map<Eigen::Vector3f> normal (rf + 6);
00138 
00139   // Find every point within specified search_radius_
00140   std::vector<int> nn_indices;
00141   std::vector<float> nn_dists;
00142   const size_t neighb_cnt = searchForNeighbors ((*indices_)[index], search_radius_, nn_indices, nn_dists);
00143   if (neighb_cnt == 0)
00144   {
00145     for (size_t i = 0; i < desc.size (); ++i)
00146       desc[i] = std::numeric_limits<float>::quiet_NaN ();
00147 
00148     memset (rf, 0, sizeof (rf[0]) * 9);
00149     return (false);
00150   }
00151 
00152   float minDist = std::numeric_limits<float>::max ();
00153   int minIndex = -1;
00154   for (size_t i = 0; i < nn_indices.size (); i++)
00155   {
00156     if (nn_dists[i] < minDist)
00157     {
00158       minDist = nn_dists[i];
00159       minIndex = nn_indices[i];
00160     }
00161   }
00162   
00163   // Get origin point
00164   Vector3fMapConst origin = input_->points[(*indices_)[index]].getVector3fMap ();
00165   // Get origin normal
00166   // Use pre-computed normals
00167   normal = normals[minIndex].getNormalVector3fMap ();
00168 
00169   // Compute and store the RF direction
00170   x_axis[0] = rnd ();
00171   x_axis[1] = rnd ();
00172   x_axis[2] = rnd ();
00173   if (!pcl::utils::equal (normal[2], 0.0f))
00174     x_axis[2] = - (normal[0]*x_axis[0] + normal[1]*x_axis[1]) / normal[2];
00175   else if (!pcl::utils::equal (normal[1], 0.0f))
00176     x_axis[1] = - (normal[0]*x_axis[0] + normal[2]*x_axis[2]) / normal[1];
00177   else if (!pcl::utils::equal (normal[0], 0.0f))
00178     x_axis[0] = - (normal[1]*x_axis[1] + normal[2]*x_axis[2]) / normal[0];
00179 
00180   x_axis.normalize ();
00181 
00182   // Check if the computed x axis is orthogonal to the normal
00183   assert (pcl::utils::equal (x_axis[0]*normal[0] + x_axis[1]*normal[1] + x_axis[2]*normal[2], 0.0f, 1E-6f));
00184 
00185   // Store the 3rd frame vector
00186   y_axis = normal.cross (x_axis);
00187 
00188   // For each point within radius
00189   for (size_t ne = 0; ne < neighb_cnt; ne++)
00190   {
00191     if (pcl::utils::equal (nn_dists[ne], 0.0f))
00192       continue;
00193     // Get neighbours coordinates
00194     Eigen::Vector3f neighbour = surface_->points[nn_indices[ne]].getVector3fMap ();
00195 
00198     float r = sqrt (nn_dists[ne]); 
00199     
00201     Eigen::Vector3f proj;
00202     pcl::geometry::project (neighbour, origin, normal, proj);
00203     proj -= origin;
00204 
00206     proj.normalize ();
00207     
00209     Eigen::Vector3f cross = x_axis.cross (proj);
00210     float phi = pcl::rad2deg (std::atan2 (cross.norm (), x_axis.dot (proj)));
00211     phi = cross.dot (normal) < 0.f ? (360.0 - phi) : phi;
00213     Eigen::Vector3f no = neighbour - origin;
00214     no.normalize ();
00215     float theta = normal.dot (no);
00216     theta = pcl::rad2deg (acos (std::min (1.0f, std::max (-1.0f, theta))));
00217 
00218     // Bin (j, k, l)
00219     size_t j = 0;
00220     size_t k = 0;
00221     size_t l = 0;
00222 
00223     // Compute the Bin(j, k, l) coordinates of current neighbour
00224     for (size_t rad = 1; rad < radius_bins_+1; rad++) 
00225     {
00226       if (r <= radii_interval_[rad]) 
00227       {
00228         j = rad-1;
00229         break;
00230       }
00231     }
00232 
00233     for (size_t ang = 1; ang < elevation_bins_+1; ang++) 
00234     {
00235       if (theta <= theta_divisions_[ang]) 
00236       {
00237         k = ang-1;
00238         break;
00239       }
00240     }
00241 
00242     for (size_t ang = 1; ang < azimuth_bins_+1; ang++) 
00243     {
00244       if (phi <= phi_divisions_[ang]) 
00245       {
00246         l = ang-1;
00247         break;
00248       }
00249     }
00250 
00251     // Local point density = number of points in a sphere of radius "point_density_radius_" around the current neighbour
00252     std::vector<int> neighbour_indices;
00253     std::vector<float> neighbour_distances;
00254     int point_density = searchForNeighbors (*surface_, nn_indices[ne], point_density_radius_, neighbour_indices, neighbour_distances);
00255     // point_density is NOT always bigger than 0 (on error, searchForNeighbors returns 0), so we must check for that
00256     if (point_density == 0)
00257       continue;
00258 
00259     float w = (1.0f / point_density) * volume_lut_[(l*elevation_bins_*radius_bins_) + 
00260                                                   (k*radius_bins_) + 
00261                                                   j];
00262       
00263     assert (w >= 0.0);
00264     if (w == std::numeric_limits<float>::infinity ())
00265       PCL_ERROR ("Shape Context Error INF!\n");
00266     if (w != w)
00267       PCL_ERROR ("Shape Context Error IND!\n");
00269     desc[(l*elevation_bins_*radius_bins_) + (k*radius_bins_) + j] += w;
00270 
00271     assert (desc[(l*elevation_bins_*radius_bins_) + (k*radius_bins_) + j] >= 0);
00272   } // end for each neighbour
00273 
00274   // 3DSC does not define a repeatable local RF, we set it to zero to signal it to the user 
00275   memset (rf, 0, sizeof (rf[0]) * 9);
00276   return (true);
00277 }
00278 
00280 template <typename PointInT, typename PointNT, typename PointOutT> void
00281 pcl::ShapeContext3DEstimation<PointInT, PointNT, PointOutT>::shiftAlongAzimuth (
00282     size_t block_size, std::vector<float>& desc)
00283 {
00284   assert (desc.size () == descriptor_length_);
00285   // L rotations for each descriptor
00286   desc.resize (descriptor_length_ * azimuth_bins_); 
00287   // Create L azimuth rotated descriptors from reference descriptor
00288   // The descriptor_length_ first ones are the same so start at 1
00289   for (size_t l = 1; l < azimuth_bins_; l++)
00290     for (size_t bin = 0; bin < descriptor_length_; bin++)
00291       desc[(l * descriptor_length_) + bin] = desc[(l*block_size + bin) % descriptor_length_];
00292 }
00293 
00295 template <typename PointInT, typename PointNT, typename PointOutT> void
00296 pcl::ShapeContext3DEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut &output)
00297 {
00298   output.is_dense = true;
00299   // Iterate over all points and compute the descriptors
00300   for (size_t point_index = 0; point_index < indices_->size (); point_index++)
00301   {
00302     output[point_index].descriptor.resize (descriptor_length_);
00303 
00304     // If the point is not finite, set the descriptor to NaN and continue
00305     if (!isFinite ((*input_)[(*indices_)[point_index]]))
00306     {
00307       for (size_t i = 0; i < descriptor_length_; ++i)
00308         output[point_index].descriptor[i] = std::numeric_limits<float>::quiet_NaN ();
00309 
00310       memset (output[point_index].rf, 0, sizeof (output[point_index].rf[0]) * 9);
00311       output.is_dense = false;
00312       continue;
00313     }
00314  
00315     if (!computePoint (point_index, *normals_, output[point_index].rf, output[point_index].descriptor))
00316       output.is_dense = false;
00317   }
00318 }
00319 
00321 template <typename PointInT, typename PointNT> void
00322 pcl::ShapeContext3DEstimation<PointInT, PointNT, Eigen::MatrixXf>::computeFeature (
00323     pcl::PointCloud<Eigen::MatrixXf> &output)
00324 {
00325   // Resize the output dataset
00326   output.points.resize (indices_->size (), descriptor_length_ + 9);
00327 
00328   float rf[9];
00329 
00330   output.is_dense = true;
00331   // Iterate over all points and compute the descriptors
00332   for (size_t point_index = 0; point_index < indices_->size (); point_index++)
00333   {
00334     // If the point is not finite, set the descriptor to NaN and continue
00335     if (!isFinite ((*input_)[(*indices_)[point_index]]))
00336     {
00337       output.points.row (point_index).setConstant (std::numeric_limits<float>::quiet_NaN ());
00338       output.is_dense = false;
00339       continue;
00340     }
00341 
00342     std::vector<float> descriptor (descriptor_length_);
00343     if (!this->computePoint (point_index, *normals_, rf, descriptor))
00344       output.is_dense = false;
00345     for (int j = 0; j < 9; ++j)
00346       output.points (point_index, j) = rf[j];
00347     for (size_t j = 0; j < descriptor_length_; ++j)
00348       output.points (point_index, 9 + j) = descriptor[j];
00349   }
00350 }
00351 
00352 #define PCL_INSTANTIATE_ShapeContext3DEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::ShapeContext3DEstimation<T,NT,OutT>;
00353 
00354 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines