43 #include <pcl/features/fpfh.h>
45 #include <pcl/common/point_tests.h>
46 #include <pcl/features/pfh_tools.h>
51 template <
typename Po
intInT,
typename Po
intNT,
typename Po
intOutT>
bool
54 int p_idx,
int q_idx,
float &f1,
float &f2,
float &f3,
float &f4)
57 cloud[q_idx].getVector4fMap (), normals[q_idx].getNormalVector4fMap (),
63 template <
typename Po
intInT,
typename Po
intNT,
typename Po
intOutT>
void
67 Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3)
69 Eigen::Vector4f pfh_tuple;
72 int nr_bins_f1 =
static_cast<int> (hist_f1.cols ());
73 int nr_bins_f2 =
static_cast<int> (hist_f2.cols ());
74 int nr_bins_f3 =
static_cast<int> (hist_f3.cols ());
77 float hist_incr = 100.0f /
static_cast<float>(indices.size () - 1);
80 for (
const auto &index : indices)
87 if (!
computePairFeatures (cloud, normals, p_idx, index, pfh_tuple[0], pfh_tuple[1], pfh_tuple[2], pfh_tuple[3]))
91 int h_index =
static_cast<int> (std::floor (nr_bins_f1 * ((pfh_tuple[0] +
M_PI) * d_pi_)));
92 if (h_index < 0) h_index = 0;
93 if (h_index >= nr_bins_f1) h_index = nr_bins_f1 - 1;
94 hist_f1 (row, h_index) += hist_incr;
96 h_index =
static_cast<int> (std::floor (nr_bins_f2 * ((pfh_tuple[1] + 1.0) * 0.5)));
97 if (h_index < 0) h_index = 0;
98 if (h_index >= nr_bins_f2) h_index = nr_bins_f2 - 1;
99 hist_f2 (row, h_index) += hist_incr;
101 h_index =
static_cast<int> (std::floor (nr_bins_f3 * ((pfh_tuple[2] + 1.0) * 0.5)));
102 if (h_index < 0) h_index = 0;
103 if (h_index >= nr_bins_f3) h_index = nr_bins_f3 - 1;
104 hist_f3 (row, h_index) += hist_incr;
109 template <
typename Po
intInT,
typename Po
intNT,
typename Po
intOutT>
void
111 const Eigen::MatrixXf &hist_f1,
const Eigen::MatrixXf &hist_f2,
const Eigen::MatrixXf &hist_f3,
112 const pcl::Indices &indices,
const std::vector<float> &dists, Eigen::VectorXf &fpfh_histogram)
114 assert (indices.size () == dists.size ());
116 double sum_f1 = 0.0, sum_f2 = 0.0, sum_f3 = 0.0;
117 float weight = 0.0, val_f1, val_f2, val_f3;
120 const auto nr_bins_f1 = hist_f1.cols ();
121 const auto nr_bins_f2 = hist_f2.cols ();
122 const auto nr_bins_f3 = hist_f3.cols ();
123 const auto nr_bins_f12 = nr_bins_f1 + nr_bins_f2;
126 fpfh_histogram.setZero (nr_bins_f1 + nr_bins_f2 + nr_bins_f3);
129 for (std::size_t idx = 0; idx < indices.size (); ++idx)
136 weight = 1.0f / dists[idx];
139 for (Eigen::MatrixXf::Index f1_i = 0; f1_i < nr_bins_f1; ++f1_i)
141 val_f1 = hist_f1 (indices[idx], f1_i) * weight;
143 fpfh_histogram[f1_i] += val_f1;
146 for (Eigen::MatrixXf::Index f2_i = 0; f2_i < nr_bins_f2; ++f2_i)
148 val_f2 = hist_f2 (indices[idx], f2_i) * weight;
150 fpfh_histogram[f2_i + nr_bins_f1] += val_f2;
153 for (Eigen::MatrixXf::Index f3_i = 0; f3_i < nr_bins_f3; ++f3_i)
155 val_f3 = hist_f3 (indices[idx], f3_i) * weight;
157 fpfh_histogram[f3_i + nr_bins_f12] += val_f3;
162 sum_f1 = 100.0 / sum_f1;
164 sum_f2 = 100.0 / sum_f2;
166 sum_f3 = 100.0 / sum_f3;
169 const auto denormalize_with = [](
auto factor)
171 return [=](
const auto& data) {
return data * factor; };
174 auto last = fpfh_histogram.data ();
175 last = std::transform(last, last + nr_bins_f1, last, denormalize_with (sum_f1));
176 last = std::transform(last, last + nr_bins_f2, last, denormalize_with (sum_f2));
177 std::transform(last, last + nr_bins_f3, last, denormalize_with (sum_f3));
181 template <
typename Po
intInT,
typename Po
intNT,
typename Po
intOutT>
void
183 Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3)
188 std::vector<float> nn_dists (k_);
190 std::set<int> spfh_indices;
191 spfh_hist_lookup.resize (surface_->size ());
195 if (surface_ != input_ ||
196 indices_->size () != surface_->size ())
198 for (
const auto& p_idx: *indices_)
200 if (this->searchForNeighbors (p_idx, search_parameter_, nn_indices, nn_dists) == 0)
203 spfh_indices.insert (nn_indices.begin (), nn_indices.end ());
209 for (std::size_t idx = 0; idx < indices_->size (); ++idx)
210 spfh_indices.insert (
static_cast<int> (idx));
214 std::size_t data_size = spfh_indices.size ();
215 hist_f1.setZero (data_size, nr_bins_f1_);
216 hist_f2.setZero (data_size, nr_bins_f2_);
217 hist_f3.setZero (data_size, nr_bins_f3_);
221 for (
const auto& p_idx: spfh_indices)
224 if (this->searchForNeighbors (*surface_, p_idx, search_parameter_, nn_indices, nn_dists) == 0)
228 computePointSPFHSignature (*surface_, *normals_, p_idx, i, nn_indices, hist_f1, hist_f2, hist_f3);
231 spfh_hist_lookup[p_idx] = i;
237 template <
typename Po
intInT,
typename Po
intNT,
typename Po
intOutT>
void
243 std::vector<float> nn_dists (k_);
245 std::vector<int> spfh_hist_lookup;
246 computeSPFHSignatures (spfh_hist_lookup, hist_f1_, hist_f2_, hist_f3_);
250 if (input_->is_dense)
253 for (std::size_t idx = 0; idx < indices_->size (); ++idx)
255 if (this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
257 for (Eigen::Index d = 0; d < fpfh_histogram_.size (); ++d)
258 output[idx].histogram[d] = std::numeric_limits<float>::quiet_NaN ();
266 for (
auto &nn_index : nn_indices)
267 nn_index = spfh_hist_lookup[nn_index];
270 weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram_);
273 std::copy_n(fpfh_histogram_.data (), fpfh_histogram_.size (), output[idx].histogram);
279 for (std::size_t idx = 0; idx < indices_->size (); ++idx)
281 if (!
isFinite ((*input_)[(*indices_)[idx]]) ||
282 this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
284 for (Eigen::Index d = 0; d < fpfh_histogram_.size (); ++d)
285 output[idx].histogram[d] = std::numeric_limits<float>::quiet_NaN ();
293 for (
auto &nn_index : nn_indices)
294 nn_index = spfh_hist_lookup[nn_index];
297 weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram_);
300 std::copy_n(fpfh_histogram_.data (), fpfh_histogram_.size (), output[idx].histogram);
305 #define PCL_INSTANTIATE_FPFHEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::FPFHEstimation<T,NT,OutT>;
void computeSPFHSignatures(std::vector< int > &spf_hist_lookup, Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3)
Estimate the set of all SPFH (Simple Point Feature Histograms) signatures for the input cloud.
void computePointSPFHSignature(const pcl::PointCloud< PointInT > &cloud, const pcl::PointCloud< PointNT > &normals, pcl::index_t p_idx, int row, const pcl::Indices &indices, Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3)
Estimate the SPFH (Simple Point Feature Histograms) individual signatures of the three angular (f1,...
void computeFeature(PointCloudOut &output) override
Estimate the Fast Point Feature Histograms (FPFH) descriptors at a set of points given by <setInputCl...
bool computePairFeatures(const pcl::PointCloud< PointInT > &cloud, const pcl::PointCloud< PointNT > &normals, int p_idx, int q_idx, float &f1, float &f2, float &f3, float &f4)
Compute the 4-tuple representation containing the three angles and one distance between two points re...
void weightPointSPFHSignature(const Eigen::MatrixXf &hist_f1, const Eigen::MatrixXf &hist_f2, const Eigen::MatrixXf &hist_f3, const pcl::Indices &indices, const std::vector< float > &dists, Eigen::VectorXf &fpfh_histogram)
Weight the SPFH (Simple Point Feature Histograms) individual histograms to create the final FPFH (Fas...
bool is_dense
True if no points are invalid (e.g., have NaN or Inf values in any of their floating point fields).
PCL_EXPORTS bool computePairFeatures(const Eigen::Vector4f &p1, const Eigen::Vector4f &n1, const Eigen::Vector4f &p2, const Eigen::Vector4f &n2, float &f1, float &f2, float &f3, float &f4)
Compute the 4-tuple representation containing the three angles and one distance between two points re...
bool isFinite(const PointT &pt)
Tests if the 3D components of a point are all finite param[in] pt point to be tested return true if f...
detail::int_type_t< detail::index_type_size, detail::index_type_signed > index_t
Type used for an index in PCL.
IndicesAllocator<> Indices
Type used for indices in PCL.