Point Cloud Library (PCL)  1.14.1-dev
correspondence_estimation.hpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2011, Willow Garage, Inc.
6  * Copyright (c) 2012-, Open Perception, Inc.
7  *
8  * All rights reserved.
9  *
10  * Redistribution and use in source and binary forms, with or without
11  * modification, are permitted provided that the following conditions
12  * are met:
13  *
14  * * Redistributions of source code must retain the above copyright
15  * notice, this list of conditions and the following disclaimer.
16  * * Redistributions in binary form must reproduce the above
17  * copyright notice, this list of conditions and the following
18  * disclaimer in the documentation and/or other materials provided
19  * with the distribution.
20  * * Neither the name of the copyright holder(s) nor the names of its
21  * contributors may be used to endorse or promote products derived
22  * from this software without specific prior written permission.
23  *
24  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
25  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
26  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
27  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
28  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
29  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
30  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
32  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
33  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
34  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35  * POSSIBILITY OF SUCH DAMAGE.
36  *
37  * $Id$
38  *
39  */
40 
41 #ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_ESTIMATION_H_
42 #define PCL_REGISTRATION_IMPL_CORRESPONDENCE_ESTIMATION_H_
43 
44 #include <pcl/common/copy_point.h>
45 #include <pcl/common/io.h>
46 
47 namespace pcl {
48 
49 namespace registration {
50 
51 template <typename PointSource, typename PointTarget, typename Scalar>
52 void
54  const PointCloudTargetConstPtr& cloud)
55 {
56  if (cloud->points.empty()) {
57  PCL_ERROR("[pcl::registration::%s::setInputTarget] Invalid or empty point cloud "
58  "dataset given!\n",
59  getClassName().c_str());
60  return;
61  }
62  target_ = cloud;
63 
64  // Set the internal point representation of choice
65  if (point_representation_)
66  tree_->setPointRepresentation(point_representation_);
67 
68  target_cloud_updated_ = true;
69 }
70 
71 template <typename PointSource, typename PointTarget, typename Scalar>
72 bool
74 {
75  if (!target_) {
76  PCL_ERROR("[pcl::registration::%s::compute] No input target dataset was given!\n",
77  getClassName().c_str());
78  return (false);
79  }
80 
81  // Only update target kd-tree if a new target cloud was set
82  if (target_cloud_updated_ && !force_no_recompute_) {
83  // If the target indices have been given via setIndicesTarget
84  if (target_indices_)
85  tree_->setInputCloud(target_, target_indices_);
86  else
87  tree_->setInputCloud(target_);
88 
89  target_cloud_updated_ = false;
90  }
91 
93 }
94 
95 template <typename PointSource, typename PointTarget, typename Scalar>
96 bool
98 {
99  // Only update source kd-tree if a new target cloud was set
100  if (source_cloud_updated_ && !force_no_recompute_reciprocal_) {
101  if (point_representation_reciprocal_)
102  tree_reciprocal_->setPointRepresentation(point_representation_reciprocal_);
103  // If the target indices have been given via setIndicesTarget
104  if (indices_)
105  tree_reciprocal_->setInputCloud(getInputSource(), getIndicesSource());
106  else
107  tree_reciprocal_->setInputCloud(getInputSource());
108 
109  source_cloud_updated_ = false;
110  }
111 
112  return (true);
113 }
114 
115 namespace detail {
116 
117 template <
118  typename PointTarget,
119  typename PointSource,
120  typename Index,
121  typename std::enable_if_t<isSamePointType<PointSource, PointTarget>()>* = nullptr>
122 const PointSource&
123 pointCopyOrRef(typename pcl::PointCloud<PointSource>::ConstPtr& input, const Index& idx)
124 {
125  return (*input)[idx];
126 }
127 
128 template <
129  typename PointTarget,
130  typename PointSource,
131  typename Index,
132  typename std::enable_if_t<!isSamePointType<PointSource, PointTarget>()>* = nullptr>
133 PointTarget
134 pointCopyOrRef(typename pcl::PointCloud<PointSource>::ConstPtr& input, const Index& idx)
135 {
136  // Copy the source data to a target PointTarget format so we can search in the tree
137  PointTarget pt;
138  copyPoint((*input)[idx], pt);
139  return pt;
140 }
141 
142 } // namespace detail
143 
144 template <typename PointSource, typename PointTarget, typename Scalar>
145 void
147  pcl::Correspondences& correspondences, double max_distance)
148 {
149  if (!initCompute())
150  return;
151 
152  correspondences.resize(indices_->size());
153 
154  pcl::Indices index(1);
155  std::vector<float> distance(1);
156  std::vector<pcl::Correspondences> per_thread_correspondences(num_threads_);
157  for (auto& corrs : per_thread_correspondences) {
158  corrs.reserve(2 * indices_->size() / num_threads_);
159  }
160  double max_dist_sqr = max_distance * max_distance;
161 
162 #pragma omp parallel for default(none) \
163  shared(max_dist_sqr, per_thread_correspondences) firstprivate(index, distance) \
164  num_threads(num_threads_)
165  // Iterate over the input set of source indices
166  for (int i = 0; i < static_cast<int>(indices_->size()); i++) {
167  const auto& idx = (*indices_)[i];
168  // Check if the template types are the same. If true, avoid a copy.
169  // Both point types MUST be registered using the POINT_CLOUD_REGISTER_POINT_STRUCT
170  // macro!
171  const auto& pt = detail::pointCopyOrRef<PointTarget, PointSource>(input_, idx);
172  tree_->nearestKSearch(pt, 1, index, distance);
173  if (distance[0] > max_dist_sqr)
174  continue;
175 
176  pcl::Correspondence corr;
177  corr.index_query = idx;
178  corr.index_match = index[0];
179  corr.distance = distance[0];
180 
181 #ifdef _OPENMP
182  const int thread_num = omp_get_thread_num();
183 #else
184  const int thread_num = 0;
185 #endif
186 
187  per_thread_correspondences[thread_num].emplace_back(corr);
188  }
189 
190  if (num_threads_ == 1) {
191  correspondences = std::move(per_thread_correspondences.front());
192  }
193  else {
194  const unsigned int nr_correspondences = std::accumulate(
195  per_thread_correspondences.begin(),
196  per_thread_correspondences.end(),
197  static_cast<unsigned int>(0),
198  [](const auto sum, const auto& corr) { return sum + corr.size(); });
199  correspondences.resize(nr_correspondences);
200 
201  // Merge per-thread correspondences while keeping them ordered
202  auto insert_loc = correspondences.begin();
203  for (const auto& corrs : per_thread_correspondences) {
204  const auto new_insert_loc = std::move(corrs.begin(), corrs.end(), insert_loc);
205  std::inplace_merge(correspondences.begin(),
206  insert_loc,
207  insert_loc + corrs.size(),
208  [](const auto& lhs, const auto& rhs) {
209  return lhs.index_query < rhs.index_query;
210  });
211  insert_loc = new_insert_loc;
212  }
213  }
214  deinitCompute();
215 }
216 
217 template <typename PointSource, typename PointTarget, typename Scalar>
218 void
221  double max_distance)
222 {
223  if (!initCompute())
224  return;
225 
226  // setup tree for reciprocal search
227  // Set the internal point representation of choice
228  if (!initComputeReciprocal())
229  return;
230  double max_dist_sqr = max_distance * max_distance;
231 
232  correspondences.resize(indices_->size());
233  pcl::Indices index(1);
234  std::vector<float> distance(1);
235  pcl::Indices index_reciprocal(1);
236  std::vector<float> distance_reciprocal(1);
237  std::vector<pcl::Correspondences> per_thread_correspondences(num_threads_);
238  for (auto& corrs : per_thread_correspondences) {
239  corrs.reserve(2 * indices_->size() / num_threads_);
240  }
241 
242 #pragma omp parallel for default(none) \
243  shared(max_dist_sqr, per_thread_correspondences) \
244  firstprivate(index, distance, index_reciprocal, distance_reciprocal) \
245  num_threads(num_threads_)
246  // Iterate over the input set of source indices
247  for (int i = 0; i < static_cast<int>(indices_->size()); i++) {
248  const auto& idx = (*indices_)[i];
249  // Check if the template types are the same. If true, avoid a copy.
250  // Both point types MUST be registered using the POINT_CLOUD_REGISTER_POINT_STRUCT
251  // macro!
252 
253  const auto& pt_src = detail::pointCopyOrRef<PointTarget, PointSource>(input_, idx);
254 
255  tree_->nearestKSearch(pt_src, 1, index, distance);
256  if (distance[0] > max_dist_sqr)
257  continue;
258 
259  const auto target_idx = index[0];
260  const auto& pt_tgt =
261  detail::pointCopyOrRef<PointSource, PointTarget>(target_, target_idx);
262 
263  tree_reciprocal_->nearestKSearch(pt_tgt, 1, index_reciprocal, distance_reciprocal);
264  if (distance_reciprocal[0] > max_dist_sqr || idx != index_reciprocal[0])
265  continue;
266 
267  pcl::Correspondence corr;
268  corr.index_query = idx;
269  corr.index_match = index[0];
270  corr.distance = distance[0];
271 
272 #ifdef _OPENMP
273  const int thread_num = omp_get_thread_num();
274 #else
275  const int thread_num = 0;
276 #endif
277 
278  per_thread_correspondences[thread_num].emplace_back(corr);
279  }
280 
281  if (num_threads_ == 1) {
282  correspondences = std::move(per_thread_correspondences.front());
283  }
284  else {
285  const unsigned int nr_correspondences = std::accumulate(
286  per_thread_correspondences.begin(),
287  per_thread_correspondences.end(),
288  static_cast<unsigned int>(0),
289  [](const auto sum, const auto& corr) { return sum + corr.size(); });
290  correspondences.resize(nr_correspondences);
291 
292  // Merge per-thread correspondences while keeping them ordered
293  auto insert_loc = correspondences.begin();
294  for (const auto& corrs : per_thread_correspondences) {
295  const auto new_insert_loc = std::move(corrs.begin(), corrs.end(), insert_loc);
296  std::inplace_merge(correspondences.begin(),
297  insert_loc,
298  insert_loc + corrs.size(),
299  [](const auto& lhs, const auto& rhs) {
300  return lhs.index_query < rhs.index_query;
301  });
302  insert_loc = new_insert_loc;
303  }
304  }
305 
306  deinitCompute();
307 }
308 
309 } // namespace registration
310 } // namespace pcl
311 
312 //#define PCL_INSTANTIATE_CorrespondenceEstimation(T,U) template class PCL_EXPORTS
313 // pcl::registration::CorrespondenceEstimation<T,U>;
314 
315 #endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_ESTIMATION_H_ */
PCL base class.
Definition: pcl_base.h:70
shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:414
bool initCompute()
Internal computation initialization.
typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr
void setInputTarget(const PointCloudTargetConstPtr &cloud)
Provide a pointer to the input target (e.g., the point cloud that we want to align the input source t...
bool initComputeReciprocal()
Internal computation initialization for reciprocal correspondences.
void determineCorrespondences(pcl::Correspondences &correspondences, double max_distance=std::numeric_limits< double >::max()) override
Determine the correspondences between input and target cloud.
void determineReciprocalCorrespondences(pcl::Correspondences &correspondences, double max_distance=std::numeric_limits< double >::max()) override
Determine the reciprocal correspondences between input and target cloud.
void copyPoint(const PointInT &point_in, PointOutT &point_out)
Copy the fields of a source point into a target point.
Definition: copy_point.hpp:137
float distance(const PointT &p1, const PointT &p2)
Definition: geometry.h:60
const PointSource & pointCopyOrRef(typename pcl::PointCloud< PointSource >::ConstPtr &input, const Index &idx)
std::vector< pcl::Correspondence, Eigen::aligned_allocator< pcl::Correspondence > > Correspondences
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:133
Correspondence represents a match between two entities (e.g., points, descriptors,...
index_t index_query
Index of the query (source) point.
index_t index_match
Index of the matching (target) point.