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
00039
00040 #ifndef PCL_FEATURES_IMPL_FPFH_H_
00041 #define PCL_FEATURES_IMPL_FPFH_H_
00042
00043 #include <pcl/features/fpfh.h>
00044 #include <pcl/features/pfh.h>
00045
00047 template <typename PointInT, typename PointNT, typename PointOutT> bool
00048 pcl::FPFHEstimation<PointInT, PointNT, PointOutT>::computePairFeatures (
00049 const pcl::PointCloud<PointInT> &cloud, const pcl::PointCloud<PointNT> &normals,
00050 int p_idx, int q_idx, float &f1, float &f2, float &f3, float &f4)
00051 {
00052 pcl::computePairFeatures (cloud.points[p_idx].getVector4fMap (), normals.points[p_idx].getNormalVector4fMap (),
00053 cloud.points[q_idx].getVector4fMap (), normals.points[q_idx].getNormalVector4fMap (),
00054 f1, f2, f3, f4);
00055 return (true);
00056 }
00057
00059 template <typename PointInT, typename PointNT, typename PointOutT> void
00060 pcl::FPFHEstimation<PointInT, PointNT, PointOutT>::computePointSPFHSignature (
00061 const pcl::PointCloud<PointInT> &cloud, const pcl::PointCloud<PointNT> &normals,
00062 int p_idx, int row, const std::vector<int> &indices,
00063 Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3)
00064 {
00065 Eigen::Vector4f pfh_tuple;
00066
00067 int nr_bins_f1 = static_cast<int> (hist_f1.cols ());
00068 int nr_bins_f2 = static_cast<int> (hist_f2.cols ());
00069 int nr_bins_f3 = static_cast<int> (hist_f3.cols ());
00070
00071
00072 float hist_incr = 100.0f / static_cast<float>(indices.size () - 1);
00073
00074
00075 for (size_t idx = 0; idx < indices.size (); ++idx)
00076 {
00077
00078 if (p_idx == indices[idx])
00079 continue;
00080
00081
00082 if (!computePairFeatures (cloud, normals, p_idx, indices[idx], pfh_tuple[0], pfh_tuple[1], pfh_tuple[2], pfh_tuple[3]))
00083 continue;
00084
00085
00086 int h_index = static_cast<int> (floor (nr_bins_f1 * ((pfh_tuple[0] + M_PI) * d_pi_)));
00087 if (h_index < 0) h_index = 0;
00088 if (h_index >= nr_bins_f1) h_index = nr_bins_f1 - 1;
00089 hist_f1 (row, h_index) += hist_incr;
00090
00091 h_index = static_cast<int> (floor (nr_bins_f2 * ((pfh_tuple[1] + 1.0) * 0.5)));
00092 if (h_index < 0) h_index = 0;
00093 if (h_index >= nr_bins_f2) h_index = nr_bins_f2 - 1;
00094 hist_f2 (row, h_index) += hist_incr;
00095
00096 h_index = static_cast<int> (floor (nr_bins_f3 * ((pfh_tuple[2] + 1.0) * 0.5)));
00097 if (h_index < 0) h_index = 0;
00098 if (h_index >= nr_bins_f3) h_index = nr_bins_f3 - 1;
00099 hist_f3 (row, h_index) += hist_incr;
00100 }
00101 }
00102
00104 template <typename PointInT, typename PointNT, typename PointOutT> void
00105 pcl::FPFHEstimation<PointInT, PointNT, PointOutT>::weightPointSPFHSignature (
00106 const Eigen::MatrixXf &hist_f1, const Eigen::MatrixXf &hist_f2, const Eigen::MatrixXf &hist_f3,
00107 const std::vector<int> &indices, const std::vector<float> &dists, Eigen::VectorXf &fpfh_histogram)
00108 {
00109 assert (indices.size () == dists.size ());
00110 double sum_f1 = 0.0, sum_f2 = 0.0, sum_f3 = 0.0;
00111 float weight = 0.0, val_f1, val_f2, val_f3;
00112
00113
00114 int nr_bins_f1 = static_cast<int> (hist_f1.cols ());
00115 int nr_bins_f2 = static_cast<int> (hist_f2.cols ());
00116 int nr_bins_f3 = static_cast<int> (hist_f3.cols ());
00117 int nr_bins_f12 = nr_bins_f1 + nr_bins_f2;
00118
00119
00120 fpfh_histogram.setZero (nr_bins_f1 + nr_bins_f2 + nr_bins_f3);
00121
00122
00123 for (size_t idx = 0, data_size = indices.size (); idx < data_size; ++idx)
00124 {
00125
00126 if (dists[idx] == 0)
00127 continue;
00128
00129
00130 weight = 1.0f / dists[idx];
00131
00132
00133 for (int f1_i = 0; f1_i < nr_bins_f1; ++f1_i)
00134 {
00135 val_f1 = hist_f1 (indices[idx], f1_i) * weight;
00136 sum_f1 += val_f1;
00137 fpfh_histogram[f1_i] += val_f1;
00138 }
00139
00140 for (int f2_i = 0; f2_i < nr_bins_f2; ++f2_i)
00141 {
00142 val_f2 = hist_f2 (indices[idx], f2_i) * weight;
00143 sum_f2 += val_f2;
00144 fpfh_histogram[f2_i + nr_bins_f1] += val_f2;
00145 }
00146
00147 for (int f3_i = 0; f3_i < nr_bins_f3; ++f3_i)
00148 {
00149 val_f3 = hist_f3 (indices[idx], f3_i) * weight;
00150 sum_f3 += val_f3;
00151 fpfh_histogram[f3_i + nr_bins_f12] += val_f3;
00152 }
00153 }
00154
00155 if (sum_f1 != 0)
00156 sum_f1 = 100.0 / sum_f1;
00157 if (sum_f2 != 0)
00158 sum_f2 = 100.0 / sum_f2;
00159 if (sum_f3 != 0)
00160 sum_f3 = 100.0 / sum_f3;
00161
00162
00163 for (int f1_i = 0; f1_i < nr_bins_f1; ++f1_i)
00164 fpfh_histogram[f1_i] *= static_cast<float> (sum_f1);
00165 for (int f2_i = 0; f2_i < nr_bins_f2; ++f2_i)
00166 fpfh_histogram[f2_i + nr_bins_f1] *= static_cast<float> (sum_f2);
00167 for (int f3_i = 0; f3_i < nr_bins_f3; ++f3_i)
00168 fpfh_histogram[f3_i + nr_bins_f12] *= static_cast<float> (sum_f3);
00169 }
00170
00172 template <typename PointInT, typename PointNT, typename PointOutT> void
00173 pcl::FPFHEstimation<PointInT, PointNT, PointOutT>::computeSPFHSignatures (std::vector<int> &spfh_hist_lookup,
00174 Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3)
00175 {
00176
00177
00178 std::vector<int> nn_indices (k_);
00179 std::vector<float> nn_dists (k_);
00180
00181 std::set<int> spfh_indices;
00182 spfh_hist_lookup.resize (surface_->points.size ());
00183
00184
00185
00186 if (surface_ != input_ ||
00187 indices_->size () != surface_->points.size ())
00188 {
00189 for (size_t idx = 0; idx < indices_->size (); ++idx)
00190 {
00191 int p_idx = (*indices_)[idx];
00192 if (this->searchForNeighbors (p_idx, search_parameter_, nn_indices, nn_dists) == 0)
00193 continue;
00194
00195 spfh_indices.insert (nn_indices.begin (), nn_indices.end ());
00196 }
00197 }
00198 else
00199 {
00200
00201 for (size_t idx = 0; idx < indices_->size (); ++idx)
00202 spfh_indices.insert (static_cast<int> (idx));
00203 }
00204
00205
00206 size_t data_size = spfh_indices.size ();
00207 hist_f1.setZero (data_size, nr_bins_f1_);
00208 hist_f2.setZero (data_size, nr_bins_f2_);
00209 hist_f3.setZero (data_size, nr_bins_f3_);
00210
00211
00212 std::set<int>::iterator spfh_indices_itr = spfh_indices.begin ();
00213 for (int i = 0; i < static_cast<int> (spfh_indices.size ()); ++i)
00214 {
00215
00216 int p_idx = *spfh_indices_itr;
00217 ++spfh_indices_itr;
00218
00219
00220 if (this->searchForNeighbors (*surface_, p_idx, search_parameter_, nn_indices, nn_dists) == 0)
00221 continue;
00222
00223
00224 computePointSPFHSignature (*surface_, *normals_, p_idx, i, nn_indices, hist_f1, hist_f2, hist_f3);
00225
00226
00227 spfh_hist_lookup[p_idx] = i;
00228 }
00229 }
00230
00232 template <typename PointInT, typename PointNT, typename PointOutT> void
00233 pcl::FPFHEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut &output)
00234 {
00235
00236
00237 std::vector<int> nn_indices (k_);
00238 std::vector<float> nn_dists (k_);
00239
00240 std::vector<int> spfh_hist_lookup;
00241 computeSPFHSignatures (spfh_hist_lookup, hist_f1_, hist_f2_, hist_f3_);
00242
00243 output.is_dense = true;
00244
00245 if (input_->is_dense)
00246 {
00247
00248 for (size_t idx = 0; idx < indices_->size (); ++idx)
00249 {
00250 if (this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
00251 {
00252 for (int d = 0; d < fpfh_histogram_.size (); ++d)
00253 output.points[idx].histogram[d] = std::numeric_limits<float>::quiet_NaN ();
00254
00255 output.is_dense = false;
00256 continue;
00257 }
00258
00259
00260
00261 for (size_t i = 0; i < nn_indices.size (); ++i)
00262 nn_indices[i] = spfh_hist_lookup[nn_indices[i]];
00263
00264
00265 weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram_);
00266
00267
00268 for (int d = 0; d < fpfh_histogram_.size (); ++d)
00269 output.points[idx].histogram[d] = fpfh_histogram_[d];
00270 }
00271 }
00272 else
00273 {
00274
00275 for (size_t idx = 0; idx < indices_->size (); ++idx)
00276 {
00277 if (!isFinite ((*input_)[(*indices_)[idx]]) ||
00278 this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
00279 {
00280 for (int d = 0; d < fpfh_histogram_.size (); ++d)
00281 output.points[idx].histogram[d] = std::numeric_limits<float>::quiet_NaN ();
00282
00283 output.is_dense = false;
00284 continue;
00285 }
00286
00287
00288
00289 for (size_t i = 0; i < nn_indices.size (); ++i)
00290 nn_indices[i] = spfh_hist_lookup[nn_indices[i]];
00291
00292
00293 weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram_);
00294
00295
00296 for (int d = 0; d < fpfh_histogram_.size (); ++d)
00297 output.points[idx].histogram[d] = fpfh_histogram_[d];
00298 }
00299 }
00300 }
00301
00303 template <typename PointInT, typename PointNT> void
00304 pcl::FPFHEstimation<PointInT, PointNT, Eigen::MatrixXf>::computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output)
00305 {
00306
00307 output.channels["fpfh"].name = "fpfh";
00308 output.channels["fpfh"].offset = 0;
00309 output.channels["fpfh"].size = 4;
00310 output.channels["fpfh"].count = 33;
00311 output.channels["fpfh"].datatype = sensor_msgs::PointField::FLOAT32;
00312
00313
00314
00315 std::vector<int> nn_indices (k_);
00316 std::vector<float> nn_dists (k_);
00317
00318 std::vector<int> spfh_hist_lookup;
00319 this->computeSPFHSignatures (spfh_hist_lookup, hist_f1_, hist_f2_, hist_f3_);
00320
00321
00322 output.points.resize (indices_->size (), nr_bins_f1_ + nr_bins_f2_ + nr_bins_f3_);
00323 output.is_dense = true;
00324
00325 if (input_->is_dense)
00326 {
00327
00328 for (size_t idx = 0; idx < indices_->size (); ++idx)
00329 {
00330 if (!isFinite ((*input_)[(*indices_)[idx]]) ||
00331 this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
00332 {
00333 output.points.row (idx).setConstant (std::numeric_limits<float>::quiet_NaN ());
00334 output.is_dense = false;
00335 continue;
00336 }
00337
00338
00339
00340 for (size_t i = 0; i < nn_indices.size (); ++i)
00341 nn_indices[i] = spfh_hist_lookup[nn_indices[i]];
00342
00343
00344 this->weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram_);
00345 output.points.row (idx) = fpfh_histogram_;
00346 }
00347 }
00348 else
00349 {
00350
00351 for (size_t idx = 0; idx < indices_->size (); ++idx)
00352 {
00353 if (this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
00354 {
00355 output.points.row (idx).setConstant (std::numeric_limits<float>::quiet_NaN ());
00356 output.is_dense = false;
00357 continue;
00358 }
00359
00360
00361
00362 for (size_t i = 0; i < nn_indices.size (); ++i)
00363 nn_indices[i] = spfh_hist_lookup[nn_indices[i]];
00364
00365
00366 this->weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram_);
00367 output.points.row (idx) = fpfh_histogram_;
00368 }
00369 }
00370 }
00371
00372
00373 #define PCL_INSTANTIATE_FPFHEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::FPFHEstimation<T,NT,OutT>;
00374
00375 #endif // PCL_FEATURES_IMPL_FPFH_H_
00376