00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #ifndef PCL_FEATURES_IMPL_PRINCIPAL_CURVATURES_H_
00039 #define PCL_FEATURES_IMPL_PRINCIPAL_CURVATURES_H_
00040
00041 #include "pcl/features/principal_curvatures.h"
00042
00044 template <typename PointInT, typename PointNT, typename PointOutT> void
00045 pcl::PrincipalCurvaturesEstimation<PointInT, PointNT, PointOutT>::computePointPrincipalCurvatures (
00046 const pcl::PointCloud<PointNT> &normals, int p_idx, const std::vector<int> &indices,
00047 float &pcx, float &pcy, float &pcz, float &pc1, float &pc2)
00048 {
00049 EIGEN_ALIGN16 Eigen::Matrix3f I = Eigen::Matrix3f::Identity ();
00050 Eigen::Vector3f n_idx (normals.points[p_idx].normal[0], normals.points[p_idx].normal[1], normals.points[p_idx].normal[2]);
00051 EIGEN_ALIGN16 Eigen::Matrix3f M = I - n_idx * n_idx.transpose ();
00052
00053
00054 Eigen::Vector3f normal;
00055 projected_normals_.resize (indices.size ());
00056 xyz_centroid_.setZero ();
00057 for (size_t idx = 0; idx < indices.size(); ++idx)
00058 {
00059 normal[0] = normals.points[indices[idx]].normal[0];
00060 normal[1] = normals.points[indices[idx]].normal[1];
00061 normal[2] = normals.points[indices[idx]].normal[2];
00062
00063 projected_normals_[idx] = M * normal;
00064 xyz_centroid_ += projected_normals_[idx];
00065 }
00066
00067
00068 xyz_centroid_ /= indices.size ();
00069
00070
00071 covariance_matrix_.setZero ();
00072
00073 double demean_xy, demean_xz, demean_yz;
00074
00075 for (size_t idx = 0; idx < indices.size (); ++idx)
00076 {
00077 demean_ = projected_normals_[idx] - xyz_centroid_;
00078
00079 demean_xy = demean_[0] * demean_[1];
00080 demean_xz = demean_[0] * demean_[2];
00081 demean_yz = demean_[1] * demean_[2];
00082
00083 covariance_matrix_(0, 0) += demean_[0] * demean_[0];
00084 covariance_matrix_(0, 1) += demean_xy;
00085 covariance_matrix_(0, 2) += demean_xz;
00086
00087 covariance_matrix_(1, 0) += demean_xy;
00088 covariance_matrix_(1, 1) += demean_[1] * demean_[1];
00089 covariance_matrix_(1, 2) += demean_yz;
00090
00091 covariance_matrix_(2, 0) += demean_xz;
00092 covariance_matrix_(2, 1) += demean_yz;
00093 covariance_matrix_(2, 2) += demean_[2] * demean_[2];
00094 }
00095
00096
00097
00098
00099
00100 pcl::eigen33 (covariance_matrix_, eigenvectors_, eigenvalues_);
00101
00102 pcx = eigenvectors_ (0, 2);
00103 pcy = eigenvectors_ (1, 2);
00104 pcz = eigenvectors_ (2, 2);
00105 pc1 = eigenvalues_ (2);
00106 pc2 = eigenvalues_ (1);
00107 }
00108
00109
00111 template <typename PointInT, typename PointNT, typename PointOutT> void
00112 pcl::PrincipalCurvaturesEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut &output)
00113 {
00114
00115 if (!normals_)
00116 {
00117 ROS_ERROR ("[pcl::%s::computeFeature] No input dataset containing normals was given!", getClassName ().c_str ());
00118 output.width = output.height = 0;
00119 output.points.clear ();
00120 return;
00121 }
00122 if (normals_->points.size () != surface_->points.size ())
00123 {
00124 ROS_ERROR ("[pcl::%s::computeFeature] The number of points in the input dataset (%zu) differs from the number of points in the dataset containing the normals (%zu)!",
00125 getClassName ().c_str (), surface_->points.size (), normals_->points.size ());
00126 output.width = output.height = 0;
00127 output.points.clear ();
00128 return;
00129 }
00130
00131
00132
00133 std::vector<int> nn_indices (k_);
00134 std::vector<float> nn_dists (k_);
00135
00136
00137 for (size_t idx = 0; idx < indices_->size (); ++idx)
00138 {
00139 searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists);
00140
00141
00142 computePointPrincipalCurvatures (*normals_, (*indices_)[idx], nn_indices,
00143 output.points[idx].principal_curvature[0], output.points[idx].principal_curvature[1], output.points[idx].principal_curvature[2],
00144 output.points[idx].pc1, output.points[idx].pc2);
00145 }
00146 }
00147
00148 #define PCL_INSTANTIATE_PrincipalCurvaturesEstimation(T,NT,OutT) template class pcl::PrincipalCurvaturesEstimation<T,NT,OutT>;
00149
00150 #endif // PCL_FEATURES_IMPL_PRINCIPAL_CURVATURES_H_