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_FPFH_H_
00039 #define PCL_FEATURES_IMPL_FPFH_H_
00040
00041 #include "pcl/features/fpfh.h"
00042
00044 template <typename PointInT, typename PointNT, typename PointOutT> bool
00045 pcl::FPFHEstimation<PointInT, PointNT, PointOutT>::computePairFeatures (
00046 const pcl::PointCloud<PointInT> &cloud, const pcl::PointCloud<PointNT> &normals,
00047 int p_idx, int q_idx, float &f1, float &f2, float &f3, float &f4)
00048 {
00049
00050 Eigen::Vector4f delta = cloud.points[q_idx].getVector4fMap () - cloud.points[p_idx].getVector4fMap ();
00051 delta[3] = 0;
00052
00053
00054 float distance_sqr = delta.squaredNorm ();
00055
00056 if (distance_sqr == 0)
00057 {
00058 ROS_ERROR ("Euclidean distance between points %d and %d is 0!", p_idx, q_idx);
00059 f1 = f2 = f3 = f4 = 0;
00060 return (false);
00061 }
00062
00063
00064 f4 = sqrt (distance_sqr);
00065
00066
00067
00068 pcl::Vector4fMapConst u = normals.points[p_idx].getNormalVector4fMap ();
00069
00070
00071
00072 f3 = u.dot (delta) / f4;
00073
00074
00075 Eigen::Vector4f v = Eigen::Vector4f::Zero ();
00076 v = delta.cross3 (u);
00077
00078 distance_sqr = v.squaredNorm ();
00079 if (distance_sqr == 0)
00080 {
00081 ROS_ERROR ("Norm of Delta x U is 0 for point %d and %d!", p_idx, q_idx);
00082 f1 = f2 = f3 = f4 = 0;
00083 return (false);
00084 }
00085
00086
00087 Eigen::Vector4f nq (normals.points[q_idx].normal_x,
00088 normals.points[q_idx].normal_y,
00089 normals.points[q_idx].normal_z,
00090 0);
00091
00092
00093 v /= sqrt (distance_sqr);
00094
00095
00096 delta = u.cross3 (v);
00097
00098
00099
00100 f2 = v.dot (nq);
00101
00102
00103
00104 f1 = atan2f (delta.dot (nq), u.dot (nq));
00105
00106 return (true);
00107 }
00108
00110 template <typename PointInT, typename PointNT, typename PointOutT> void
00111 pcl::FPFHEstimation<PointInT, PointNT, PointOutT>::computePointSPFHSignature (
00112 const pcl::PointCloud<PointInT> &cloud, const pcl::PointCloud<PointNT> &normals,
00113 int p_idx, const std::vector<int> &indices,
00114 Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3)
00115 {
00116 Eigen::Vector4f pfh_tuple;
00117
00118 int nr_bins_f1 = hist_f1.cols ();
00119 int nr_bins_f2 = hist_f2.cols ();
00120 int nr_bins_f3 = hist_f3.cols ();
00121
00122
00123 float hist_incr = 100.0 / (float)(indices.size () - 1);
00124
00125
00126 for (size_t idx = 0; idx < indices.size (); ++idx)
00127 {
00128
00129 if (p_idx == indices[idx])
00130 continue;
00131
00132
00133 if (!computePairFeatures (cloud, normals, p_idx, indices[idx], pfh_tuple[0], pfh_tuple[1], pfh_tuple[2], pfh_tuple[3]))
00134 continue;
00135
00136
00137 int h_index = floor (nr_bins_f1 * ((pfh_tuple[0] + M_PI) * d_pi_));
00138 if (h_index < 0) h_index = 0;
00139 if (h_index >= nr_bins_f1) h_index = nr_bins_f1 - 1;
00140 hist_f1 (p_idx, h_index) += hist_incr;
00141
00142 h_index = floor (nr_bins_f2 * ((pfh_tuple[1] + 1.0) * 0.5));
00143 if (h_index < 0) h_index = 0;
00144 if (h_index >= nr_bins_f2) h_index = nr_bins_f2 - 1;
00145 hist_f2 (p_idx, h_index) += hist_incr;
00146
00147 h_index = floor (nr_bins_f3 * ((pfh_tuple[2] + 1.0) * 0.5));
00148 if (h_index < 0) h_index = 0;
00149 if (h_index >= nr_bins_f3) h_index = nr_bins_f3 - 1;
00150 hist_f3 (p_idx, h_index) += hist_incr;
00151 }
00152 }
00153
00155 template <typename PointInT, typename PointNT, typename PointOutT> void
00156 pcl::FPFHEstimation<PointInT, PointNT, PointOutT>::weightPointSPFHSignature (
00157 const Eigen::MatrixXf &hist_f1, const Eigen::MatrixXf &hist_f2, const Eigen::MatrixXf &hist_f3,
00158 const std::vector<int> &indices, const std::vector<float> &dists, Eigen::VectorXf &fpfh_histogram)
00159 {
00160 assert (indices.size () == dists.size ());
00161 double sum_f1 = 0.0, sum_f2 = 0.0, sum_f3 = 0.0;
00162 float weight = 0.0, val_f1, val_f2, val_f3;
00163
00164
00165 int nr_bins_f1 = hist_f1.cols ();
00166 int nr_bins_f2 = hist_f2.cols ();
00167 int nr_bins_f3 = hist_f3.cols ();
00168 int nr_bins_f12 = nr_bins_f1 + nr_bins_f2;
00169
00170
00171 for (size_t idx = 0, data_size = indices.size (); idx < data_size; ++idx)
00172 {
00173
00174 if (dists[idx] == 0)
00175 continue;
00176
00177
00178 weight = 1.0 / dists[idx];
00179
00180
00181 for (int f1_i = 0; f1_i < nr_bins_f1; ++f1_i)
00182 {
00183 val_f1 = hist_f1 (indices[idx], f1_i) * weight;
00184 sum_f1 += val_f1;
00185 fpfh_histogram[f1_i] += val_f1;
00186 }
00187
00188 for (int f2_i = 0; f2_i < nr_bins_f2; ++f2_i)
00189 {
00190 val_f2 = hist_f2 (indices[idx], f2_i) * weight;
00191 sum_f2 += val_f2;
00192 fpfh_histogram[f2_i + nr_bins_f1] += val_f2;
00193 }
00194
00195 for (int f3_i = 0; f3_i < nr_bins_f3; ++f3_i)
00196 {
00197 val_f3 = hist_f3 (indices[idx], f3_i) * weight;
00198 sum_f3 += val_f3;
00199 fpfh_histogram[f3_i + nr_bins_f12] += val_f3;
00200 }
00201 }
00202
00203 if (sum_f1 != 0)
00204 sum_f1 = 100.0 / sum_f1;
00205 if (sum_f2 != 0)
00206 sum_f2 = 100.0 / sum_f2;
00207 if (sum_f3 != 0)
00208 sum_f3 = 100.0 / sum_f3;
00209
00210
00211 for (int f1_i = 0; f1_i < nr_bins_f1; ++f1_i)
00212 fpfh_histogram[f1_i] *= sum_f1;
00213 for (int f2_i = 0; f2_i < nr_bins_f2; ++f2_i)
00214 fpfh_histogram[f2_i + nr_bins_f1] *= sum_f2;
00215 for (int f3_i = 0; f3_i < nr_bins_f3; ++f3_i)
00216 fpfh_histogram[f3_i + nr_bins_f12] *= sum_f3;
00217 }
00218
00220 template <typename PointInT, typename PointNT, typename PointOutT> void
00221 pcl::FPFHEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut &output)
00222 {
00223
00224 if (!normals_)
00225 {
00226 ROS_ERROR ("[pcl::%s::computeFeature] No input dataset containing normals was given!", getClassName ().c_str ());
00227 output.width = output.height = 0;
00228 output.points.clear ();
00229 return;
00230 }
00231 if (normals_->points.size () != surface_->points.size ())
00232 {
00233 ROS_ERROR ("[pcl::%s::computeFeature] The number of points in the input dataset differs from the number of points in the dataset containing the normals!", getClassName ().c_str ());
00234 output.width = output.height = 0;
00235 output.points.clear ();
00236 return;
00237 }
00238
00239
00240
00241 std::vector<int> nn_indices (k_);
00242 std::vector<float> nn_dists (k_);
00243
00244 size_t data_size = indices_->size ();
00245
00246 hist_f1_.setZero (data_size, nr_bins_f1_);
00247 hist_f2_.setZero (data_size, nr_bins_f2_);
00248 hist_f3_.setZero (data_size, nr_bins_f3_);
00249
00250 int nr_bins = nr_bins_f1_ + nr_bins_f2_ + nr_bins_f3_;
00251
00252
00253 for (size_t idx = 0; idx < data_size; ++idx)
00254 {
00255 int p_idx = (*indices_)[idx];
00256 searchForNeighbors (p_idx, search_parameter_, nn_indices, nn_dists);
00257
00258
00259 computePointSPFHSignature (*surface_, *normals_, p_idx, nn_indices,
00260 hist_f1_, hist_f2_, hist_f3_);
00261 }
00262
00263 fpfh_histogram_.setZero (nr_bins);
00264
00265 for (size_t idx = 0; idx < data_size; ++idx)
00266 {
00267 searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists);
00268
00269 weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram_);
00270
00271
00272 for (int d = 0; d < fpfh_histogram_.size (); ++d)
00273 output.points[idx].histogram[d] = fpfh_histogram_[d];
00274 fpfh_histogram_.setZero ();
00275 }
00276
00277 }
00278
00279 #define PCL_INSTANTIATE_FPFHEstimation(T,NT,OutT) template class pcl::FPFHEstimation<T,NT,OutT>;
00280
00281 #endif // PCL_FEATURES_IMPL_FPFH_H_
00282