intensity_gradient.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: intensity_gradient.hpp 6144 2012-07-04 22:06:28Z rusu $
00037  *
00038  */
00039 
00040 #ifndef PCL_FEATURES_IMPL_INTENSITY_GRADIENT_H_
00041 #define PCL_FEATURES_IMPL_INTENSITY_GRADIENT_H_
00042 
00043 #include <pcl/features/intensity_gradient.h>
00044 
00046 template <typename PointInT, typename PointNT, typename PointOutT, typename IntensitySelectorT> void
00047 pcl::IntensityGradientEstimation <PointInT, PointNT, PointOutT, IntensitySelectorT>::computePointIntensityGradient (
00048   const pcl::PointCloud <PointInT> &cloud, const std::vector <int> &indices,
00049   const Eigen::Vector3f &point, float mean_intensity, const Eigen::Vector3f &normal, Eigen::Vector3f &gradient)
00050 {
00051   if (indices.size () < 3)
00052   {
00053     gradient[0] = gradient[1] = gradient[2] = std::numeric_limits<float>::quiet_NaN ();
00054     return;
00055   }
00056 
00057   Eigen::Matrix3f A = Eigen::Matrix3f::Zero ();
00058   Eigen::Vector3f b = Eigen::Vector3f::Zero ();
00059 
00060   for (size_t i_point = 0; i_point < indices.size (); ++i_point)
00061   {
00062     PointInT p = cloud.points[indices[i_point]];
00063     if (!pcl_isfinite (p.x) ||
00064         !pcl_isfinite (p.y) ||
00065         !pcl_isfinite (p.z) ||
00066         !pcl_isfinite (intensity_ (p)))
00067       continue;
00068 
00069     p.x -= point[0];
00070     p.y -= point[1];
00071     p.z -= point[2];
00072     intensity_.demean (p, mean_intensity);
00073 
00074     A (0, 0) += p.x * p.x;
00075     A (0, 1) += p.x * p.y;
00076     A (0, 2) += p.x * p.z;
00077 
00078     A (1, 1) += p.y * p.y;
00079     A (1, 2) += p.y * p.z;
00080 
00081     A (2, 2) += p.z * p.z;
00082 
00083     b[0] += p.x * intensity_ (p);
00084     b[1] += p.y * intensity_ (p);
00085     b[2] += p.z * intensity_ (p);
00086   }
00087   // Fill in the lower triangle of A
00088   A (1, 0) = A (0, 1);
00089   A (2, 0) = A (0, 2);
00090   A (2, 1) = A (1, 2);
00091 
00092 //*
00093   Eigen::Vector3f x = A.colPivHouseholderQr ().solve (b);
00094 /*/
00095 
00096   Eigen::Vector3f eigen_values;
00097   Eigen::Matrix3f eigen_vectors;
00098   eigen33 (A, eigen_vectors, eigen_values);
00099 
00100   b = eigen_vectors.transpose () * b;
00101 
00102   if ( eigen_values (0) != 0)
00103     b (0) /= eigen_values (0);
00104   else
00105     b (0) = 0;
00106 
00107   if ( eigen_values (1) != 0)
00108     b (1) /= eigen_values (1);
00109   else
00110     b (1) = 0;
00111 
00112   if ( eigen_values (2) != 0)
00113     b (2) /= eigen_values (2);
00114   else
00115     b (2) = 0;
00116 
00117 
00118   Eigen::Vector3f x = eigen_vectors * b;
00119 
00120 //  if (A.col (0).squaredNorm () != 0)
00121 //    x [0] /= A.col (0).squaredNorm ();
00122 //  b -= x [0] * A.col (0);
00123 //
00124 //
00125 //  if (A.col (1).squaredNorm ()  != 0)
00126 //    x [1] /= A.col (1).squaredNorm ();
00127 //  b -= x[1] * A.col (1);
00128 //
00129 //  x [2] = b.dot (A.col (2));
00130 //  if (A.col (2).squaredNorm () != 0)
00131 //    x[2] /= A.col (2).squaredNorm ();
00132   // Fit a hyperplane to the data
00133 
00134 //*/
00135 //  std::cout << A << "\n*\n" << bb << "\n=\n" << x << "\nvs.\n" << x2 << "\n\n";
00136 //  std::cout << A * x << "\nvs.\n" << A * x2 << "\n\n------\n";
00137   // Project the gradient vector, x, onto the tangent plane
00138   gradient = (Eigen::Matrix3f::Identity () - normal*normal.transpose ()) * x;
00139 }
00140 
00142 template <typename PointInT, typename PointNT, typename PointOutT, typename IntensitySelectorT> void
00143 pcl::IntensityGradientEstimation<PointInT, PointNT, PointOutT, IntensitySelectorT>::computeFeature (PointCloudOut &output)
00144 {
00145   // Allocate enough space to hold the results
00146   // \note This resize is irrelevant for a radiusSearch ().
00147   std::vector<int> nn_indices (k_);
00148   std::vector<float> nn_dists (k_);
00149   output.is_dense = true;
00150 
00151   // If the data is dense, we don't need to check for NaN
00152   if (surface_->is_dense)
00153   {
00154 #if defined (HAVE_OPENMP) && (defined(_WIN32) || ((__GNUC__ > 4) && (__GNUC_MINOR__ > 2)))
00155 #pragma omp parallel for shared (output) private (nn_indices, nn_dists) num_threads(threads_)
00156 #endif
00157     // Iterating over the entire index vector
00158     for (int idx = 0; idx < static_cast<int> (indices_->size ()); ++idx)
00159     {
00160       PointOutT &p_out = output.points[idx];
00161 
00162       if (!this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists))
00163       {
00164         p_out.gradient[0] = p_out.gradient[1] = p_out.gradient[2] = std::numeric_limits<float>::quiet_NaN ();
00165         output.is_dense = false;
00166         continue;
00167       }
00168 
00169       Eigen::Vector3f centroid;
00170       float mean_intensity = 0;
00171       // Initialize to 0
00172       centroid.setZero ();
00173       for (size_t i = 0; i < nn_indices.size (); ++i)
00174       {
00175         centroid += surface_->points[nn_indices[i]].getVector3fMap ();
00176         mean_intensity += intensity_ (surface_->points[nn_indices[i]]);
00177       }
00178       centroid /= static_cast<float> (nn_indices.size ());
00179       mean_intensity /= static_cast<float> (nn_indices.size ());
00180 
00181       Eigen::Vector3f normal = Eigen::Vector3f::Map (normals_->points[(*indices_) [idx]].normal);
00182       Eigen::Vector3f gradient;
00183       computePointIntensityGradient (*surface_, nn_indices, centroid, mean_intensity, normal, gradient);
00184 
00185       p_out.gradient[0] = gradient[0];
00186       p_out.gradient[1] = gradient[1];
00187       p_out.gradient[2] = gradient[2];
00188     }
00189   }
00190   else
00191   {
00192 #if defined (HAVE_OPENMP) && (defined(_WIN32) || ((__GNUC__ > 4) && (__GNUC_MINOR__ > 2)))
00193 #pragma omp parallel for shared (output) private (nn_indices, nn_dists) num_threads(threads_)
00194 #endif
00195     // Iterating over the entire index vector
00196     for (int idx = 0; idx < static_cast<int> (indices_->size ()); ++idx)
00197     {
00198       PointOutT &p_out = output.points[idx];
00199       if (!isFinite ((*surface_) [(*indices_)[idx]]) ||
00200           !this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists))
00201       {
00202         p_out.gradient[0] = p_out.gradient[1] = p_out.gradient[2] = std::numeric_limits<float>::quiet_NaN ();
00203         output.is_dense = false;
00204         continue;
00205       }
00206       Eigen::Vector3f centroid;
00207       float mean_intensity = 0;
00208       // Initialize to 0
00209       centroid.setZero ();
00210       unsigned cp = 0;
00211       for (size_t i = 0; i < nn_indices.size (); ++i)
00212       {
00213         // Check if the point is invalid
00214         if (!isFinite ((*surface_) [nn_indices[i]]))
00215           continue;
00216 
00217         centroid += surface_->points [nn_indices[i]].getVector3fMap ();
00218         mean_intensity += intensity_ (surface_->points [nn_indices[i]]);
00219         ++cp;
00220       }
00221       centroid /= static_cast<float> (cp);
00222       mean_intensity /= static_cast<float> (cp);
00223       Eigen::Vector3f normal = Eigen::Vector3f::Map (normals_->points[(*indices_) [idx]].normal);
00224       Eigen::Vector3f gradient;
00225       computePointIntensityGradient (*surface_, nn_indices, centroid, mean_intensity, normal, gradient);
00226 
00227       p_out.gradient[0] = gradient[0];
00228       p_out.gradient[1] = gradient[1];
00229       p_out.gradient[2] = gradient[2];
00230     }
00231   }
00232 }
00233 
00235 template <typename PointInT, typename PointNT> void
00236 pcl::IntensityGradientEstimation<PointInT, PointNT, Eigen::MatrixXf>::computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output)
00237 {
00238   // Resize the output dataset
00239   output.points.resize (indices_->size (), 3);
00240 
00241   // Allocate enough space to hold the results
00242   // \note This resize is irrelevant for a radiusSearch ().
00243   std::vector<int> nn_indices (k_);
00244   std::vector<float> nn_dists (k_);
00245 
00246   output.is_dense = true;
00247   // Iterating over the entire index vector
00248   for (size_t idx = 0; idx < indices_->size (); ++idx)
00249   {
00250     if (this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
00251     {
00252       output.points.row (idx).setConstant (std::numeric_limits<float>::quiet_NaN ());
00253       output.is_dense = false;
00254       continue;
00255     }
00256 
00257     Eigen::Vector4f centroid;
00258     compute3DCentroid (*surface_, nn_indices, centroid);
00259 
00260     float mean_intensity = 0;
00261     unsigned valid_neighbor_count = 0;
00262     for (size_t nIdx = 0; nIdx < nn_indices.size (); ++nIdx)
00263     {
00264       const PointInT& p = (*surface_)[nn_indices[nIdx]];
00265       if (!pcl_isfinite (p.intensity))
00266         continue;
00267 
00268       mean_intensity += p.intensity;
00269       ++valid_neighbor_count;
00270     }
00271 
00272     mean_intensity /= static_cast<float> (valid_neighbor_count);
00273 
00274     Eigen::Vector3f normal = Eigen::Vector3f::Map (normals_->points[idx].normal);
00275     Eigen::Vector3f gradient;
00276     this->computePointIntensityGradient (*surface_, nn_indices, centroid.head<3> (), mean_intensity, normal, gradient);
00277 
00278     output.points (idx, 0) = gradient[0];
00279     output.points (idx, 1) = gradient[1];
00280     output.points (idx, 2) = gradient[2];
00281   }
00282 }
00283 
00284 
00285 #define PCL_INSTANTIATE_IntensityGradientEstimation(InT,NT,OutT) template class PCL_EXPORTS pcl::IntensityGradientEstimation<InT,NT,OutT>;
00286 
00287 #endif    // PCL_FEATURES_IMPL_INTENSITY_GRADIENT_H_


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