harris_keypoint3D.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  */
00037 
00038 #ifndef PCL_HARRIS_KEYPOINT_3D_IMPL_H_
00039 #define PCL_HARRIS_KEYPOINT_3D_IMPL_H_
00040 
00041 #include <pcl/keypoints/harris_keypoint3D.h>
00042 #include <pcl/common/io.h>
00043 #include <pcl/filters/passthrough.h>
00044 #include <pcl/filters/extract_indices.h>
00045 #include <pcl/features/normal_3d.h>
00046 #include <pcl/features/integral_image_normal.h>
00047 #include <pcl/common/time.h>
00048 #include <pcl/common/centroid.h>
00049 #ifdef __SSE__
00050 #include <xmmintrin.h>
00051 #endif
00052 
00054 template <typename PointInT, typename PointOutT, typename NormalT> void
00055 pcl::HarrisKeypoint3D<PointInT, PointOutT, NormalT>::setMethod (ResponseMethod method)
00056 {
00057   method_ = method;
00058 }
00059 
00061 template <typename PointInT, typename PointOutT, typename NormalT> void
00062 pcl::HarrisKeypoint3D<PointInT, PointOutT, NormalT>::setThreshold (float threshold)
00063 {
00064   threshold_= threshold;
00065 }
00066 
00068 template <typename PointInT, typename PointOutT, typename NormalT> void
00069 pcl::HarrisKeypoint3D<PointInT, PointOutT, NormalT>::setRadius (float radius)
00070 {
00071   search_radius_ = radius;
00072 }
00073 
00075 template <typename PointInT, typename PointOutT, typename NormalT> void
00076 pcl::HarrisKeypoint3D<PointInT, PointOutT, NormalT>::setRefine (bool do_refine)
00077 {
00078   refine_ = do_refine;
00079 }
00080 
00082 template <typename PointInT, typename PointOutT, typename NormalT> void
00083 pcl::HarrisKeypoint3D<PointInT, PointOutT, NormalT>::setNonMaxSupression (bool nonmax)
00084 {
00085   nonmax_ = nonmax;
00086 }
00087 
00089 template <typename PointInT, typename PointOutT, typename NormalT> void
00090 pcl::HarrisKeypoint3D<PointInT, PointOutT, NormalT>::setNormals (const PointCloudNPtr &normals)
00091 {
00092   normals_.reset (normals.get ());
00093 }
00094 
00096 template <typename PointInT, typename PointOutT, typename NormalT> void
00097 pcl::HarrisKeypoint3D<PointInT, PointOutT, NormalT>::calculateNormalCovar (const std::vector<int>& neighbors, float* coefficients) const
00098 {
00099   unsigned count = 0;
00100   // indices        0   1   2   3   4   5   6   7
00101   // coefficients: xx  xy  xz  ??  yx  yy  yz  ??
00102 #ifdef __SSE__
00103   // accumulator for xx, xy, xz
00104   __m128 vec1 = _mm_setzero_ps();
00105   // accumulator for yy, yz, zz
00106   __m128 vec2 = _mm_setzero_ps();
00107 
00108   __m128 norm1;
00109 
00110   __m128 norm2;
00111 
00112   float zz = 0;
00113 
00114   for (std::vector<int>::const_iterator iIt = neighbors.begin(); iIt != neighbors.end(); ++iIt)
00115   {
00116     if (pcl_isfinite (normals_->points[*iIt].normal_x))
00117     {
00118       // nx, ny, nz, h
00119       norm1 = _mm_load_ps (&(normals_->points[*iIt].normal_x));
00120 
00121       // nx, nx, nx, nx
00122       norm2 = _mm_set1_ps (normals_->points[*iIt].normal_x);
00123 
00124       // nx * nx, nx * ny, nx * nz, nx * h
00125       norm2 = _mm_mul_ps (norm1, norm2);
00126 
00127       // accumulate
00128       vec1 = _mm_add_ps (vec1, norm2);
00129 
00130       // ny, ny, ny, ny
00131       norm2 = _mm_set1_ps (normals_->points[*iIt].normal_y);
00132 
00133       // ny * nx, ny * ny, ny * nz, ny * h
00134       norm2 = _mm_mul_ps (norm1, norm2);
00135 
00136       // accumulate
00137       vec2 = _mm_add_ps (vec2, norm2);
00138 
00139       zz += normals_->points[*iIt].normal_z * normals_->points[*iIt].normal_z;
00140       ++count;
00141     }
00142   }
00143   if (count > 0)
00144   {
00145     norm2 = _mm_set1_ps (float(count));
00146     vec1 = _mm_div_ps (vec1, norm2);
00147     vec2 = _mm_div_ps (vec2, norm2);
00148     _mm_store_ps (coefficients, vec1);
00149     _mm_store_ps (coefficients + 4, vec2);
00150     coefficients [7] = zz / float(count);
00151   }
00152   else
00153     memset (coefficients, 0, sizeof (float) * 8);
00154 #else
00155   memset (coefficients, 0, sizeof (float) * 8);
00156   for (std::vector<int>::const_iterator iIt = neighbors.begin(); iIt != neighbors.end(); ++iIt)
00157   {
00158     if (pcl_isfinite (normals_->points[*iIt].normal_x))
00159     {
00160       coefficients[0] += normals_->points[*iIt].normal_x * normals_->points[*iIt].normal_x;
00161       coefficients[1] += normals_->points[*iIt].normal_x * normals_->points[*iIt].normal_y;
00162       coefficients[2] += normals_->points[*iIt].normal_x * normals_->points[*iIt].normal_z;
00163 
00164       coefficients[5] += normals_->points[*iIt].normal_y * normals_->points[*iIt].normal_y;
00165       coefficients[6] += normals_->points[*iIt].normal_y * normals_->points[*iIt].normal_z;
00166       coefficients[7] += normals_->points[*iIt].normal_z * normals_->points[*iIt].normal_z;
00167 
00168       ++count;
00169     }
00170   }
00171   if (count > 0)
00172   {
00173     float norm = 1.0 / float (count);
00174     coefficients[0] *= norm;
00175     coefficients[1] *= norm;
00176     coefficients[2] *= norm;
00177     coefficients[5] *= norm;
00178     coefficients[6] *= norm;
00179     coefficients[7] *= norm;
00180   }
00181 #endif
00182 }
00183 
00185 template <typename PointInT, typename PointOutT, typename NormalT> bool
00186 pcl::HarrisKeypoint3D<PointInT, PointOutT, NormalT>::initCompute ()
00187 {
00188   if (!Keypoint<PointInT, PointOutT>::initCompute ())
00189   {
00190     PCL_ERROR ("[pcl::%s::initCompute] init failed!\n", name_.c_str ());
00191     return (false);
00192   }
00193 
00194   if (method_ < 1 || method_ > 5)
00195   {
00196     PCL_ERROR ("[pcl::%s::initCompute] method (%d) must be in [1..5]!\n", name_.c_str (), method_);
00197     return (false);
00198   }
00199 
00200   if (normals_->empty ())
00201   {
00202     normals_->reserve (surface_->size ());
00203     if (input_->height == 1 ) // not organized
00204     {
00205       pcl::NormalEstimation<PointInT, NormalT> normal_estimation;
00206       normal_estimation.setInputCloud(surface_);
00207       normal_estimation.setRadiusSearch(search_radius_);
00208       normal_estimation.compute (*normals_);
00209     }
00210     else
00211     {
00212       IntegralImageNormalEstimation<PointInT, NormalT> normal_estimation;
00213       normal_estimation.setNormalEstimationMethod (pcl::IntegralImageNormalEstimation<PointInT, NormalT>::SIMPLE_3D_GRADIENT);
00214       normal_estimation.setInputCloud(surface_);
00215       normal_estimation.setNormalSmoothingSize (5.0);
00216       normal_estimation.compute (*normals_);
00217     }
00218   }
00219   return (true);
00220 }
00221 
00223 template <typename PointInT, typename PointOutT, typename NormalT> void
00224 pcl::HarrisKeypoint3D<PointInT, PointOutT, NormalT>::detectKeypoints (PointCloudOut &output)
00225 {
00226   boost::shared_ptr<pcl::PointCloud<PointOutT> > response (new pcl::PointCloud<PointOutT> ());
00227 
00228   response->points.reserve (input_->points.size());
00229 
00230   switch (method_)
00231   {
00232     case HARRIS:
00233       responseHarris(*response);
00234       break;
00235     case NOBLE:
00236       responseNoble(*response);
00237       break;
00238     case LOWE:
00239       responseLowe(*response);
00240       break;
00241     case CURVATURE:
00242       responseCurvature(*response);
00243       break;
00244     case TOMASI:
00245       responseTomasi(*response);
00246       break;
00247   }
00248 
00249   if (!nonmax_)
00250     output = *response;
00251   else
00252   {
00253     output.points.clear ();
00254     output.points.reserve (response->points.size());
00255 
00256 #if defined (HAVE_OPENMP) && (defined(_WIN32) || ((__GNUC__ > 4) && (__GNUC_MINOR__ > 2)))
00257 #pragma omp parallel for shared (output) num_threads(threads_)   
00258 #endif
00259     for (int idx = 0; idx < static_cast<int> (response->points.size ()); ++idx)
00260     {
00261       if (!isFinite (response->points[idx]) || response->points[idx].intensity < threshold_)
00262         continue;
00263                   std::vector<int> nn_indices;
00264                   std::vector<float> nn_dists;
00265       tree_->radiusSearch (idx, search_radius_, nn_indices, nn_dists);
00266       bool is_maxima = true;
00267       for (std::vector<int>::const_iterator iIt = nn_indices.begin(); iIt != nn_indices.end(); ++iIt)
00268       {
00269         if (response->points[idx].intensity < response->points[*iIt].intensity)
00270         {
00271           is_maxima = false;
00272           break;
00273         }
00274       }
00275       if (is_maxima)
00276 #if defined (HAVE_OPENMP) && (defined(_WIN32) || ((__GNUC__ > 4) && (__GNUC_MINOR__ > 2)))        
00277 #pragma omp critical
00278 #endif
00279         output.points.push_back (response->points[idx]);
00280     }
00281 
00282     if (refine_)
00283       refineCorners (output);
00284 
00285     output.height = 1;
00286     output.width = static_cast<uint32_t> (output.points.size());
00287   }
00288 
00289   // we don not change the denseness
00290   output.is_dense = input_->is_dense;
00291 }
00292 
00294 template <typename PointInT, typename PointOutT, typename NormalT> void
00295 pcl::HarrisKeypoint3D<PointInT, PointOutT, NormalT>::responseHarris (PointCloudOut &output) const
00296 {
00297   PCL_ALIGN (16) float covar [8];
00298   output.resize (input_->size ());
00299 #if defined (HAVE_OPENMP) && (defined(_WIN32) || ((__GNUC__ > 4) && (__GNUC_MINOR__ > 2)))
00300   #pragma omp parallel for shared (output) private (covar) num_threads(threads_)
00301 #endif
00302   for (int pIdx = 0; pIdx < static_cast<int> (input_->size ()); ++pIdx)
00303   {
00304     const PointInT& pointIn = input_->points [pIdx];
00305     output [pIdx].intensity = 0.0; //std::numeric_limits<float>::quiet_NaN ();
00306     if (isFinite (pointIn))
00307     {
00308                         std::vector<int> nn_indices;
00309                         std::vector<float> nn_dists;
00310       tree_->radiusSearch (pointIn, search_radius_, nn_indices, nn_dists);
00311       calculateNormalCovar (nn_indices, covar);
00312 
00313       float trace = covar [0] + covar [5] + covar [7];
00314       if (trace != 0)
00315       {
00316         float det = covar [0] * covar [5] * covar [7] + 2.0f * covar [1] * covar [2] * covar [6]
00317                   - covar [2] * covar [2] * covar [5]
00318                   - covar [1] * covar [1] * covar [7]
00319                   - covar [6] * covar [6] * covar [0];
00320 
00321         output [pIdx].intensity = 0.04f + det - 0.04f * trace * trace;
00322       }
00323     }
00324     output [pIdx].x = pointIn.x;
00325     output [pIdx].y = pointIn.y;
00326     output [pIdx].z = pointIn.z;
00327   }
00328   output.height = input_->height;
00329   output.width = input_->width;
00330 }
00331 
00333 template <typename PointInT, typename PointOutT, typename NormalT> void
00334 pcl::HarrisKeypoint3D<PointInT, PointOutT, NormalT>::responseNoble (PointCloudOut &output) const
00335 {
00336   PCL_ALIGN (16) float covar [8];
00337   output.resize (input_->size ());
00338 #if defined (HAVE_OPENMP) && (defined(_WIN32) || ((__GNUC__ > 4) && (__GNUC_MINOR__ > 2)))
00339   #pragma omp parallel for shared (output) private (covar) num_threads(threads_)
00340 #endif
00341   for (int pIdx = 0; pIdx < static_cast<int> (input_->size ()); ++pIdx)
00342   {
00343     const PointInT& pointIn = input_->points [pIdx];
00344     output [pIdx].intensity = 0.0;
00345     if (isFinite (pointIn))
00346     {
00347                         std::vector<int> nn_indices;
00348                         std::vector<float> nn_dists;
00349       tree_->radiusSearch (pointIn, search_radius_, nn_indices, nn_dists);
00350       calculateNormalCovar (nn_indices, covar);
00351       float trace = covar [0] + covar [5] + covar [7];
00352       if (trace != 0)
00353       {
00354         float det = covar [0] * covar [5] * covar [7] + 2.0f * covar [1] * covar [2] * covar [6]
00355                   - covar [2] * covar [2] * covar [5]
00356                   - covar [1] * covar [1] * covar [7]
00357                   - covar [6] * covar [6] * covar [0];
00358 
00359         output [pIdx].intensity = det / trace;
00360       }
00361     }
00362     output [pIdx].x = pointIn.x;
00363     output [pIdx].y = pointIn.y;
00364     output [pIdx].z = pointIn.z;
00365   }
00366   output.height = input_->height;
00367   output.width = input_->width;
00368 }
00369 
00371 template <typename PointInT, typename PointOutT, typename NormalT> void
00372 pcl::HarrisKeypoint3D<PointInT, PointOutT, NormalT>::responseLowe (PointCloudOut &output) const
00373 {
00374   PCL_ALIGN (16) float covar [8];
00375   output.resize (input_->size ());
00376 #if defined (HAVE_OPENMP) && (defined(_WIN32) || ((__GNUC__ > 4) && (__GNUC_MINOR__ > 2)))
00377   #pragma omp parallel for shared (output) private (covar) num_threads(threads_)
00378 #endif
00379   for (int pIdx = 0; pIdx < static_cast<int> (input_->size ()); ++pIdx)
00380   {
00381     const PointInT& pointIn = input_->points [pIdx];
00382     output [pIdx].intensity = 0.0;
00383     if (isFinite (pointIn))
00384     {
00385                         std::vector<int> nn_indices;
00386                         std::vector<float> nn_dists;
00387       tree_->radiusSearch (pointIn, search_radius_, nn_indices, nn_dists);
00388       calculateNormalCovar (nn_indices, covar);
00389       float trace = covar [0] + covar [5] + covar [7];
00390       if (trace != 0)
00391       {
00392         float det = covar [0] * covar [5] * covar [7] + 2.0f * covar [1] * covar [2] * covar [6]
00393                   - covar [2] * covar [2] * covar [5]
00394                   - covar [1] * covar [1] * covar [7]
00395                   - covar [6] * covar [6] * covar [0];
00396 
00397         output [pIdx].intensity = det / (trace * trace);
00398       }
00399     }
00400     output [pIdx].x = pointIn.x;
00401     output [pIdx].y = pointIn.y;
00402     output [pIdx].z = pointIn.z;
00403   }
00404   output.height = input_->height;
00405   output.width = input_->width;
00406 }
00407 
00409 template <typename PointInT, typename PointOutT, typename NormalT> void
00410 pcl::HarrisKeypoint3D<PointInT, PointOutT, NormalT>::responseCurvature (PointCloudOut &output) const
00411 {
00412   PointOutT point;
00413   for (unsigned idx = 0; idx < input_->points.size(); ++idx)
00414   {
00415     point.x = input_->points[idx].x;
00416     point.y = input_->points[idx].y;
00417     point.z = input_->points[idx].z;
00418     point.intensity = normals_->points[idx].curvature;
00419     output.points.push_back(point);
00420   }
00421   // does not change the order
00422   output.height = input_->height;
00423   output.width = input_->width;
00424 }
00425 
00427 template <typename PointInT, typename PointOutT, typename NormalT> void
00428 pcl::HarrisKeypoint3D<PointInT, PointOutT, NormalT>::responseTomasi (PointCloudOut &output) const
00429 {
00430   PCL_ALIGN (16) float covar [8];
00431   Eigen::Matrix3f covariance_matrix;
00432   output.resize (input_->size ());
00433 #if defined (HAVE_OPENMP) && (defined(_WIN32) || ((__GNUC__ > 4) && (__GNUC_MINOR__ > 2)))
00434   #pragma omp parallel for shared (output) private (covar, covariance_matrix) num_threads(threads_)
00435 #endif
00436   for (int pIdx = 0; pIdx < static_cast<int> (input_->size ()); ++pIdx)
00437   {
00438     const PointInT& pointIn = input_->points [pIdx];
00439     output [pIdx].intensity = 0.0;
00440     if (isFinite (pointIn))
00441     {
00442                         std::vector<int> nn_indices;
00443                         std::vector<float> nn_dists;
00444       tree_->radiusSearch (pointIn, search_radius_, nn_indices, nn_dists);
00445       calculateNormalCovar (nn_indices, covar);
00446       float trace = covar [0] + covar [5] + covar [7];
00447       if (trace != 0)
00448       {
00449         covariance_matrix.coeffRef (0) = covar [0];
00450         covariance_matrix.coeffRef (1) = covariance_matrix.coeffRef (3) = covar [1];
00451         covariance_matrix.coeffRef (2) = covariance_matrix.coeffRef (6) = covar [2];
00452         covariance_matrix.coeffRef (4) = covar [5];
00453         covariance_matrix.coeffRef (5) = covariance_matrix.coeffRef (7) = covar [6];
00454         covariance_matrix.coeffRef (8) = covar [7];
00455 
00456         EIGEN_ALIGN16 Eigen::Vector3f eigen_values;
00457         pcl::eigen33(covariance_matrix, eigen_values);
00458         output [pIdx].intensity = eigen_values[0];
00459       }
00460     }
00461     output [pIdx].x = pointIn.x;
00462     output [pIdx].y = pointIn.y;
00463     output [pIdx].z = pointIn.z;
00464   }
00465   output.height = input_->height;
00466   output.width = input_->width;
00467 }
00468 
00470 template <typename PointInT, typename PointOutT, typename NormalT> void
00471 pcl::HarrisKeypoint3D<PointInT, PointOutT, NormalT>::refineCorners (PointCloudOut &corners) const
00472 {
00473   Eigen::Matrix3f nnT;
00474   Eigen::Matrix3f NNT;
00475   Eigen::Matrix3f NNTInv;
00476   Eigen::Vector3f NNTp;
00477   float diff;
00478   const unsigned max_iterations = 10;
00479 #if defined (HAVE_OPENMP) && (defined(_WIN32) || ((__GNUC__ > 4) && (__GNUC_MINOR__ > 2)))
00480   #pragma omp parallel for shared (corners) private (nnT, NNT, NNTInv, NNTp, diff) num_threads(threads_)
00481 #endif
00482   for (int cIdx = 0; cIdx < static_cast<int> (corners.size ()); ++cIdx)
00483   {
00484     unsigned iterations = 0;
00485     do {
00486       NNT.setZero();
00487       NNTp.setZero();
00488       PointInT corner;
00489       corner.x = corners[cIdx].x;
00490       corner.y = corners[cIdx].y;
00491       corner.z = corners[cIdx].z;
00492                         std::vector<int> nn_indices;
00493                         std::vector<float> nn_dists;
00494       tree_->radiusSearch (corner, search_radius_, nn_indices, nn_dists);
00495       for (std::vector<int>::const_iterator iIt = nn_indices.begin(); iIt != nn_indices.end(); ++iIt)
00496       {
00497         if (!pcl_isfinite (normals_->points[*iIt].normal_x))
00498           continue;
00499 
00500         nnT = normals_->points[*iIt].getNormalVector3fMap () * normals_->points[*iIt].getNormalVector3fMap ().transpose();
00501         NNT += nnT;
00502         NNTp += nnT * surface_->points[*iIt].getVector3fMap ();
00503       }
00504       if (invert3x3SymMatrix (NNT, NNTInv) != 0)
00505         corners[cIdx].getVector3fMap () = NNTInv * NNTp;
00506 
00507       diff = (corners[cIdx].getVector3fMap () - corner.getVector3fMap()).squaredNorm ();
00508     } while (diff > 1e-6 && ++iterations < max_iterations);
00509   }
00510 }
00511 
00512 #define PCL_INSTANTIATE_HarrisKeypoint3D(T,U,N) template class PCL_EXPORTS pcl::HarrisKeypoint3D<T,U,N>;
00513 #endif // #ifndef PCL_HARRIS_KEYPOINT_3D_IMPL_H_
00514 


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