Point Cloud Library (PCL)  1.11.1-dev
ppf_registration.hpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2011, Alexandru-Eugen Ichim
6  * Willow Garage, Inc
7  * Copyright (c) 2012-, Open Perception, Inc.
8  *
9  * All rights reserved.
10  *
11  * Redistribution and use in source and binary forms, with or without
12  * modification, are permitted provided that the following conditions
13  * are met:
14  *
15  * * Redistributions of source code must retain the above copyright
16  * notice, this list of conditions and the following disclaimer.
17  * * Redistributions in binary form must reproduce the above
18  * copyright notice, this list of conditions and the following
19  * disclaimer in the documentation and/or other materials provided
20  * with the distribution.
21  * * Neither the name of the copyright holder(s) nor the names of its
22  * contributors may be used to endorse or promote products derived
23  * from this software without specific prior written permission.
24  *
25  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
26  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
27  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
28  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
29  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
30  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
31  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
32  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
33  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
34  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
35  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
36  * POSSIBILITY OF SUCH DAMAGE.
37  *
38  * $Id$
39  *
40  */
41 
42 #ifndef PCL_REGISTRATION_IMPL_PPF_REGISTRATION_H_
43 #define PCL_REGISTRATION_IMPL_PPF_REGISTRATION_H_
44 
45 #include <pcl/common/transforms.h>
46 #include <pcl/features/pfh.h>
47 #include <pcl/features/pfh_tools.h> // for computePairFeatures
48 #include <pcl/features/ppf.h>
49 #include <pcl/registration/ppf_registration.h>
50 //////////////////////////////////////////////////////////////////////////////////////////////
51 template <typename PointSource, typename PointTarget>
52 void
54  const PointCloudTargetConstPtr& cloud)
55 {
57 
58  scene_search_tree_ =
60  scene_search_tree_->setInputCloud(target_);
61 }
62 
63 //////////////////////////////////////////////////////////////////////////////////////////////
64 template <typename PointSource, typename PointTarget>
65 void
67  PointCloudSource& output, const Eigen::Matrix4f& guess)
68 {
69  if (!search_method_) {
70  PCL_ERROR("[pcl::PPFRegistration::computeTransformation] Search method not set - "
71  "skipping computeTransformation!\n");
72  return;
73  }
74 
75  if (guess != Eigen::Matrix4f::Identity()) {
76  PCL_ERROR("[pcl::PPFRegistration::computeTransformation] setting initial transform "
77  "(guess) not implemented!\n");
78  }
79 
80  const auto aux_size = static_cast<std::size_t>(
81  std::floor(2 * M_PI / search_method_->getAngleDiscretizationStep()));
82 
83  const std::vector<unsigned int> tmp_vec(aux_size, 0);
84  std::vector<std::vector<unsigned int>> accumulator_array(input_->size(), tmp_vec);
85 
86  PCL_INFO("Accumulator array size: %u x %u.\n",
87  accumulator_array.size(),
88  accumulator_array.back().size());
89 
90  PoseWithVotesList voted_poses;
91  // Consider every <scene_reference_point_sampling_rate>-th point as the reference
92  // point => fix s_r
93  float f1, f2, f3, f4;
94  for (std::size_t scene_reference_index = 0; scene_reference_index < target_->size();
95  scene_reference_index += scene_reference_point_sampling_rate_) {
96  Eigen::Vector3f scene_reference_point =
97  (*target_)[scene_reference_index].getVector3fMap(),
98  scene_reference_normal =
99  (*target_)[scene_reference_index].getNormalVector3fMap();
100 
101  float rotation_angle_sg =
102  std::acos(scene_reference_normal.dot(Eigen::Vector3f::UnitX()));
103  bool parallel_to_x_sg =
104  (scene_reference_normal.y() == 0.0f && scene_reference_normal.z() == 0.0f);
105  Eigen::Vector3f rotation_axis_sg =
106  (parallel_to_x_sg)
107  ? (Eigen::Vector3f::UnitY())
108  : (scene_reference_normal.cross(Eigen::Vector3f::UnitX()).normalized());
109  Eigen::AngleAxisf rotation_sg(rotation_angle_sg, rotation_axis_sg);
110  Eigen::Affine3f transform_sg(
111  Eigen::Translation3f(rotation_sg * ((-1) * scene_reference_point)) *
112  rotation_sg);
113 
114  // For every other point in the scene => now have pair (s_r, s_i) fixed
115  std::vector<int> indices;
116  std::vector<float> distances;
117  scene_search_tree_->radiusSearch((*target_)[scene_reference_index],
118  search_method_->getModelDiameter() / 2,
119  indices,
120  distances);
121  for (const auto& scene_point_index : indices)
122  // for(std::size_t i = 0; i < target_->size (); ++i)
123  {
124  // size_t scene_point_index = i;
125  if (scene_reference_index != scene_point_index) {
126  if (/*pcl::computePPFPairFeature*/ pcl::computePairFeatures(
127  (*target_)[scene_reference_index].getVector4fMap(),
128  (*target_)[scene_reference_index].getNormalVector4fMap(),
129  (*target_)[scene_point_index].getVector4fMap(),
130  (*target_)[scene_point_index].getNormalVector4fMap(),
131  f1,
132  f2,
133  f3,
134  f4)) {
135  std::vector<std::pair<std::size_t, std::size_t>> nearest_indices;
136  search_method_->nearestNeighborSearch(f1, f2, f3, f4, nearest_indices);
137 
138  // Compute alpha_s angle
139  Eigen::Vector3f scene_point = (*target_)[scene_point_index].getVector3fMap();
140 
141  Eigen::Vector3f scene_point_transformed = transform_sg * scene_point;
142  float alpha_s =
143  std::atan2(-scene_point_transformed(2), scene_point_transformed(1));
144  if (std::sin(alpha_s) * scene_point_transformed(2) < 0.0f)
145  alpha_s *= (-1);
146  alpha_s *= (-1);
147 
148  // Go through point pairs in the model with the same discretized feature
149  for (const auto& nearest_index : nearest_indices) {
150  std::size_t model_reference_index = nearest_index.first;
151  std::size_t model_point_index = nearest_index.second;
152  // Calculate angle alpha = alpha_m - alpha_s
153  float alpha =
154  search_method_->alpha_m_[model_reference_index][model_point_index] -
155  alpha_s;
156  unsigned int alpha_discretized = static_cast<unsigned int>(
157  std::floor(alpha) +
158  std::floor(M_PI / search_method_->getAngleDiscretizationStep()));
159  accumulator_array[model_reference_index][alpha_discretized]++;
160  }
161  }
162  else
163  PCL_ERROR("[pcl::PPFRegistration::computeTransformation] Computing pair "
164  "feature vector between points %u and %u went wrong.\n",
165  scene_reference_index,
166  scene_point_index);
167  }
168  }
169 
170  std::size_t max_votes_i = 0, max_votes_j = 0;
171  unsigned int max_votes = 0;
172 
173  for (std::size_t i = 0; i < accumulator_array.size(); ++i)
174  for (std::size_t j = 0; j < accumulator_array.back().size(); ++j) {
175  if (accumulator_array[i][j] > max_votes) {
176  max_votes = accumulator_array[i][j];
177  max_votes_i = i;
178  max_votes_j = j;
179  }
180  // Reset accumulator_array for the next set of iterations with a new scene
181  // reference point
182  accumulator_array[i][j] = 0;
183  }
184 
185  Eigen::Vector3f model_reference_point = (*input_)[max_votes_i].getVector3fMap(),
186  model_reference_normal =
187  (*input_)[max_votes_i].getNormalVector3fMap();
188  float rotation_angle_mg =
189  std::acos(model_reference_normal.dot(Eigen::Vector3f::UnitX()));
190  bool parallel_to_x_mg =
191  (model_reference_normal.y() == 0.0f && model_reference_normal.z() == 0.0f);
192  Eigen::Vector3f rotation_axis_mg =
193  (parallel_to_x_mg)
194  ? (Eigen::Vector3f::UnitY())
195  : (model_reference_normal.cross(Eigen::Vector3f::UnitX()).normalized());
196  Eigen::AngleAxisf rotation_mg(rotation_angle_mg, rotation_axis_mg);
197  Eigen::Affine3f transform_mg(
198  Eigen::Translation3f(rotation_mg * ((-1) * model_reference_point)) *
199  rotation_mg);
200  Eigen::Affine3f max_transform =
201  transform_sg.inverse() *
202  Eigen::AngleAxisf((static_cast<float>(max_votes_j) -
203  std::floor(static_cast<float>(M_PI) /
204  search_method_->getAngleDiscretizationStep())) *
205  search_method_->getAngleDiscretizationStep(),
206  Eigen::Vector3f::UnitX()) *
207  transform_mg;
208 
209  voted_poses.push_back(PoseWithVotes(max_transform, max_votes));
210  }
211  PCL_DEBUG("Done with the Hough Transform ...\n");
212 
213  // Cluster poses for filtering out outliers and obtaining more precise results
214  PoseWithVotesList results;
215  clusterPoses(voted_poses, results);
216 
217  pcl::transformPointCloud(*input_, output, results.front().pose);
218 
219  transformation_ = final_transformation_ = results.front().pose.matrix();
220  converged_ = true;
221 }
222 
223 //////////////////////////////////////////////////////////////////////////////////////////////
224 template <typename PointSource, typename PointTarget>
225 void
229 {
230  PCL_INFO("Clustering poses ...\n");
231  // Start off by sorting the poses by the number of votes
232  sort(poses.begin(), poses.end(), poseWithVotesCompareFunction);
233 
234  std::vector<PoseWithVotesList> clusters;
235  std::vector<std::pair<std::size_t, unsigned int>> cluster_votes;
236  for (std::size_t poses_i = 0; poses_i < poses.size(); ++poses_i) {
237  bool found_cluster = false;
238  for (std::size_t clusters_i = 0; clusters_i < clusters.size(); ++clusters_i) {
239  if (posesWithinErrorBounds(poses[poses_i].pose,
240  clusters[clusters_i].front().pose)) {
241  found_cluster = true;
242  clusters[clusters_i].push_back(poses[poses_i]);
243  cluster_votes[clusters_i].second += poses[poses_i].votes;
244  break;
245  }
246  }
247 
248  if (!found_cluster) {
249  // Create a new cluster with the current pose
250  PoseWithVotesList new_cluster;
251  new_cluster.push_back(poses[poses_i]);
252  clusters.push_back(new_cluster);
253  cluster_votes.push_back(std::pair<std::size_t, unsigned int>(
254  clusters.size() - 1, poses[poses_i].votes));
255  }
256  }
257 
258  // Sort clusters by total number of votes
259  std::sort(cluster_votes.begin(), cluster_votes.end(), clusterVotesCompareFunction);
260  // Compute pose average and put them in result vector
261  /// @todo some kind of threshold for determining whether a cluster has enough votes or
262  /// not... now just taking the first three clusters
263  result.clear();
264  std::size_t max_clusters = (clusters.size() < 3) ? clusters.size() : 3;
265  for (std::size_t cluster_i = 0; cluster_i < max_clusters; ++cluster_i) {
266  PCL_INFO("Winning cluster has #votes: %d and #poses voted: %d.\n",
267  cluster_votes[cluster_i].second,
268  clusters[cluster_votes[cluster_i].first].size());
269  Eigen::Vector3f translation_average(0.0, 0.0, 0.0);
270  Eigen::Vector4f rotation_average(0.0, 0.0, 0.0, 0.0);
271  for (typename PoseWithVotesList::iterator v_it =
272  clusters[cluster_votes[cluster_i].first].begin();
273  v_it != clusters[cluster_votes[cluster_i].first].end();
274  ++v_it) {
275  translation_average += v_it->pose.translation();
276  /// averaging rotations by just averaging the quaternions in 4D space - reference
277  /// "On Averaging Rotations" by CLAUS GRAMKOW
278  rotation_average += Eigen::Quaternionf(v_it->pose.rotation()).coeffs();
279  }
280 
281  translation_average /=
282  static_cast<float>(clusters[cluster_votes[cluster_i].first].size());
283  rotation_average /=
284  static_cast<float>(clusters[cluster_votes[cluster_i].first].size());
285 
286  Eigen::Affine3f transform_average;
287  transform_average.translation().matrix() = translation_average;
288  transform_average.linear().matrix() =
289  Eigen::Quaternionf(rotation_average).normalized().toRotationMatrix();
290 
291  result.push_back(PoseWithVotes(transform_average, cluster_votes[cluster_i].second));
292  }
293 }
294 
295 //////////////////////////////////////////////////////////////////////////////////////////////
296 template <typename PointSource, typename PointTarget>
297 bool
299  Eigen::Affine3f& pose1, Eigen::Affine3f& pose2)
300 {
301  float position_diff = (pose1.translation() - pose2.translation()).norm();
302  Eigen::AngleAxisf rotation_diff_mat(
303  (pose1.rotation().inverse().lazyProduct(pose2.rotation()).eval()));
304 
305  float rotation_diff_angle = std::abs(rotation_diff_mat.angle());
306 
307  return (position_diff < clustering_position_diff_threshold_ &&
308  rotation_diff_angle < clustering_rotation_diff_threshold_);
309 }
310 
311 //////////////////////////////////////////////////////////////////////////////////////////////
312 template <typename PointSource, typename PointTarget>
313 bool
317 {
318  return (a.votes > b.votes);
319 }
320 
321 //////////////////////////////////////////////////////////////////////////////////////////////
322 template <typename PointSource, typename PointTarget>
323 bool
325  const std::pair<std::size_t, unsigned int>& a,
326  const std::pair<std::size_t, unsigned int>& b)
327 {
328  return (a.second > b.second);
329 }
330 
331 //#define PCL_INSTANTIATE_PPFRegistration(PointSource,PointTarget) template class
332 // PCL_EXPORTS pcl::PPFRegistration<PointSource, PointTarget>;
333 
334 #endif // PCL_REGISTRATION_IMPL_PPF_REGISTRATION_H_
pcl::Registration
Registration represents the base registration class for general purpose, ICP-like methods.
Definition: registration.h:57
pcl::PPFRegistration::setInputTarget
void setInputTarget(const PointCloudTargetConstPtr &cloud) override
Provide a pointer to the input target (e.g., the point cloud that we want to align the input source t...
Definition: ppf_registration.hpp:53
pcl::PPFRegistration::PointCloudTargetConstPtr
typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr
Definition: ppf_registration.h:208
pcl::device::normalized
__device__ __forceinline__ float3 normalized(const float3 &v)
Definition: utils.hpp:101
pcl::transformPointCloud
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 4, 4 > &transform, bool copy_all_fields)
Apply a rigid transform defined by a 4x4 matrix.
Definition: transforms.hpp:221
pcl::PPFRegistration::PoseWithVotesList
std::vector< PoseWithVotes, Eigen::aligned_allocator< PoseWithVotes > > PoseWithVotesList
Definition: ppf_registration.h:192
pcl::KdTreeFLANN< PointTarget >
M_PI
#define M_PI
Definition: pcl_macros.h:201
pcl::PPFRegistration::PoseWithVotes
Structure for storing a pose (represented as an Eigen::Affine3f) and an integer for counting votes.
Definition: ppf_registration.h:183
pcl::device::norm
__device__ __host__ __forceinline__ float norm(const float3 &v1, const float3 &v2)
Definition: vector_operations.hpp:60
pcl::PPFRegistration
Class that registers two point clouds based on their sets of PPFSignatures.
Definition: ppf_registration.h:176
pcl::PPFRegistration::PoseWithVotes::votes
unsigned int votes
Definition: ppf_registration.h:189
pcl::computePairFeatures
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...
pcl::KdTreeFLANN::Ptr
shared_ptr< KdTreeFLANN< PointT, Dist > > Ptr
Definition: kdtree_flann.h:84