principal_curvatures.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: principal_curvatures.hpp 5026 2012-03-12 02:51:44Z rusu $
00037  *
00038  */
00039 
00040 #ifndef PCL_FEATURES_IMPL_PRINCIPAL_CURVATURES_H_
00041 #define PCL_FEATURES_IMPL_PRINCIPAL_CURVATURES_H_
00042 
00043 #include <pcl/features/principal_curvatures.h>
00044 
00046 template <typename PointInT, typename PointNT, typename PointOutT> void
00047 pcl::PrincipalCurvaturesEstimation<PointInT, PointNT, PointOutT>::computePointPrincipalCurvatures (
00048       const pcl::PointCloud<PointNT> &normals, int p_idx, const std::vector<int> &indices,
00049       float &pcx, float &pcy, float &pcz, float &pc1, float &pc2)
00050 {
00051   EIGEN_ALIGN16 Eigen::Matrix3f I = Eigen::Matrix3f::Identity ();
00052   Eigen::Vector3f n_idx (normals.points[p_idx].normal[0], normals.points[p_idx].normal[1], normals.points[p_idx].normal[2]);
00053   EIGEN_ALIGN16 Eigen::Matrix3f M = I - n_idx * n_idx.transpose ();    // projection matrix (into tangent plane)
00054 
00055   // Project normals into the tangent plane
00056   Eigen::Vector3f normal;
00057   projected_normals_.resize (indices.size ());
00058   xyz_centroid_.setZero ();
00059   for (size_t idx = 0; idx < indices.size(); ++idx)
00060   {
00061     normal[0] = normals.points[indices[idx]].normal[0];
00062     normal[1] = normals.points[indices[idx]].normal[1];
00063     normal[2] = normals.points[indices[idx]].normal[2];
00064 
00065     projected_normals_[idx] = M * normal;
00066     xyz_centroid_ += projected_normals_[idx];
00067   }
00068 
00069   // Estimate the XYZ centroid
00070   xyz_centroid_ /= static_cast<float> (indices.size ());
00071 
00072   // Initialize to 0
00073   covariance_matrix_.setZero ();
00074 
00075   double demean_xy, demean_xz, demean_yz;
00076   // For each point in the cloud
00077   for (size_t idx = 0; idx < indices.size (); ++idx)
00078   {
00079     demean_ = projected_normals_[idx] - xyz_centroid_;
00080 
00081     demean_xy = demean_[0] * demean_[1];
00082     demean_xz = demean_[0] * demean_[2];
00083     demean_yz = demean_[1] * demean_[2];
00084 
00085     covariance_matrix_(0, 0) += demean_[0] * demean_[0];
00086     covariance_matrix_(0, 1) += static_cast<float> (demean_xy);
00087     covariance_matrix_(0, 2) += static_cast<float> (demean_xz);
00088 
00089     covariance_matrix_(1, 0) += static_cast<float> (demean_xy);
00090     covariance_matrix_(1, 1) += demean_[1] * demean_[1];
00091     covariance_matrix_(1, 2) += static_cast<float> (demean_yz);
00092 
00093     covariance_matrix_(2, 0) += static_cast<float> (demean_xz);
00094     covariance_matrix_(2, 1) += static_cast<float> (demean_yz);
00095     covariance_matrix_(2, 2) += demean_[2] * demean_[2];
00096   }
00097 
00098   // Extract the eigenvalues and eigenvectors
00099   pcl::eigen33 (covariance_matrix_, eigenvalues_);
00100   pcl::computeCorrespondingEigenVector (covariance_matrix_, eigenvalues_ [2], eigenvector_);
00101 
00102   pcx = eigenvector_ [0];
00103   pcy = eigenvector_ [1];
00104   pcz = eigenvector_ [2];
00105   float indices_size = 1.0f / static_cast<float> (indices.size ());
00106   pc1 = eigenvalues_ [2] * indices_size;
00107   pc2 = eigenvalues_ [1] * indices_size;
00108 }
00109 
00110 
00112 template <typename PointInT, typename PointNT, typename PointOutT> void
00113 pcl::PrincipalCurvaturesEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut &output)
00114 {
00115   // Allocate enough space to hold the results
00116   // \note This resize is irrelevant for a radiusSearch ().
00117   std::vector<int> nn_indices (k_);
00118   std::vector<float> nn_dists (k_);
00119 
00120   output.is_dense = true;
00121   // Save a few cycles by not checking every point for NaN/Inf values if the cloud is set to dense
00122   if (input_->is_dense)
00123   {
00124     // Iterating over the entire index vector
00125     for (size_t idx = 0; idx < indices_->size (); ++idx)
00126     {
00127       if (this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
00128       {
00129         output.points[idx].principal_curvature[0] = output.points[idx].principal_curvature[1] = output.points[idx].principal_curvature[2] =
00130           output.points[idx].pc1 = output.points[idx].pc2 = std::numeric_limits<float>::quiet_NaN ();
00131         output.is_dense = false;
00132         continue;
00133       }
00134 
00135       // Estimate the principal curvatures at each patch
00136       computePointPrincipalCurvatures (*normals_, (*indices_)[idx], nn_indices,
00137                                        output.points[idx].principal_curvature[0], output.points[idx].principal_curvature[1], output.points[idx].principal_curvature[2],
00138                                        output.points[idx].pc1, output.points[idx].pc2);
00139     }
00140   }
00141   else
00142   {
00143     // Iterating over the entire index vector
00144     for (size_t idx = 0; idx < indices_->size (); ++idx)
00145     {
00146       if (!isFinite ((*input_)[(*indices_)[idx]]) ||
00147           this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
00148       {
00149         output.points[idx].principal_curvature[0] = output.points[idx].principal_curvature[1] = output.points[idx].principal_curvature[2] =
00150           output.points[idx].pc1 = output.points[idx].pc2 = std::numeric_limits<float>::quiet_NaN ();
00151         output.is_dense = false;
00152         continue;
00153       }
00154 
00155       // Estimate the principal curvatures at each patch
00156       computePointPrincipalCurvatures (*normals_, (*indices_)[idx], nn_indices,
00157                                        output.points[idx].principal_curvature[0], output.points[idx].principal_curvature[1], output.points[idx].principal_curvature[2],
00158                                        output.points[idx].pc1, output.points[idx].pc2);
00159     }
00160   }
00161 }
00163 template <typename PointInT, typename PointNT> void
00164 pcl::PrincipalCurvaturesEstimation<PointInT, PointNT, Eigen::MatrixXf>::computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output)
00165 {
00166   // Resize the output dataset
00167   output.points.resize (indices_->size (), 5);
00168 
00169   // Allocate enough space to hold the results
00170   // \note This resize is irrelevant for a radiusSearch ().
00171   std::vector<int> nn_indices (k_);
00172   std::vector<float> nn_dists (k_);
00173 
00174   output.is_dense = true;
00175   // Save a few cycles by not checking every point for NaN/Inf values if the cloud is set to dense
00176   if (input_->is_dense)
00177   {
00178     // Iterating over the entire index vector
00179     for (size_t idx = 0; idx < indices_->size (); ++idx)
00180     {
00181       if (this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
00182       {
00183         output.points.row (idx).setConstant (std::numeric_limits<float>::quiet_NaN ());
00184         output.is_dense = false;
00185         continue;
00186       }
00187 
00188       // Estimate the principal curvatures at each patch
00189       this->computePointPrincipalCurvatures (*normals_, (*indices_)[idx], nn_indices,
00190                                        output.points (idx, 0), output.points (idx, 1), output.points (idx, 2),
00191                                        output.points (idx, 3), output.points (idx, 4));
00192     }
00193   }
00194   else
00195   {
00196     // Iterating over the entire index vector
00197     for (size_t idx = 0; idx < indices_->size (); ++idx)
00198     {
00199       if (!isFinite ((*input_)[(*indices_)[idx]]) ||
00200           this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
00201       {
00202         output.points.row (idx).setConstant (std::numeric_limits<float>::quiet_NaN ());
00203         output.is_dense = false;
00204         continue;
00205       }
00206 
00207       // Estimate the principal curvatures at each patch
00208       this->computePointPrincipalCurvatures (*normals_, (*indices_)[idx], nn_indices,
00209                                        output.points (idx, 0), output.points (idx, 1), output.points (idx, 2),
00210                                        output.points (idx, 3), output.points (idx, 4));
00211     }
00212   }
00213 }
00214 
00215 #define PCL_INSTANTIATE_PrincipalCurvaturesEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::PrincipalCurvaturesEstimation<T,NT,OutT>;
00216 
00217 #endif    // PCL_FEATURES_IMPL_PRINCIPAL_CURVATURES_H_


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