Go to the documentation of this file.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_NORMAL_BASED_SIGNATURE_H_
00039 #define PCL_FEATURES_IMPL_NORMAL_BASED_SIGNATURE_H_
00040
00041 #include <pcl/features/normal_based_signature.h>
00042
00043 template <typename PointT, typename PointNT, typename PointFeature> void
00044 pcl::NormalBasedSignatureEstimation<PointT, PointNT, PointFeature>::computeFeature (FeatureCloud &output)
00045 {
00046
00047
00048 PointFeature test_feature;
00049 if (N_prime_ * M_prime_ != sizeof (test_feature.values) / sizeof (float))
00050 {
00051 PCL_ERROR ("NormalBasedSignatureEstimation: not using the proper signature size: %u vs %u\n", N_prime_ * M_prime_, sizeof (test_feature.values) / sizeof (float));
00052 return;
00053 }
00054
00055 std::vector<int> k_indices;
00056 std::vector<float> k_sqr_distances;
00057
00058 tree_->setInputCloud (input_);
00059 output.points.resize (indices_->size ());
00060
00061 for (size_t index_i = 0; index_i < indices_->size (); ++index_i)
00062 {
00063 size_t point_i = (*indices_)[index_i];
00064 Eigen::MatrixXf s_matrix (N_, M_);
00065
00066 Eigen::Vector4f center_point = input_->points[point_i].getVector4fMap ();
00067
00068 for (size_t k = 0; k < N_; ++k)
00069 {
00070 Eigen::VectorXf s_row (M_);
00071
00072 for (size_t l = 0; l < M_; ++l)
00073 {
00074 Eigen::Vector4f normal = normals_->points[point_i].getNormalVector4fMap ();
00075 Eigen::Vector4f normal_u = Eigen::Vector4f::Zero ();
00076 Eigen::Vector4f normal_v = Eigen::Vector4f::Zero ();
00077
00078 if (fabs (normal.x ()) > 0.0001f)
00079 {
00080 normal_u.x () = - normal.y () / normal.x ();
00081 normal_u.y () = 1.0f;
00082 normal_u.z () = 0.0f;
00083 normal_u.normalize ();
00084
00085 }
00086 else if (fabs (normal.y ()) > 0.0001f)
00087 {
00088 normal_u.x () = 1.0f;
00089 normal_u.y () = - normal.x () / normal.y ();
00090 normal_u.z () = 0.0f;
00091 normal_u.normalize ();
00092 }
00093 else
00094 {
00095 normal_u.x () = 0.0f;
00096 normal_u.y () = 1.0f;
00097 normal_u.z () = - normal.y () / normal.z ();
00098 }
00099 normal_v = normal.cross3 (normal_u);
00100
00101 Eigen::Vector4f zeta_point = 2.0f * static_cast<float> (l + 1) * scale_h_ / static_cast<float> (M_) *
00102 (cosf (2.0f * static_cast<float> (M_PI) * static_cast<float> ((k + 1) / N_)) * normal_u +
00103 sinf (2.0f * static_cast<float> (M_PI) * static_cast<float> ((k + 1) / N_)) * normal_v);
00104
00105
00106 Eigen::Vector4f zeta_point_plus_center = zeta_point + center_point;
00107 PointT zeta_point_pcl;
00108 zeta_point_pcl.x = zeta_point_plus_center.x (); zeta_point_pcl.y = zeta_point_plus_center.y (); zeta_point_pcl.z = zeta_point_plus_center.z ();
00109
00110 tree_->radiusSearch (zeta_point_pcl, search_radius_, k_indices, k_sqr_distances);
00111
00112
00113 if (k_indices.size () == 0)
00114 {
00115 k_indices.resize (5);
00116 k_sqr_distances.resize (5);
00117 tree_->nearestKSearch (zeta_point_pcl, 5, k_indices, k_sqr_distances);
00118 }
00119
00120 Eigen::Vector4f average_normal = Eigen::Vector4f::Zero ();
00121
00122 float average_normalization_factor = 0.0f;
00123
00124
00125 for (size_t nn_i = 0; nn_i < k_indices.size (); ++nn_i)
00126 {
00127 if (k_sqr_distances[nn_i] < 1e-7f)
00128 {
00129 average_normal = normals_->points[k_indices[nn_i]].getNormalVector4fMap ();
00130 average_normalization_factor = 1.0f;
00131 break;
00132 }
00133 average_normal += normals_->points[k_indices[nn_i]].getNormalVector4fMap () / k_sqr_distances[nn_i];
00134 average_normalization_factor += 1.0f / k_sqr_distances[nn_i];
00135 }
00136 average_normal /= average_normalization_factor;
00137 float s = zeta_point.dot (average_normal) / zeta_point.norm ();
00138 s_row[l] = s;
00139 }
00140
00141
00142 Eigen::VectorXf dct_row (M_);
00143 for (int m = 0; m < s_row.size (); ++m)
00144 {
00145 float Xk = 0.0f;
00146 for (int n = 0; n < s_row.size (); ++n)
00147 Xk += static_cast<float> (s_row[n] * cos (M_PI / (static_cast<double> (M_ * n) + 0.5) * static_cast<double> (k)));
00148 dct_row[m] = Xk;
00149 }
00150 s_row = dct_row;
00151 s_matrix.row (k) = dct_row;
00152 }
00153
00154
00155 Eigen::MatrixXf dft_matrix (N_, M_);
00156 for (size_t column_i = 0; column_i < M_; ++column_i)
00157 {
00158 Eigen::VectorXf dft_col (N_);
00159 for (size_t k = 0; k < N_; ++k)
00160 {
00161 float Xk_real = 0.0f, Xk_imag = 0.0f;
00162 for (size_t n = 0; n < N_; ++n)
00163 {
00164 Xk_real += static_cast<float> (s_matrix (n, column_i) * cos (2.0f * M_PI / static_cast<double> (N_ * k * n)));
00165 Xk_imag += static_cast<float> (s_matrix (n, column_i) * sin (2.0f * M_PI / static_cast<double> (N_ * k * n)));
00166 }
00167 dft_col[k] = sqrt (Xk_real*Xk_real + Xk_imag*Xk_imag);
00168 }
00169 dft_matrix.col (column_i) = dft_col;
00170 }
00171
00172 Eigen::MatrixXf final_matrix = dft_matrix.block (0, 0, N_prime_, M_prime_);
00173
00174 PointFeature feature_point;
00175 for (size_t i = 0; i < N_prime_; ++i)
00176 for (size_t j = 0; j < M_prime_; ++j)
00177 feature_point.values[i*M_prime_ + j] = final_matrix (i, j);
00178
00179 output.points[index_i] = feature_point;
00180 }
00181 }
00182
00183
00184
00185 #define PCL_INSTANTIATE_NormalBasedSignatureEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::NormalBasedSignatureEstimation<T,NT,OutT>;
00186
00187
00188 #endif