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  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  * $Id$
00038  *
00039  */
00040 
00041 #ifndef PCL_FEATURES_IMPL_INTENSITY_GRADIENT_H_
00042 #define PCL_FEATURES_IMPL_INTENSITY_GRADIENT_H_
00043 
00044 #include <pcl/features/intensity_gradient.h>
00045 
00047 template <typename PointInT, typename PointNT, typename PointOutT, typename IntensitySelectorT> void
00048 pcl::IntensityGradientEstimation <PointInT, PointNT, PointOutT, IntensitySelectorT>::computePointIntensityGradient (
00049   const pcl::PointCloud <PointInT> &cloud, const std::vector <int> &indices,
00050   const Eigen::Vector3f &point, float mean_intensity, const Eigen::Vector3f &normal, Eigen::Vector3f &gradient)
00051 {
00052   if (indices.size () < 3)
00053   {
00054     gradient[0] = gradient[1] = gradient[2] = std::numeric_limits<float>::quiet_NaN ();
00055     return;
00056   }
00057 
00058   Eigen::Matrix3f A = Eigen::Matrix3f::Zero ();
00059   Eigen::Vector3f b = Eigen::Vector3f::Zero ();
00060 
00061   for (size_t i_point = 0; i_point < indices.size (); ++i_point)
00062   {
00063     PointInT p = cloud.points[indices[i_point]];
00064     if (!pcl_isfinite (p.x) ||
00065         !pcl_isfinite (p.y) ||
00066         !pcl_isfinite (p.z) ||
00067         !pcl_isfinite (intensity_ (p)))
00068       continue;
00069 
00070     p.x -= point[0];
00071     p.y -= point[1];
00072     p.z -= point[2];
00073     intensity_.demean (p, mean_intensity);
00074 
00075     A (0, 0) += p.x * p.x;
00076     A (0, 1) += p.x * p.y;
00077     A (0, 2) += p.x * p.z;
00078 
00079     A (1, 1) += p.y * p.y;
00080     A (1, 2) += p.y * p.z;
00081 
00082     A (2, 2) += p.z * p.z;
00083 
00084     b[0] += p.x * intensity_ (p);
00085     b[1] += p.y * intensity_ (p);
00086     b[2] += p.z * intensity_ (p);
00087   }
00088   // Fill in the lower triangle of A
00089   A (1, 0) = A (0, 1);
00090   A (2, 0) = A (0, 2);
00091   A (2, 1) = A (1, 2);
00092 
00093 //*
00094   Eigen::Vector3f x = A.colPivHouseholderQr ().solve (b);
00095 /*/
00096 
00097   Eigen::Vector3f eigen_values;
00098   Eigen::Matrix3f eigen_vectors;
00099   eigen33 (A, eigen_vectors, eigen_values);
00100 
00101   b = eigen_vectors.transpose () * b;
00102 
00103   if ( eigen_values (0) != 0)
00104     b (0) /= eigen_values (0);
00105   else
00106     b (0) = 0;
00107 
00108   if ( eigen_values (1) != 0)
00109     b (1) /= eigen_values (1);
00110   else
00111     b (1) = 0;
00112 
00113   if ( eigen_values (2) != 0)
00114     b (2) /= eigen_values (2);
00115   else
00116     b (2) = 0;
00117 
00118 
00119   Eigen::Vector3f x = eigen_vectors * b;
00120 
00121 //  if (A.col (0).squaredNorm () != 0)
00122 //    x [0] /= A.col (0).squaredNorm ();
00123 //  b -= x [0] * A.col (0);
00124 //
00125 //
00126 //  if (A.col (1).squaredNorm ()  != 0)
00127 //    x [1] /= A.col (1).squaredNorm ();
00128 //  b -= x[1] * A.col (1);
00129 //
00130 //  x [2] = b.dot (A.col (2));
00131 //  if (A.col (2).squaredNorm () != 0)
00132 //    x[2] /= A.col (2).squaredNorm ();
00133   // Fit a hyperplane to the data
00134 
00135 //*/
00136 //  std::cout << A << "\n*\n" << bb << "\n=\n" << x << "\nvs.\n" << x2 << "\n\n";
00137 //  std::cout << A * x << "\nvs.\n" << A * x2 << "\n\n------\n";
00138   // Project the gradient vector, x, onto the tangent plane
00139   gradient = (Eigen::Matrix3f::Identity () - normal*normal.transpose ()) * x;
00140 }
00141 
00143 template <typename PointInT, typename PointNT, typename PointOutT, typename IntensitySelectorT> void
00144 pcl::IntensityGradientEstimation<PointInT, PointNT, PointOutT, IntensitySelectorT>::computeFeature (PointCloudOut &output)
00145 {
00146   // Allocate enough space to hold the results
00147   // \note This resize is irrelevant for a radiusSearch ().
00148   std::vector<int> nn_indices (k_);
00149   std::vector<float> nn_dists (k_);
00150   output.is_dense = true;
00151 
00152   // If the data is dense, we don't need to check for NaN
00153   if (surface_->is_dense)
00154   {
00155 #ifdef _OPENMP
00156 #pragma omp parallel for shared (output) private (nn_indices, nn_dists) num_threads(threads_)
00157 #endif
00158     // Iterating over the entire index vector
00159     for (int idx = 0; idx < static_cast<int> (indices_->size ()); ++idx)
00160     {
00161       PointOutT &p_out = output.points[idx];
00162 
00163       if (!this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists))
00164       {
00165         p_out.gradient[0] = p_out.gradient[1] = p_out.gradient[2] = std::numeric_limits<float>::quiet_NaN ();
00166         output.is_dense = false;
00167         continue;
00168       }
00169 
00170       Eigen::Vector3f centroid;
00171       float mean_intensity = 0;
00172       // Initialize to 0
00173       centroid.setZero ();
00174       for (size_t i = 0; i < nn_indices.size (); ++i)
00175       {
00176         centroid += surface_->points[nn_indices[i]].getVector3fMap ();
00177         mean_intensity += intensity_ (surface_->points[nn_indices[i]]);
00178       }
00179       centroid /= static_cast<float> (nn_indices.size ());
00180       mean_intensity /= static_cast<float> (nn_indices.size ());
00181 
00182       Eigen::Vector3f normal = Eigen::Vector3f::Map (normals_->points[(*indices_) [idx]].normal);
00183       Eigen::Vector3f gradient;
00184       computePointIntensityGradient (*surface_, nn_indices, centroid, mean_intensity, normal, gradient);
00185 
00186       p_out.gradient[0] = gradient[0];
00187       p_out.gradient[1] = gradient[1];
00188       p_out.gradient[2] = gradient[2];
00189     }
00190   }
00191   else
00192   {
00193 #ifdef _OPENMP
00194 #pragma omp parallel for shared (output) private (nn_indices, nn_dists) num_threads(threads_)
00195 #endif
00196     // Iterating over the entire index vector
00197     for (int idx = 0; idx < static_cast<int> (indices_->size ()); ++idx)
00198     {
00199       PointOutT &p_out = output.points[idx];
00200       if (!isFinite ((*surface_) [(*indices_)[idx]]) ||
00201           !this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists))
00202       {
00203         p_out.gradient[0] = p_out.gradient[1] = p_out.gradient[2] = std::numeric_limits<float>::quiet_NaN ();
00204         output.is_dense = false;
00205         continue;
00206       }
00207       Eigen::Vector3f centroid;
00208       float mean_intensity = 0;
00209       // Initialize to 0
00210       centroid.setZero ();
00211       unsigned cp = 0;
00212       for (size_t i = 0; i < nn_indices.size (); ++i)
00213       {
00214         // Check if the point is invalid
00215         if (!isFinite ((*surface_) [nn_indices[i]]))
00216           continue;
00217 
00218         centroid += surface_->points [nn_indices[i]].getVector3fMap ();
00219         mean_intensity += intensity_ (surface_->points [nn_indices[i]]);
00220         ++cp;
00221       }
00222       centroid /= static_cast<float> (cp);
00223       mean_intensity /= static_cast<float> (cp);
00224       Eigen::Vector3f normal = Eigen::Vector3f::Map (normals_->points[(*indices_) [idx]].normal);
00225       Eigen::Vector3f gradient;
00226       computePointIntensityGradient (*surface_, nn_indices, centroid, mean_intensity, normal, gradient);
00227 
00228       p_out.gradient[0] = gradient[0];
00229       p_out.gradient[1] = gradient[1];
00230       p_out.gradient[2] = gradient[2];
00231     }
00232   }
00233 }
00234 
00235 #define PCL_INSTANTIATE_IntensityGradientEstimation(InT,NT,OutT) template class PCL_EXPORTS pcl::IntensityGradientEstimation<InT,NT,OutT>;
00236 
00237 #endif    // PCL_FEATURES_IMPL_INTENSITY_GRADIENT_H_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:25:02