Point Cloud Library (PCL) 1.13.0
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
52namespace pcl {
53namespace 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 */
59template <typename PointSource, typename PointTarget, typename Scalar = float>
60class CorrespondenceEstimationBase : public PCLBase<PointSource> {
61public:
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;
68 using PCLBase<PointSource>::deinitCompute;
69 using PCLBase<PointSource>::input_;
70 using PCLBase<PointSource>::indices_;
71 using PCLBase<PointSource>::setIndices;
72
74 using KdTreePtr = typename KdTree::Ptr;
75
78
82
86
88
89 /** \brief Empty constructor. */
91 : corr_name_("CorrespondenceEstimationBase")
92 , tree_(new pcl::search::KdTree<PointTarget>)
93 , tree_reciprocal_(new pcl::search::KdTree<PointSource>)
94 , target_()
99 , force_no_recompute_(false)
101 {}
102
103 /** \brief Empty destructor */
104 ~CorrespondenceEstimationBase() override = default;
105
106 /** \brief Provide a pointer to the input source
107 * (e.g., the point cloud that we want to align to the target)
108 *
109 * \param[in] cloud the input point cloud source
110 */
111 inline void
113 {
116 input_fields_ = pcl::getFields<PointSource>();
117 }
118
119 /** \brief Get a pointer to the input point cloud dataset target. */
120 inline PointCloudSourceConstPtr const
122 {
123 return (input_);
124 }
125
126 /** \brief Provide a pointer to the input target
127 * (e.g., the point cloud that we want to align the input source to)
128 * \param[in] cloud the input point cloud target
129 */
130 inline void
132
133 /** \brief Get a pointer to the input point cloud dataset target. */
134 inline PointCloudTargetConstPtr const
136 {
137 return (target_);
138 }
139
140 /** \brief See if this rejector requires source normals */
141 virtual bool
143 {
144 return (false);
145 }
146
147 /** \brief Abstract method for setting the source normals */
148 virtual void
150 {
151 PCL_WARN("[pcl::registration::%s::setSourceNormals] This class does not require "
152 "input source normals\n",
153 getClassName().c_str());
154 }
155
156 /** \brief See if this rejector requires target normals */
157 virtual bool
159 {
160 return (false);
161 }
162
163 /** \brief Abstract method for setting the target normals */
164 virtual void
166 {
167 PCL_WARN("[pcl::registration::%s::setTargetNormals] This class does not require "
168 "input target normals\n",
169 getClassName().c_str());
170 }
171
172 /** \brief Provide a pointer to the vector of indices that represent the
173 * input source point cloud.
174 * \param[in] indices a pointer to the vector of indices
175 */
176 inline void
178 {
179 setIndices(indices);
180 }
181
182 /** \brief Get a pointer to the vector of indices used for the source dataset. */
183 inline IndicesPtr const
185 {
186 return (indices_);
187 }
188
189 /** \brief Provide a pointer to the vector of indices that represent the input target
190 * point cloud. \param[in] indices a pointer to the vector of indices
191 */
192 inline void
194 {
196 target_indices_ = indices;
197 }
198
199 /** \brief Get a pointer to the vector of indices used for the target dataset. */
200 inline IndicesPtr const
202 {
203 return (target_indices_);
204 }
205
206 /** \brief Provide a pointer to the search object used to find correspondences in
207 * the target cloud.
208 * \param[in] tree a pointer to the spatial search object.
209 * \param[in] force_no_recompute If set to true, this tree will NEVER be
210 * recomputed, regardless of calls to setInputTarget. Only use if you are
211 * confident that the tree will be set correctly.
212 */
213 inline void
214 setSearchMethodTarget(const KdTreePtr& tree, bool force_no_recompute = false)
215 {
216 tree_ = tree;
217 force_no_recompute_ = force_no_recompute;
218 // Since we just set a new tree, we need to check for updates
220 }
221
222 /** \brief Get a pointer to the search method used to find correspondences in the
223 * target cloud. */
224 inline KdTreePtr
226 {
227 return (tree_);
228 }
229
230 /** \brief Provide a pointer to the search object used to find correspondences in
231 * the source cloud (usually used by reciprocal correspondence finding).
232 * \param[in] tree a pointer to the spatial search object.
233 * \param[in] force_no_recompute If set to true, this tree will NEVER be
234 * recomputed, regardless of calls to setInputSource. Only use if you are
235 * extremely confident that the tree will be set correctly.
236 */
237 inline void
239 bool force_no_recompute = false)
240 {
241 tree_reciprocal_ = tree;
242 force_no_recompute_reciprocal_ = force_no_recompute;
243 // Since we just set a new tree, we need to check for updates
245 }
246
247 /** \brief Get a pointer to the search method used to find correspondences in the
248 * source cloud. */
251 {
252 return (tree_reciprocal_);
253 }
254
255 /** \brief Determine the correspondences between input and target cloud.
256 * \param[out] correspondences the found correspondences (index of query point, index
257 * of target point, distance) \param[in] max_distance maximum allowed distance between
258 * correspondences
259 */
260 virtual void
262 pcl::Correspondences& correspondences,
263 double max_distance = std::numeric_limits<double>::max()) = 0;
264
265 /** \brief Determine the reciprocal correspondences between input and target cloud.
266 * A correspondence is considered reciprocal if both Src_i has Tgt_i as a
267 * correspondence, and Tgt_i has Src_i as one.
268 *
269 * \param[out] correspondences the found correspondences (index of query and target
270 * point, distance) \param[in] max_distance maximum allowed distance between
271 * correspondences
272 */
273 virtual void
275 pcl::Correspondences& correspondences,
276 double max_distance = std::numeric_limits<double>::max()) = 0;
277
278 /** \brief Provide a boost shared pointer to the PointRepresentation to be used
279 * when searching for nearest neighbors.
280 *
281 * \param[in] point_representation the PointRepresentation to be used by the
282 * k-D tree for nearest neighbor search
283 */
284 inline void
286 {
287 point_representation_ = point_representation;
288 }
289
290 /** \brief Clone and cast to CorrespondenceEstimationBase */
292 clone() const = 0;
293
294protected:
295 /** \brief The correspondence estimation method name. */
296 std::string corr_name_;
297
298 /** \brief A pointer to the spatial search object used for the target dataset. */
300
301 /** \brief A pointer to the spatial search object used for the source dataset. */
303
304 /** \brief The input point cloud dataset target. */
306
307 /** \brief The target point cloud dataset indices. */
309
310 /** \brief The point representation used (internal). */
312
313 /** \brief The transformed input source point cloud dataset. */
315
316 /** \brief The types of input point fields available. */
317 std::vector<pcl::PCLPointField> input_fields_;
318
319 /** \brief Abstract class get name method. */
320 inline const std::string&
322 {
323 return (corr_name_);
324 }
325
326 /** \brief Internal computation initialization. */
327 bool
328 initCompute();
329
330 /** \brief Internal computation initialization for reciprocal correspondences. */
331 bool
333
334 /** \brief Variable that stores whether we have a new target cloud, meaning we need to
335 * pre-process it again. This way, we avoid rebuilding the kd-tree for the target
336 * cloud every time the determineCorrespondences () method is called. */
338 /** \brief Variable that stores whether we have a new source cloud, meaning we need to
339 * pre-process it again. This way, we avoid rebuilding the reciprocal kd-tree for the
340 * source cloud every time the determineCorrespondences () method is called. */
342 /** \brief A flag which, if set, means the tree operating on the target cloud
343 * will never be recomputed*/
345
346 /** \brief A flag which, if set, means the tree operating on the source cloud
347 * will never be recomputed*/
349};
350
351/** \brief @b CorrespondenceEstimation represents the base class for
352 * determining correspondences between target and query point
353 * sets/features.
354 *
355 * Code example:
356 *
357 * \code
358 * pcl::PointCloud<pcl::PointXYZRGBA>::Ptr source, target;
359 * // ... read or fill in source and target
360 * pcl::CorrespondenceEstimation<pcl::PointXYZ, pcl::PointXYZ> est;
361 * est.setInputSource (source);
362 * est.setInputTarget (target);
363 *
364 * pcl::Correspondences all_correspondences;
365 * // Determine all reciprocal correspondences
366 * est.determineReciprocalCorrespondences (all_correspondences);
367 * \endcode
368 *
369 * \author Radu B. Rusu, Michael Dixon, Dirk Holz
370 * \ingroup registration
371 */
372template <typename PointSource, typename PointTarget, typename Scalar = float>
374: public CorrespondenceEstimationBase<PointSource, PointTarget, Scalar> {
375public:
376 using Ptr = shared_ptr<CorrespondenceEstimation<PointSource, PointTarget, Scalar>>;
377 using ConstPtr =
378 shared_ptr<const CorrespondenceEstimation<PointSource, PointTarget, Scalar>>;
379
380 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::
382 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::
384 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::tree_;
385 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::
387 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::target_;
388 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::corr_name_;
389 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::target_indices_;
390 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::getClassName;
391 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::initCompute;
392 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::
394 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::input_;
395 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::indices_;
396 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::input_fields_;
397 using PCLBase<PointSource>::deinitCompute;
398
400 using KdTreePtr = typename KdTree::Ptr;
401
405
409
411
412 /** \brief Empty constructor. */
413 CorrespondenceEstimation() { corr_name_ = "CorrespondenceEstimation"; }
414
415 /** \brief Empty destructor */
416 ~CorrespondenceEstimation() override = default;
417
418 /** \brief Determine the correspondences between input and target cloud.
419 * \param[out] correspondences the found correspondences (index of query point, index
420 * of target point, distance) \param[in] max_distance maximum allowed distance between
421 * correspondences
422 */
423 void
425 pcl::Correspondences& correspondences,
426 double max_distance = std::numeric_limits<double>::max()) override;
427
428 /** \brief Determine the reciprocal correspondences between input and target cloud.
429 * A correspondence is considered reciprocal if both Src_i has Tgt_i as a
430 * correspondence, and Tgt_i has Src_i as one.
431 *
432 * \param[out] correspondences the found correspondences (index of query and target
433 * point, distance) \param[in] max_distance maximum allowed distance between
434 * correspondences
435 */
436 void
438 pcl::Correspondences& correspondences,
439 double max_distance = std::numeric_limits<double>::max()) override;
440
441 /** \brief Clone and cast to CorrespondenceEstimationBase */
443 clone() const override
444 {
446 return (copy);
447 }
448};
449} // namespace registration
450} // namespace pcl
451
452#include <pcl/registration/impl/correspondence_estimation.hpp>
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
bool deinitCompute()
This method should get called after finishing the actual computation.
Definition: pcl_base.hpp:174
shared_ptr< PointCloud< PointSource > > Ptr
Definition: point_cloud.h:413
shared_ptr< const PointCloud< PointSource > > ConstPtr
Definition: point_cloud.h:414
Abstract CorrespondenceEstimationBase class.
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 CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::Ptr clone() const =0
Clone and cast to CorrespondenceEstimationBase.
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.
void setPointRepresentation(const PointRepresentationConstPtr &point_representation)
Provide a boost shared pointer to the PointRepresentation to be used when searching for nearest neigh...
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
KdTreeReciprocalPtr getSearchMethodSource() const
Get a pointer to the search method used to find correspondences in the source cloud.
PointRepresentationConstPtr point_representation_
The 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...
const std::string & getClassName() const
Abstract class get name method.
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.
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...
void determineCorrespondences(pcl::Correspondences &correspondences, double max_distance=std::numeric_limits< double >::max()) override
Determine the correspondences between input and target cloud.
typename PointCloudSource::ConstPtr PointCloudSourceConstPtr
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
CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::Ptr clone() const override
Clone and cast to CorrespondenceEstimationBase.
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
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