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_INTENSITY_GRADIENT_H_
00039 #define PCL_FEATURES_IMPL_INTENSITY_GRADIENT_H_
00040
00041 #include "pcl/features/intensity_gradient.h"
00042
00043 template <typename PointInT, typename PointNT, typename PointOutT> void
00044 pcl::IntensityGradientEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut &output)
00045 {
00046
00047
00048 std::vector<int> nn_indices (k_);
00049 std::vector<float> nn_dists (k_);
00050
00051
00052 for (size_t idx = 0; idx < indices_->size (); ++idx)
00053 {
00054 PointOutT &p_out = output.points[idx];
00055
00056 if (!searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists))
00057 {
00058 p_out.gradient[0] = p_out.gradient[1] = p_out.gradient[2] = std::numeric_limits<float>::quiet_NaN ();
00059 continue;
00060 }
00061
00062 Eigen::Vector4f centroid;
00063 compute3DCentroid (*surface_, nn_indices, centroid);
00064
00065 Eigen::Vector3f normal = Eigen::Vector3f::Map (normals_->points[idx].normal);
00066 Eigen::Vector3f gradient;
00067 computePointIntensityGradient (*surface_, nn_indices, centroid.head<3> (), normal, gradient);
00068
00069 p_out.gradient[0] = gradient[0];
00070 p_out.gradient[1] = gradient[1];
00071 p_out.gradient[2] = gradient[2];
00072
00073 }
00074 }
00075
00076 template <typename PointInT, typename PointNT, typename PointOutT> void
00077 pcl::IntensityGradientEstimation <PointInT, PointNT, PointOutT>::computePointIntensityGradient (
00078 const pcl::PointCloud <PointInT> &cloud, const std::vector <int> &indices,
00079 const Eigen::Vector3f &point, const Eigen::Vector3f &normal, Eigen::Vector3f &gradient)
00080 {
00081 if (indices.size () < 3)
00082 {
00083 gradient[0] = gradient[1] = gradient[2] = std::numeric_limits<float>::quiet_NaN ();
00084 return;
00085 }
00086
00087 Eigen::Matrix3f A = Eigen::Matrix3f::Zero ();
00088 Eigen::Vector3f b = Eigen::Vector3f::Zero ();
00089
00090 for (size_t i_point = 0; i_point < indices.size (); ++i_point)
00091 {
00092 PointInT p = cloud.points[indices[i_point]];
00093 if (!pcl_isfinite (p.x) ||
00094 !pcl_isfinite (p.y) ||
00095 !pcl_isfinite (p.z) ||
00096 !pcl_isfinite (p.intensity))
00097 continue;
00098
00099 p.x -= point[0];
00100 p.y -= point[1];
00101 p.z -= point[2];
00102
00103 A (0, 0) += p.x*p.x;
00104 A (0, 1) += p.x*p.y;
00105 A (0, 2) += p.x*p.z;
00106
00107 A (1, 1) += p.y*p.y;
00108 A (1, 2) += p.y*p.z;
00109
00110 A (2, 2) += p.z*p.z;
00111
00112 b[0] += p.x * p.intensity;
00113 b[1] += p.y * p.intensity;
00114 b[2] += p.z * p.intensity;
00115 }
00116
00117 A (1, 0) = A (0, 1);
00118 A (2, 0) = A (0, 2);
00119 A (2, 1) = A (1, 2);
00120
00121
00122 Eigen::Vector3f x = A.colPivHouseholderQr ().solve (b);
00123
00124
00125 gradient = (Eigen::Matrix3f::Identity () - normal*normal.transpose ()) * x;
00126 }
00127
00128
00129 #define PCL_INSTANTIATE_IntensityGradientEstimation(InT,NT,OutT) template class pcl::IntensityGradientEstimation<InT,NT,OutT>;
00130
00131 #endif // PCL_FEATURES_IMPL_INTENSITY_GRADIENT_H_