Point Cloud Library (PCL)  1.13.1-dev
correspondence_estimation.h
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 #pragma once
42 
43 #include <pcl/common/io.h> // for getFields
44 #include <pcl/registration/correspondence_types.h>
45 #include <pcl/search/kdtree.h>
46 #include <pcl/memory.h>
47 #include <pcl/pcl_base.h>
48 #include <pcl/pcl_macros.h>
49 
50 #include <string>
51 
52 namespace pcl {
53 namespace registration {
54 /** \brief Abstract @b CorrespondenceEstimationBase class.
55  * All correspondence estimation methods should inherit from this.
56  * \author Radu B. Rusu
57  * \ingroup registration
58  */
59 template <typename PointSource, typename PointTarget, typename Scalar = float>
60 class CorrespondenceEstimationBase : public PCLBase<PointSource> {
61 public:
62  using Ptr =
63  shared_ptr<CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>>;
64  using ConstPtr =
65  shared_ptr<const CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>>;
66 
67  // using PCLBase<PointSource>::initCompute;
72 
74  using KdTreePtr = typename KdTree::Ptr;
75  using KdTreeConstPtr = typename KdTree::ConstPtr;
76 
80 
84 
88 
92 
93  /** \brief Empty constructor. */
95  : corr_name_("CorrespondenceEstimationBase")
96  , tree_(new pcl::search::KdTree<PointTarget>)
97  , tree_reciprocal_(new pcl::search::KdTree<PointSource>)
98  , target_()
101  , target_cloud_updated_(true)
102  , source_cloud_updated_(true)
103  , force_no_recompute_(false)
105  {}
106 
107  /** \brief Empty destructor */
108  ~CorrespondenceEstimationBase() override = default;
109 
110  /** \brief Provide a pointer to the input source
111  * (e.g., the point cloud that we want to align to the target)
112  *
113  * \param[in] cloud the input point cloud source
114  */
115  inline void
117  {
118  source_cloud_updated_ = true;
120  input_fields_ = pcl::getFields<PointSource>();
121  }
122 
123  /** \brief Get a pointer to the input point cloud dataset target. */
124  inline PointCloudSourceConstPtr const
126  {
127  return (input_);
128  }
129 
130  /** \brief Provide a pointer to the input target
131  * (e.g., the point cloud that we want to align the input source to)
132  * \param[in] cloud the input point cloud target
133  */
134  inline void
136 
137  /** \brief Get a pointer to the input point cloud dataset target. */
138  inline PointCloudTargetConstPtr const
140  {
141  return (target_);
142  }
143 
144  /** \brief See if this rejector requires source normals */
145  virtual bool
147  {
148  return (false);
149  }
150 
151  /** \brief Abstract method for setting the source normals */
152  virtual void
154  {
155  PCL_WARN("[pcl::registration::%s::setSourceNormals] This class does not require "
156  "input source normals\n",
157  getClassName().c_str());
158  }
159 
160  /** \brief See if this rejector requires target normals */
161  virtual bool
163  {
164  return (false);
165  }
166 
167  /** \brief Abstract method for setting the target normals */
168  virtual void
170  {
171  PCL_WARN("[pcl::registration::%s::setTargetNormals] This class does not require "
172  "input target normals\n",
173  getClassName().c_str());
174  }
175 
176  /** \brief Provide a pointer to the vector of indices that represent the
177  * input source point cloud.
178  * \param[in] indices a pointer to the vector of indices
179  */
180  inline void
181  setIndicesSource(const IndicesPtr& indices)
182  {
183  setIndices(indices);
184  }
185 
186  /** \brief Get a pointer to the vector of indices used for the source dataset. */
187  inline IndicesPtr const
189  {
190  return (indices_);
191  }
192 
193  /** \brief Provide a pointer to the vector of indices that represent the input target
194  * point cloud. \param[in] indices a pointer to the vector of indices
195  */
196  inline void
197  setIndicesTarget(const IndicesPtr& indices)
198  {
199  target_cloud_updated_ = true;
200  target_indices_ = indices;
201  }
202 
203  /** \brief Get a pointer to the vector of indices used for the target dataset. */
204  inline IndicesPtr const
206  {
207  return (target_indices_);
208  }
209 
210  /** \brief Provide a pointer to the search object used to find correspondences in
211  * the target cloud.
212  * \param[in] tree a pointer to the spatial search object.
213  * \param[in] force_no_recompute If set to true, this tree will NEVER be
214  * recomputed, regardless of calls to setInputTarget. Only use if you are
215  * confident that the tree will be set correctly.
216  */
217  inline void
218  setSearchMethodTarget(const KdTreePtr& tree, bool force_no_recompute = false)
219  {
220  tree_ = tree;
221  force_no_recompute_ = force_no_recompute;
222  // Since we just set a new tree, we need to check for updates
223  target_cloud_updated_ = true;
224  }
225 
226  /** \brief Get a pointer to the search method used to find correspondences in the
227  * target cloud. */
228  inline KdTreePtr
230  {
231  return (tree_);
232  }
233 
234  /** \brief Provide a pointer to the search object used to find correspondences in
235  * the source cloud (usually used by reciprocal correspondence finding).
236  * \param[in] tree a pointer to the spatial search object.
237  * \param[in] force_no_recompute If set to true, this tree will NEVER be
238  * recomputed, regardless of calls to setInputSource. Only use if you are
239  * extremely confident that the tree will be set correctly.
240  */
241  inline void
243  bool force_no_recompute = false)
244  {
245  tree_reciprocal_ = tree;
246  force_no_recompute_reciprocal_ = force_no_recompute;
247  // Since we just set a new tree, we need to check for updates
248  source_cloud_updated_ = true;
249  }
250 
251  /** \brief Get a pointer to the search method used to find correspondences in the
252  * source cloud. */
253  inline KdTreeReciprocalPtr
255  {
256  return (tree_reciprocal_);
257  }
258 
259  /** \brief Determine the correspondences between input and target cloud.
260  * \param[out] correspondences the found correspondences (index of query point, index
261  * of target point, distance) \param[in] max_distance maximum allowed distance between
262  * correspondences
263  */
264  virtual void
266  pcl::Correspondences& correspondences,
267  double max_distance = std::numeric_limits<double>::max()) = 0;
268 
269  /** \brief Determine the reciprocal correspondences between input and target cloud.
270  * A correspondence is considered reciprocal if both Src_i has Tgt_i as a
271  * correspondence, and Tgt_i has Src_i as one.
272  *
273  * \param[out] correspondences the found correspondences (index of query and target
274  * point, distance) \param[in] max_distance maximum allowed distance between
275  * correspondences
276  */
277  virtual void
279  pcl::Correspondences& correspondences,
280  double max_distance = std::numeric_limits<double>::max()) = 0;
281 
282  /** \brief Provide a boost shared pointer to the PointRepresentation for target cloud
283  * to be used when searching for nearest neighbors.
284  *
285  * \param[in] point_representation the PointRepresentation to be used by the
286  * k-D tree for nearest neighbor search
287  */
288  inline void
290  {
291  point_representation_ = point_representation;
292  }
293 
294  /** \brief Provide a boost shared pointer to the PointRepresentation for source cloud
295  * to be used when searching for nearest neighbors.
296  *
297  * \param[in] point_representation the PointRepresentation to be used by the
298  * k-D tree for nearest neighbor search
299  */
300  inline void
302  const PointRepresentationReciprocalConstPtr& point_representation_reciprocal)
303  {
304  point_representation_reciprocal_ = point_representation_reciprocal;
305  }
306 
307  /** \brief Clone and cast to CorrespondenceEstimationBase */
309  clone() const = 0;
310 
311 protected:
312  /** \brief The correspondence estimation method name. */
313  std::string corr_name_;
314 
315  /** \brief A pointer to the spatial search object used for the target dataset. */
317 
318  /** \brief A pointer to the spatial search object used for the source dataset. */
320 
321  /** \brief The input point cloud dataset target. */
323 
324  /** \brief The target point cloud dataset indices. */
326 
327  /** \brief The target point representation used (internal). */
329 
330  /** \brief The source point representation used (internal). */
332 
333  /** \brief The transformed input source point cloud dataset. */
335 
336  /** \brief The types of input point fields available. */
337  std::vector<pcl::PCLPointField> input_fields_;
338 
339  /** \brief Abstract class get name method. */
340  inline const std::string&
341  getClassName() const
342  {
343  return (corr_name_);
344  }
345 
346  /** \brief Internal computation initialization. */
347  bool
348  initCompute();
349 
350  /** \brief Internal computation initialization for reciprocal correspondences. */
351  bool
353 
354  /** \brief Variable that stores whether we have a new target cloud, meaning we need to
355  * pre-process it again. This way, we avoid rebuilding the kd-tree for the target
356  * cloud every time the determineCorrespondences () method is called. */
358  /** \brief Variable that stores whether we have a new source cloud, meaning we need to
359  * pre-process it again. This way, we avoid rebuilding the reciprocal kd-tree for the
360  * source cloud every time the determineCorrespondences () method is called. */
362  /** \brief A flag which, if set, means the tree operating on the target cloud
363  * will never be recomputed*/
365 
366  /** \brief A flag which, if set, means the tree operating on the source cloud
367  * will never be recomputed*/
369 };
370 
371 /** \brief @b CorrespondenceEstimation represents the base class for
372  * determining correspondences between target and query point
373  * sets/features.
374  *
375  * Code example:
376  *
377  * \code
378  * pcl::PointCloud<pcl::PointXYZRGBA>::Ptr source, target;
379  * // ... read or fill in source and target
380  * pcl::CorrespondenceEstimation<pcl::PointXYZ, pcl::PointXYZ> est;
381  * est.setInputSource (source);
382  * est.setInputTarget (target);
383  *
384  * pcl::Correspondences all_correspondences;
385  * // Determine all reciprocal correspondences
386  * est.determineReciprocalCorrespondences (all_correspondences);
387  * \endcode
388  *
389  * \author Radu B. Rusu, Michael Dixon, Dirk Holz
390  * \ingroup registration
391  */
392 template <typename PointSource, typename PointTarget, typename Scalar = float>
394 : public CorrespondenceEstimationBase<PointSource, PointTarget, Scalar> {
395 public:
396  using Ptr = shared_ptr<CorrespondenceEstimation<PointSource, PointTarget, Scalar>>;
397  using ConstPtr =
398  shared_ptr<const CorrespondenceEstimation<PointSource, PointTarget, Scalar>>;
399 
418 
419  using KdTree =
421  using KdTreePtr = typename CorrespondenceEstimationBase<PointSource,
422  PointTarget,
423  Scalar>::KdTreePtr;
424  using KdTreeConstPtr = typename CorrespondenceEstimationBase<PointSource,
425  PointTarget,
426  Scalar>::KdTreeConstPtr;
433 
437 
441 
445 
448  typename KdTreeReciprocal::PointRepresentationConstPtr;
449 
450  /** \brief Empty constructor. */
451  CorrespondenceEstimation() { corr_name_ = "CorrespondenceEstimation"; }
452 
453  /** \brief Empty destructor */
454  ~CorrespondenceEstimation() override = default;
455 
456  /** \brief Determine the correspondences between input and target cloud.
457  * \param[out] correspondences the found correspondences (index of query point, index
458  * of target point, distance) \param[in] max_distance maximum allowed distance between
459  * correspondences
460  */
461  void
463  pcl::Correspondences& correspondences,
464  double max_distance = std::numeric_limits<double>::max()) override;
465 
466  /** \brief Determine the reciprocal correspondences between input and target cloud.
467  * A correspondence is considered reciprocal if both Src_i has Tgt_i as a
468  * correspondence, and Tgt_i has Src_i as one.
469  *
470  * \param[out] correspondences the found correspondences (index of query and target
471  * point, distance) \param[in] max_distance maximum allowed distance between
472  * correspondences
473  */
474  void
476  pcl::Correspondences& correspondences,
477  double max_distance = std::numeric_limits<double>::max()) override;
478 
479  /** \brief Clone and cast to CorrespondenceEstimationBase */
481  clone() const override
482  {
484  return (copy);
485  }
486 };
487 } // namespace registration
488 } // namespace pcl
489 
490 #include <pcl/registration/impl/correspondence_estimation.hpp>
typename PointRepresentation::ConstPtr PointRepresentationConstPtr
Definition: kdtree.h:66
PCL base class.
Definition: pcl_base.h:70
PointCloudConstPtr input_
The input point cloud dataset.
Definition: pcl_base.h:147
virtual void setInputCloud(const PointCloudConstPtr &cloud)
Provide a pointer to the input dataset.
Definition: pcl_base.hpp:65
IndicesPtr indices_
A pointer to the vector of point indices to use.
Definition: pcl_base.h:150
virtual void setIndices(const IndicesPtr &indices)
Provide a pointer to the vector of indices that represents the input data.
Definition: pcl_base.hpp:72
shared_ptr< PointCloud< PointSource > > Ptr
Definition: point_cloud.h:413
shared_ptr< const PointCloud< PointSource > > ConstPtr
Definition: point_cloud.h:414
Abstract CorrespondenceEstimationBase class.
void setPointRepresentationReciprocal(const PointRepresentationReciprocalConstPtr &point_representation_reciprocal)
Provide a boost shared pointer to the PointRepresentation for source cloud to be used when searching ...
typename KdTree::PointRepresentationConstPtr PointRepresentationConstPtr
PointCloudTargetPtr input_transformed_
The transformed input source point cloud dataset.
void setSearchMethodSource(const KdTreeReciprocalPtr &tree, bool force_no_recompute=false)
Provide a pointer to the search object used to find correspondences in the source cloud (usually used...
PointCloudTargetConstPtr target_
The input point cloud dataset target.
PointCloudTargetConstPtr const getInputTarget()
Get a pointer to the input point cloud dataset target.
shared_ptr< const CorrespondenceEstimationBase< PointSource, PointTarget, Scalar > > ConstPtr
bool initCompute()
Internal computation initialization.
virtual void determineReciprocalCorrespondences(pcl::Correspondences &correspondences, double max_distance=std::numeric_limits< double >::max())=0
Determine the reciprocal correspondences between input and target cloud.
IndicesPtr const getIndicesTarget()
Get a pointer to the vector of indices used for the target dataset.
const std::string & getClassName() const
Abstract class get name method.
void setPointRepresentation(const PointRepresentationConstPtr &point_representation)
Provide a boost shared pointer to the PointRepresentation for target cloud to be used when searching ...
bool source_cloud_updated_
Variable that stores whether we have a new source cloud, meaning we need to pre-process it again.
void setSearchMethodTarget(const KdTreePtr &tree, bool force_no_recompute=false)
Provide a pointer to the search object used to find correspondences in the target cloud.
virtual void setSourceNormals(pcl::PCLPointCloud2::ConstPtr)
Abstract method for setting the source normals.
typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr
PointRepresentationReciprocalConstPtr point_representation_reciprocal_
The source point representation used (internal).
typename KdTreeReciprocal::PointRepresentationConstPtr PointRepresentationReciprocalConstPtr
KdTreeReciprocalPtr getSearchMethodSource() const
Get a pointer to the search method used to find correspondences in the source cloud.
PointRepresentationConstPtr point_representation_
The target point representation used (internal).
IndicesPtr const getIndicesSource()
Get a pointer to the vector of indices used for the source dataset.
void setInputSource(const PointCloudSourceConstPtr &cloud)
Provide a pointer to the input source (e.g., the point cloud that we want to align to the target)
virtual bool requiresTargetNormals() const
See if this rejector requires target normals.
std::vector< pcl::PCLPointField > input_fields_
The types of input point fields available.
virtual bool requiresSourceNormals() const
See if this rejector requires source normals.
std::string corr_name_
The correspondence estimation method name.
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...
virtual CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::Ptr clone() const =0
Clone and cast to CorrespondenceEstimationBase.
bool target_cloud_updated_
Variable that stores whether we have a new target cloud, meaning we need to pre-process it again.
void setIndicesSource(const IndicesPtr &indices)
Provide a pointer to the vector of indices that represent the input source point cloud.
KdTreePtr tree_
A pointer to the spatial search object used for the target dataset.
PointCloudSourceConstPtr const getInputSource()
Get a pointer to the input point cloud dataset target.
KdTreeReciprocalPtr tree_reciprocal_
A pointer to the spatial search object used for the source dataset.
virtual void setTargetNormals(pcl::PCLPointCloud2::ConstPtr)
Abstract method for setting the target normals.
typename KdTreeReciprocal::ConstPtr KdTreeReciprocalConstPtr
virtual void determineCorrespondences(pcl::Correspondences &correspondences, double max_distance=std::numeric_limits< double >::max())=0
Determine the correspondences between input and target cloud.
~CorrespondenceEstimationBase() override=default
Empty destructor.
bool initComputeReciprocal()
Internal computation initialization for reciprocal correspondences.
bool force_no_recompute_reciprocal_
A flag which, if set, means the tree operating on the source cloud will never be recomputed.
IndicesPtr target_indices_
The target point cloud dataset indices.
void setIndicesTarget(const IndicesPtr &indices)
Provide a pointer to the vector of indices that represent the input target point cloud.
typename PointCloudSource::ConstPtr PointCloudSourceConstPtr
shared_ptr< CorrespondenceEstimationBase< PointSource, PointTarget, Scalar > > Ptr
bool force_no_recompute_
A flag which, if set, means the tree operating on the target cloud will never be recomputed.
KdTreePtr getSearchMethodTarget() const
Get a pointer to the search method used to find correspondences in the target cloud.
CorrespondenceEstimation represents the base class for determining correspondences between target and...
typename CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::KdTreeReciprocalPtr KdTreeReciprocalPtr
void determineCorrespondences(pcl::Correspondences &correspondences, double max_distance=std::numeric_limits< double >::max()) override
Determine the correspondences between input and target cloud.
typename KdTreeReciprocal::PointRepresentationConstPtr PointRepresentationReciprocalConstPtr
typename CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::KdTreeReciprocalConstPtr KdTreeReciprocalConstPtr
CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::Ptr clone() const override
Clone and cast to CorrespondenceEstimationBase.
typename CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::KdTree KdTree
typename PointCloudSource::ConstPtr PointCloudSourceConstPtr
typename CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::KdTreeConstPtr KdTreeConstPtr
shared_ptr< CorrespondenceEstimation< PointSource, PointTarget, Scalar > > Ptr
void determineReciprocalCorrespondences(pcl::Correspondences &correspondences, double max_distance=std::numeric_limits< double >::max()) override
Determine the reciprocal correspondences between input and target cloud.
shared_ptr< const CorrespondenceEstimation< PointSource, PointTarget, Scalar > > ConstPtr
typename KdTree::PointRepresentationConstPtr PointRepresentationConstPtr
~CorrespondenceEstimation() override=default
Empty destructor.
typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr
typename CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::KdTreePtr KdTreePtr
typename CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::KdTreeReciprocal KdTreeReciprocal
search::KdTree is a wrapper class which inherits the pcl::KdTree class for performing search function...
Definition: kdtree.h:62
shared_ptr< KdTree< PointT, Tree > > Ptr
Definition: kdtree.h:75
shared_ptr< const KdTree< PointT, Tree > > ConstPtr
Definition: kdtree.h:76
typename PointRepresentation< PointT >::ConstPtr PointRepresentationConstPtr
Definition: kdtree.h:80
Defines functions, macros and traits for allocating and using memory.
std::vector< pcl::Correspondence, Eigen::aligned_allocator< pcl::Correspondence > > Correspondences
shared_ptr< Indices > IndicesPtr
Definition: pcl_base.h:58
Defines all the PCL and non-PCL macros used.
shared_ptr< const ::pcl::PCLPointCloud2 > ConstPtr