Point Cloud Library (PCL)  1.11.1-dev
correspondence_estimation_normal_shooting.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/registration/correspondence_estimation.h>
44 #include <pcl/registration/correspondence_types.h>
45 
46 namespace pcl {
47 namespace registration {
48 /** \brief @b CorrespondenceEstimationNormalShooting computes
49  * correspondences as points in the target cloud which have minimum
50  * distance to normals computed on the input cloud
51  *
52  * Code example:
53  *
54  * \code
55  * pcl::PointCloud<pcl::PointNormal>::Ptr source, target;
56  * // ... read or fill in source and target
57  * pcl::CorrespondenceEstimationNormalShooting<pcl::PointNormal, pcl::PointNormal,
58  * pcl::PointNormal> est; est.setInputSource (source); est.setSourceNormals (source);
59  *
60  * est.setInputTarget (target);
61  *
62  * // Test the first 10 correspondences for each point in source, and return the best
63  * est.setKSearch (10);
64  *
65  * pcl::Correspondences all_correspondences;
66  * // Determine all correspondences
67  * est.determineCorrespondences (all_correspondences);
68  * \endcode
69  *
70  * \author Aravindhan K. Krishnan, Radu B. Rusu
71  * \ingroup registration
72  */
73 template <typename PointSource,
74  typename PointTarget,
75  typename NormalT,
76  typename Scalar = float>
78 : public CorrespondenceEstimationBase<PointSource, PointTarget, Scalar> {
79 public:
80  using Ptr = shared_ptr<CorrespondenceEstimationNormalShooting<PointSource,
81  PointTarget,
82  NormalT,
83  Scalar>>;
84  using ConstPtr = shared_ptr<const CorrespondenceEstimationNormalShooting<PointSource,
85  PointTarget,
86  NormalT,
87  Scalar>>;
88 
101 
103  using KdTreePtr = typename KdTree::Ptr;
104 
108 
112 
116 
117  /** \brief Empty constructor.
118  *
119  * \note
120  * Sets the number of neighbors to be considered in the target point cloud (k_) to 10.
121  */
123  : source_normals_(), source_normals_transformed_(), k_(10)
124  {
125  corr_name_ = "CorrespondenceEstimationNormalShooting";
126  }
127 
128  /** \brief Empty destructor */
130 
131  /** \brief Set the normals computed on the source point cloud
132  * \param[in] normals the normals computed for the source cloud
133  */
134  inline void
136  {
137  source_normals_ = normals;
138  }
139 
140  /** \brief Get the normals of the source point cloud
141  */
142  inline NormalsConstPtr
144  {
145  return (source_normals_);
146  }
147 
148  /** \brief See if this rejector requires source normals */
149  bool
150  requiresSourceNormals() const override
151  {
152  return (true);
153  }
154 
155  /** \brief Blob method for setting the source normals */
156  void
158  {
159  NormalsPtr cloud(new PointCloudNormals);
160  fromPCLPointCloud2(*cloud2, *cloud);
161  setSourceNormals(cloud);
162  }
163 
164  /** \brief Determine the correspondences between input and target cloud.
165  * \param[out] correspondences the found correspondences (index of query point, index
166  * of target point, distance) \param[in] max_distance maximum distance between the
167  * normal on the source point cloud and the corresponding point in the target point
168  * cloud
169  */
170  void
172  pcl::Correspondences& correspondences,
173  double max_distance = std::numeric_limits<double>::max()) override;
174 
175  /** \brief Determine the reciprocal correspondences between input and target cloud.
176  * A correspondence is considered reciprocal if both Src_i has Tgt_i as a
177  * correspondence, and Tgt_i has Src_i as one.
178  *
179  * \param[out] correspondences the found correspondences (index of query and target
180  * point, distance) \param[in] max_distance maximum allowed distance between
181  * correspondences
182  */
183  void
185  pcl::Correspondences& correspondences,
186  double max_distance = std::numeric_limits<double>::max()) override;
187 
188  /** \brief Set the number of nearest neighbours to be considered in the target
189  * point cloud. By default, we use k = 10 nearest neighbors.
190  *
191  * \param[in] k the number of nearest neighbours to be considered
192  */
193  inline void
194  setKSearch(unsigned int k)
195  {
196  k_ = k;
197  }
198 
199  /** \brief Get the number of nearest neighbours considered in the target point
200  * cloud for computing correspondences. By default we use k = 10 nearest
201  * neighbors.
202  */
203  inline unsigned int
204  getKSearch() const
205  {
206  return (k_);
207  }
208 
209  /** \brief Clone and cast to CorrespondenceEstimationBase */
211  clone() const override
212  {
213  Ptr copy(new CorrespondenceEstimationNormalShooting<PointSource,
214  PointTarget,
215  NormalT,
216  Scalar>(*this));
217  return (copy);
218  }
219 
220 protected:
226 
227  /** \brief Internal computation initialization. */
228  bool
229  initCompute();
230 
231 private:
232  /** \brief The normals computed at each point in the source cloud */
233  NormalsConstPtr source_normals_;
234 
235  /** \brief The normals computed at each point in the source cloud */
236  NormalsPtr source_normals_transformed_;
237 
238  /** \brief The number of neighbours to be considered in the target point cloud */
239  unsigned int k_;
240 };
241 } // namespace registration
242 } // namespace pcl
243 
244 #include <pcl/registration/impl/correspondence_estimation_normal_shooting.hpp>
pcl
Definition: convolution.h:46
pcl::Normal
A point structure representing normal coordinates and the surface curvature estimate.
Definition: point_types.hpp:812
pcl::registration::CorrespondenceEstimationNormalShooting::determineCorrespondences
void determineCorrespondences(pcl::Correspondences &correspondences, double max_distance=std::numeric_limits< double >::max()) override
Determine the correspondences between input and target cloud.
Definition: correspondence_estimation_normal_shooting.hpp:69
pcl::registration::CorrespondenceEstimationNormalShooting
CorrespondenceEstimationNormalShooting computes correspondences as points in the target cloud which h...
Definition: correspondence_estimation_normal_shooting.h:77
pcl::registration::CorrespondenceEstimationNormalShooting::PointCloudSourceConstPtr
typename PointCloudSource::ConstPtr PointCloudSourceConstPtr
Definition: correspondence_estimation_normal_shooting.h:107
pcl::registration::CorrespondenceEstimationNormalShooting::ConstPtr
shared_ptr< const CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar > > ConstPtr
Definition: correspondence_estimation_normal_shooting.h:87
pcl::registration::CorrespondenceEstimationNormalShooting::getKSearch
unsigned int getKSearch() const
Get the number of nearest neighbours considered in the target point cloud for computing correspondenc...
Definition: correspondence_estimation_normal_shooting.h:204
pcl::registration::CorrespondenceEstimationNormalShooting::determineReciprocalCorrespondences
void determineReciprocalCorrespondences(pcl::Correspondences &correspondences, double max_distance=std::numeric_limits< double >::max()) override
Determine the reciprocal correspondences between input and target cloud.
Definition: correspondence_estimation_normal_shooting.hpp:178
pcl::registration::CorrespondenceEstimationNormalShooting::clone
CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::Ptr clone() const override
Clone and cast to CorrespondenceEstimationBase.
Definition: correspondence_estimation_normal_shooting.h:211
pcl::registration::CorrespondenceEstimationNormalShooting::setSourceNormals
void setSourceNormals(const NormalsConstPtr &normals)
Set the normals computed on the source point cloud.
Definition: correspondence_estimation_normal_shooting.h:135
pcl::registration::CorrespondenceEstimationNormalShooting::CorrespondenceEstimationNormalShooting
CorrespondenceEstimationNormalShooting()
Empty constructor.
Definition: correspondence_estimation_normal_shooting.h:122
pcl::registration::CorrespondenceEstimationNormalShooting::Ptr
shared_ptr< CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar > > Ptr
Definition: correspondence_estimation_normal_shooting.h:83
pcl::PCLBase
PCL base class.
Definition: pcl_base.h:69
pcl::registration::CorrespondenceEstimationBase
Abstract CorrespondenceEstimationBase class.
Definition: correspondence_estimation.h:60
pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, float >::tree_reciprocal_
KdTreeReciprocalPtr tree_reciprocal_
A pointer to the spatial search object used for the source dataset.
Definition: correspondence_estimation.h:300
pcl::PointCloud< PointSource >
pcl::search::KdTree::Ptr
shared_ptr< KdTree< PointT, Tree > > Ptr
Definition: kdtree.h:75
pcl::registration::CorrespondenceEstimationNormalShooting::PointCloudSourcePtr
typename PointCloudSource::Ptr PointCloudSourcePtr
Definition: correspondence_estimation_normal_shooting.h:106
pcl::registration::CorrespondenceEstimationNormalShooting::NormalsConstPtr
typename PointCloudNormals::ConstPtr NormalsConstPtr
Definition: correspondence_estimation_normal_shooting.h:115
pcl::registration::CorrespondenceEstimationNormalShooting::PointCloudTargetConstPtr
typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr
Definition: correspondence_estimation_normal_shooting.h:111
pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, float >::initComputeReciprocal
bool initComputeReciprocal()
Internal computation initialization for reciprocal correspondences.
Definition: correspondence_estimation.hpp:97
pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, float >::point_representation_
PointRepresentationConstPtr point_representation_
The point representation used (internal).
Definition: correspondence_estimation.h:309
pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, float >::input_transformed_
PointCloudTargetPtr input_transformed_
The transformed input source point cloud dataset.
Definition: correspondence_estimation.h:312
pcl::registration::CorrespondenceEstimationNormalShooting::NormalsPtr
typename PointCloudNormals::Ptr NormalsPtr
Definition: correspondence_estimation_normal_shooting.h:114
pcl::registration::CorrespondenceEstimationNormalShooting::KdTreePtr
typename KdTree::Ptr KdTreePtr
Definition: correspondence_estimation_normal_shooting.h:103
pcl::PCLPointCloud2::ConstPtr
shared_ptr< const ::pcl::PCLPointCloud2 > ConstPtr
Definition: PCLPointCloud2.h:36
pcl::registration::CorrespondenceEstimationBase::Ptr
shared_ptr< CorrespondenceEstimationBase< PointSource, PointTarget, Scalar > > Ptr
Definition: correspondence_estimation.h:63
pcl::registration::CorrespondenceEstimationNormalShooting::initCompute
bool initCompute()
Internal computation initialization.
Definition: correspondence_estimation_normal_shooting.hpp:53
pcl::registration::CorrespondenceEstimationNormalShooting::setKSearch
void setKSearch(unsigned int k)
Set the number of nearest neighbours to be considered in the target point cloud.
Definition: correspondence_estimation_normal_shooting.h:194
pcl::search::KdTree
search::KdTree is a wrapper class which inherits the pcl::KdTree class for performing search function...
Definition: kdtree.h:61
pcl::registration::CorrespondenceEstimationNormalShooting::requiresSourceNormals
bool requiresSourceNormals() const override
See if this rejector requires source normals.
Definition: correspondence_estimation_normal_shooting.h:150
pcl::registration::CorrespondenceEstimationNormalShooting::~CorrespondenceEstimationNormalShooting
~CorrespondenceEstimationNormalShooting()
Empty destructor.
Definition: correspondence_estimation_normal_shooting.h:129
pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, float >::corr_name_
std::string corr_name_
The correspondence estimation method name.
Definition: correspondence_estimation.h:294
pcl::registration::CorrespondenceEstimationNormalShooting::setSourceNormals
void setSourceNormals(pcl::PCLPointCloud2::ConstPtr cloud2) override
Blob method for setting the source normals.
Definition: correspondence_estimation_normal_shooting.h:157
pcl::PointCloud< PointSource >::Ptr
shared_ptr< PointCloud< PointSource > > Ptr
Definition: point_cloud.h:406
pcl::PointCloud< PointSource >::ConstPtr
shared_ptr< const PointCloud< PointSource > > ConstPtr
Definition: point_cloud.h:407
pcl::registration::CorrespondenceEstimationNormalShooting::PointCloudTargetPtr
typename PointCloudTarget::Ptr PointCloudTargetPtr
Definition: correspondence_estimation_normal_shooting.h:110
pcl::registration::CorrespondenceEstimationNormalShooting::getSourceNormals
NormalsConstPtr getSourceNormals() const
Get the normals of the source point cloud.
Definition: correspondence_estimation_normal_shooting.h:143
pcl::Correspondences
std::vector< pcl::Correspondence, Eigen::aligned_allocator< pcl::Correspondence > > Correspondences
Definition: correspondence.h:89
pcl::fromPCLPointCloud2
void fromPCLPointCloud2(const pcl::PCLPointCloud2 &msg, pcl::PointCloud< PointT > &cloud, const MsgFieldMap &field_map)
Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map.
Definition: conversions.h:167