Point Cloud Library (PCL) 1.12.0
Loading...
Searching...
No Matches
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 =
64 using ConstPtr =
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_()
101 {}
102
103 /** \brief Empty destructor */
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
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 */
149 {
150 PCL_WARN("[pcl::registration::%s::setSourceNormals] This class does not require "
151 "input source normals\n",
152 getClassName().c_str());
153 }
154
155 /** \brief See if this rejector requires target normals */
156 virtual bool
158 {
159 return (false);
160 }
161
162 /** \brief Abstract method for setting the target normals */
164 {
165 PCL_WARN("[pcl::registration::%s::setTargetNormals] This class does not require "
166 "input target normals\n",
167 getClassName().c_str());
168 }
169
170 /** \brief Provide a pointer to the vector of indices that represent the
171 * input source point cloud.
172 * \param[in] indices a pointer to the vector of indices
173 */
174 inline void
176 {
177 setIndices(indices);
178 }
179
180 /** \brief Get a pointer to the vector of indices used for the source dataset. */
181 inline IndicesPtr const
183 {
184 return (indices_);
185 }
186
187 /** \brief Provide a pointer to the vector of indices that represent the input target
188 * point cloud. \param[in] indices a pointer to the vector of indices
189 */
190 inline void
192 {
194 target_indices_ = indices;
195 }
196
197 /** \brief Get a pointer to the vector of indices used for the target dataset. */
198 inline IndicesPtr const
200 {
201 return (target_indices_);
202 }
203
204 /** \brief Provide a pointer to the search object used to find correspondences in
205 * the target cloud.
206 * \param[in] tree a pointer to the spatial search object.
207 * \param[in] force_no_recompute If set to true, this tree will NEVER be
208 * recomputed, regardless of calls to setInputTarget. Only use if you are
209 * confident that the tree will be set correctly.
210 */
211 inline void
213 {
214 tree_ = tree;
216 // Since we just set a new tree, we need to check for updates
218 }
219
220 /** \brief Get a pointer to the search method used to find correspondences in the
221 * target cloud. */
222 inline KdTreePtr
224 {
225 return (tree_);
226 }
227
228 /** \brief Provide a pointer to the search object used to find correspondences in
229 * the source cloud (usually used by reciprocal correspondence finding).
230 * \param[in] tree a pointer to the spatial search object.
231 * \param[in] force_no_recompute If set to true, this tree will NEVER be
232 * recomputed, regardless of calls to setInputSource. Only use if you are
233 * extremely confident that the tree will be set correctly.
234 */
235 inline void
237 bool force_no_recompute = false)
238 {
239 tree_reciprocal_ = tree;
241 // Since we just set a new tree, we need to check for updates
243 }
244
245 /** \brief Get a pointer to the search method used to find correspondences in the
246 * source cloud. */
249 {
250 return (tree_reciprocal_);
251 }
252
253 /** \brief Determine the correspondences between input and target cloud.
254 * \param[out] correspondences the found correspondences (index of query point, index
255 * of target point, distance) \param[in] max_distance maximum allowed distance between
256 * correspondences
257 */
258 virtual void
260 pcl::Correspondences& correspondences,
261 double max_distance = std::numeric_limits<double>::max()) = 0;
262
263 /** \brief Determine the reciprocal correspondences between input and target cloud.
264 * A correspondence is considered reciprocal if both Src_i has Tgt_i as a
265 * correspondence, and Tgt_i has Src_i as one.
266 *
267 * \param[out] correspondences the found correspondences (index of query and target
268 * point, distance) \param[in] max_distance maximum allowed distance between
269 * correspondences
270 */
271 virtual void
273 pcl::Correspondences& correspondences,
274 double max_distance = std::numeric_limits<double>::max()) = 0;
275
276 /** \brief Provide a boost shared pointer to the PointRepresentation to be used
277 * when searching for nearest neighbors.
278 *
279 * \param[in] point_representation the PointRepresentation to be used by the
280 * k-D tree for nearest neighbor search
281 */
282 inline void
287
288 /** \brief Clone and cast to CorrespondenceEstimationBase */
290 clone() const = 0;
291
292protected:
293 /** \brief The correspondence estimation method name. */
294 std::string corr_name_;
295
296 /** \brief A pointer to the spatial search object used for the target dataset. */
298
299 /** \brief A pointer to the spatial search object used for the source dataset. */
301
302 /** \brief The input point cloud dataset target. */
304
305 /** \brief The target point cloud dataset indices. */
307
308 /** \brief The point representation used (internal). */
310
311 /** \brief The transformed input source point cloud dataset. */
313
314 /** \brief The types of input point fields available. */
315 std::vector<pcl::PCLPointField> input_fields_;
316
317 /** \brief Abstract class get name method. */
318 inline const std::string&
320 {
321 return (corr_name_);
322 }
323
324 /** \brief Internal computation initialization. */
325 bool
326 initCompute();
327
328 /** \brief Internal computation initialization for reciprocal correspondences. */
329 bool
331
332 /** \brief Variable that stores whether we have a new target cloud, meaning we need to
333 * pre-process it again. This way, we avoid rebuilding the kd-tree for the target
334 * cloud every time the determineCorrespondences () method is called. */
336 /** \brief Variable that stores whether we have a new source cloud, meaning we need to
337 * pre-process it again. This way, we avoid rebuilding the reciprocal kd-tree for the
338 * source cloud every time the determineCorrespondences () method is called. */
340 /** \brief A flag which, if set, means the tree operating on the target cloud
341 * will never be recomputed*/
343
344 /** \brief A flag which, if set, means the tree operating on the source cloud
345 * will never be recomputed*/
347};
348
349/** \brief @b CorrespondenceEstimation represents the base class for
350 * determining correspondences between target and query point
351 * sets/features.
352 *
353 * Code example:
354 *
355 * \code
356 * pcl::PointCloud<pcl::PointXYZRGBA>::Ptr source, target;
357 * // ... read or fill in source and target
358 * pcl::CorrespondenceEstimation<pcl::PointXYZ, pcl::PointXYZ> est;
359 * est.setInputSource (source);
360 * est.setInputTarget (target);
361 *
362 * pcl::Correspondences all_correspondences;
363 * // Determine all reciprocal correspondences
364 * est.determineReciprocalCorrespondences (all_correspondences);
365 * \endcode
366 *
367 * \author Radu B. Rusu, Michael Dixon, Dirk Holz
368 * \ingroup registration
369 */
370template <typename PointSource, typename PointTarget, typename Scalar = float>
372: public CorrespondenceEstimationBase<PointSource, PointTarget, Scalar> {
373public:
375 using ConstPtr =
377
378 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::
380 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::
382 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::tree_;
383 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::
385 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::target_;
386 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::corr_name_;
387 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::target_indices_;
388 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::getClassName;
389 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::initCompute;
390 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::
392 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::input_;
393 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::indices_;
394 using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::input_fields_;
395 using PCLBase<PointSource>::deinitCompute;
396
398 using KdTreePtr = typename KdTree::Ptr;
399
403
407
409
410 /** \brief Empty constructor. */
411 CorrespondenceEstimation() { corr_name_ = "CorrespondenceEstimation"; }
412
413 /** \brief Empty destructor */
415
416 /** \brief Determine the correspondences between input and target cloud.
417 * \param[out] correspondences the found correspondences (index of query point, index
418 * of target point, distance) \param[in] max_distance maximum allowed distance between
419 * correspondences
420 */
421 void
423 pcl::Correspondences& correspondences,
424 double max_distance = std::numeric_limits<double>::max()) override;
425
426 /** \brief Determine the reciprocal correspondences between input and target cloud.
427 * A correspondence is considered reciprocal if both Src_i has Tgt_i as a
428 * correspondence, and Tgt_i has Src_i as one.
429 *
430 * \param[out] correspondences the found correspondences (index of query and target
431 * point, distance) \param[in] max_distance maximum allowed distance between
432 * correspondences
433 */
434 void
436 pcl::Correspondences& correspondences,
437 double max_distance = std::numeric_limits<double>::max()) override;
438
439 /** \brief Clone and cast to CorrespondenceEstimationBase */
441 clone() const override
442 {
444 return (copy);
445 }
446};
447} // namespace registration
448} // namespace pcl
449
450#include <pcl/registration/impl/correspondence_estimation.hpp>
Iterator class for point clouds with or without given indices.
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
shared_ptr< const PointCloud< PointSource > > ConstPtr
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.
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.
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.
shared_ptr< CorrespondenceEstimation< PointSource, PointTarget, Scalar > > Ptr
typename PointCloudSource::ConstPtr PointCloudSourceConstPtr
void determineReciprocalCorrespondences(pcl::Correspondences &correspondences, double max_distance=std::numeric_limits< double >::max()) override
Determine the reciprocal correspondences between input and target cloud.
typename KdTree::PointRepresentationConstPtr PointRepresentationConstPtr
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