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
00039
00040
00041 #ifndef PCL_FEATURES_IMPL_FPFH_OMP_H_
00042 #define PCL_FEATURES_IMPL_FPFH_OMP_H_
00043
00044 #include <pcl/features/fpfh_omp.h>
00045
00047 template <typename PointInT, typename PointNT, typename PointOutT> void
00048 pcl::FPFHEstimationOMP<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut &output)
00049 {
00050 std::vector<int> spfh_indices_vec;
00051 std::vector<int> spfh_hist_lookup (surface_->points.size ());
00052
00053
00054
00055 if (surface_ != input_ ||
00056 indices_->size () != surface_->points.size ())
00057 {
00058 std::vector<int> nn_indices (k_);
00059 std::vector<float> nn_dists (k_);
00060
00061 std::set<int> spfh_indices_set;
00062 for (size_t idx = 0; idx < indices_->size (); ++idx)
00063 {
00064 int p_idx = (*indices_)[idx];
00065 if (this->searchForNeighbors (p_idx, search_parameter_, nn_indices, nn_dists) == 0)
00066 continue;
00067
00068 spfh_indices_set.insert (nn_indices.begin (), nn_indices.end ());
00069 }
00070 spfh_indices_vec.resize (spfh_indices_set.size ());
00071 std::copy (spfh_indices_set.begin (), spfh_indices_set.end (), spfh_indices_vec.begin ());
00072 }
00073 else
00074 {
00075
00076 spfh_indices_vec.resize (indices_->size ());
00077 for (int idx = 0; idx < static_cast<int> (indices_->size ()); ++idx)
00078 spfh_indices_vec[idx] = idx;
00079 }
00080
00081
00082 size_t data_size = spfh_indices_vec.size ();
00083 hist_f1_.setZero (data_size, nr_bins_f1_);
00084 hist_f2_.setZero (data_size, nr_bins_f2_);
00085 hist_f3_.setZero (data_size, nr_bins_f3_);
00086
00087 std::vector<int> nn_indices (k_);
00088 std::vector<float> nn_dists (k_);
00089
00090
00091
00092 #ifdef _OPENMP
00093 #pragma omp parallel for shared (spfh_hist_lookup) private (nn_indices, nn_dists) num_threads(threads_)
00094 #endif
00095 for (int i = 0; i < static_cast<int> (spfh_indices_vec.size ()); ++i)
00096 {
00097
00098 int p_idx = spfh_indices_vec[i];
00099
00100
00101 if (this->searchForNeighbors (*surface_, p_idx, search_parameter_, nn_indices, nn_dists) == 0)
00102 continue;
00103
00104
00105 this->computePointSPFHSignature (*surface_, *normals_, p_idx, i, nn_indices, hist_f1_, hist_f2_, hist_f3_);
00106
00107
00108 spfh_hist_lookup[p_idx] = i;
00109 }
00110
00111
00112 int nr_bins = nr_bins_f1_ + nr_bins_f2_ + nr_bins_f3_;
00113
00114 nn_indices.clear();
00115 nn_dists.clear();
00116
00117
00118 #ifdef _OPENMP
00119 #pragma omp parallel for shared (output) private (nn_indices, nn_dists) num_threads(threads_)
00120 #endif
00121 for (int idx = 0; idx < static_cast<int> (indices_->size ()); ++idx)
00122 {
00123
00124 if (!isFinite ((*input_)[(*indices_)[idx]]) ||
00125 this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
00126 {
00127 for (int d = 0; d < nr_bins; ++d)
00128 output.points[idx].histogram[d] = std::numeric_limits<float>::quiet_NaN ();
00129
00130 output.is_dense = false;
00131 continue;
00132 }
00133
00134
00135
00136
00137 for (size_t i = 0; i < nn_indices.size (); ++i)
00138 nn_indices[i] = spfh_hist_lookup[nn_indices[i]];
00139
00140
00141 Eigen::VectorXf fpfh_histogram = Eigen::VectorXf::Zero (nr_bins);
00142 weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram);
00143
00144
00145 for (int d = 0; d < nr_bins; ++d)
00146 output.points[idx].histogram[d] = fpfh_histogram[d];
00147 }
00148
00149 }
00150
00151 #define PCL_INSTANTIATE_FPFHEstimationOMP(T,NT,OutT) template class PCL_EXPORTS pcl::FPFHEstimationOMP<T,NT,OutT>;
00152
00153 #endif // PCL_FEATURES_IMPL_FPFH_OMP_H_
00154