Point Cloud Library (PCL)
1.7.2
Main Page
Modules
Namespaces
Classes
registration
include
pcl
registration
joint_icp.h
1
/*
2
* Software License Agreement (BSD License)
3
*
4
* Point Cloud Library (PCL) - www.pointclouds.org
5
* Copyright (c) 2009-2012, 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
*/
38
39
#ifndef PCL_JOINT_ICP_H_
40
#define PCL_JOINT_ICP_H_
41
42
// PCL includes
43
#include <pcl/registration/icp.h>
44
namespace
pcl
45
{
46
/** \brief @b JointIterativeClosestPoint extends ICP to multiple frames which
47
* share the same transform. This is particularly useful when solving for
48
* camera extrinsics using multiple observations. When given a single pair of
49
* clouds, this reduces to vanilla ICP.
50
*
51
* \author Stephen Miller
52
* \ingroup registration
53
*/
54
template
<
typename
Po
int
Source,
typename
Po
int
Target,
typename
Scalar =
float
>
55
class
JointIterativeClosestPoint
:
public
IterativeClosestPoint
<PointSource, PointTarget, Scalar>
56
{
57
public
:
58
typedef
typename
IterativeClosestPoint<PointSource, PointTarget, Scalar>::PointCloudSource
PointCloudSource
;
59
typedef
typename
PointCloudSource::Ptr
PointCloudSourcePtr
;
60
typedef
typename
PointCloudSource::ConstPtr
PointCloudSourceConstPtr
;
61
62
typedef
typename
IterativeClosestPoint<PointSource, PointTarget, Scalar>::PointCloudTarget
PointCloudTarget
;
63
typedef
typename
PointCloudTarget::Ptr
PointCloudTargetPtr
;
64
typedef
typename
PointCloudTarget::ConstPtr
PointCloudTargetConstPtr
;
65
66
typedef
pcl::search::KdTree<PointTarget>
KdTree
;
67
typedef
typename
pcl::search::KdTree<PointTarget>::Ptr
KdTreePtr
;
68
69
typedef
pcl::search::KdTree<PointSource>
KdTreeReciprocal
;
70
typedef
typename
KdTree::Ptr
KdTreeReciprocalPtr
;
71
72
73
typedef
PointIndices::Ptr
PointIndicesPtr
;
74
typedef
PointIndices::ConstPtr
PointIndicesConstPtr
;
75
76
typedef
boost::shared_ptr<JointIterativeClosestPoint<PointSource, PointTarget, Scalar> >
Ptr
;
77
typedef
boost::shared_ptr<const JointIterativeClosestPoint<PointSource, PointTarget, Scalar> >
ConstPtr
;
78
79
typedef
typename
pcl::registration::CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>
CorrespondenceEstimation
;
80
typedef
typename
CorrespondenceEstimation::Ptr
CorrespondenceEstimationPtr
;
81
typedef
typename
CorrespondenceEstimation::ConstPtr
CorrespondenceEstimationConstPtr
;
82
83
84
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::reg_name_
;
85
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::getClassName
;
86
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::setInputSource
;
87
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::input_
;
88
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::indices_
;
89
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::target_
;
90
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::nr_iterations_
;
91
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::max_iterations_
;
92
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::previous_transformation_
;
93
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::final_transformation_
;
94
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::transformation_
;
95
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::transformation_epsilon_
;
96
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::converged_
;
97
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::corr_dist_threshold_
;
98
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::inlier_threshold_
;
99
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::min_number_correspondences_
;
100
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::update_visualizer_
;
101
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::euclidean_fitness_epsilon_
;
102
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::correspondences_
;
103
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::transformation_estimation_
;
104
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::correspondence_estimation_
;
105
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::correspondence_rejectors_
;
106
107
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::use_reciprocal_correspondence_
;
108
109
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::convergence_criteria_
;
110
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::source_has_normals_
;
111
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::target_has_normals_
;
112
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::need_source_blob_
;
113
using
IterativeClosestPoint<PointSource, PointTarget, Scalar>::need_target_blob_
;
114
115
116
typedef
typename
IterativeClosestPoint<PointSource, PointTarget, Scalar>::Matrix4
Matrix4
;
117
118
/** \brief Empty constructor. */
119
JointIterativeClosestPoint
()
120
{
121
IterativeClosestPoint<PointSource, PointTarget, Scalar>
();
122
reg_name_
=
"JointIterativeClosestPoint"
;
123
};
124
125
/** \brief Empty destructor */
126
virtual
~JointIterativeClosestPoint
() {}
127
128
129
/** \brief Provide a pointer to the input source
130
* (e.g., the point cloud that we want to align to the target)
131
*/
132
virtual
void
133
setInputSource
(
const
PointCloudSourceConstPtr
&
/*cloud*/
)
134
{
135
PCL_WARN (
"[pcl::%s::setInputSource] Warning; JointIterativeClosestPoint expects multiple clouds. Please use addInputSource."
,
136
getClassName
().c_str ());
137
return
;
138
}
139
140
/** \brief Add a source cloud to the joint solver
141
*
142
* \param[in] cloud source cloud
143
*/
144
inline
void
145
addInputSource
(
const
PointCloudSourceConstPtr
&cloud)
146
{
147
// Set the parent InputSource, just to get all cached values (e.g. the existence of normals).
148
if
(
sources_
.empty ())
149
IterativeClosestPoint<PointSource, PointTarget, Scalar>::setInputSource
(cloud);
150
sources_
.push_back (cloud);
151
}
152
153
/** \brief Provide a pointer to the input target
154
* (e.g., the point cloud that we want to align to the target)
155
*/
156
virtual
void
157
setInputTarget
(
const
PointCloudTargetConstPtr
&
/*cloud*/
)
158
{
159
PCL_WARN (
"[pcl::%s::setInputTarget] Warning; JointIterativeClosestPoint expects multiple clouds. Please use addInputTarget."
,
160
getClassName
().c_str ());
161
return
;
162
}
163
164
/** \brief Add a target cloud to the joint solver
165
*
166
* \param[in] cloud target cloud
167
*/
168
inline
void
169
addInputTarget
(
const
PointCloudTargetConstPtr
&cloud)
170
{
171
// Set the parent InputTarget, just to get all cached values (e.g. the existence of normals).
172
if
(
targets_
.empty ())
173
IterativeClosestPoint<PointSource, PointTarget, Scalar>::setInputTarget
(cloud);
174
targets_
.push_back (cloud);
175
}
176
177
/** \brief Add a manual correspondence estimator
178
* If you choose to do this, you must add one for each
179
* input source / target pair. They do not need to have trees
180
* or input clouds set ahead of time.
181
*
182
* \param[in] ce Correspondence estimation
183
*/
184
inline
void
185
addCorrespondenceEstimation
(
CorrespondenceEstimationPtr
ce)
186
{
187
correspondence_estimations_
.push_back (ce);
188
}
189
190
/** \brief Reset my list of input sources
191
*/
192
inline
void
193
clearInputSources
()
194
{
sources_
.clear (); }
195
196
/** \brief Reset my list of input targets
197
*/
198
inline
void
199
clearInputTargets
()
200
{
targets_
.clear (); }
201
202
/** \brief Reset my list of correspondence estimation methods.
203
*/
204
inline
void
205
clearCorrespondenceEstimations
()
206
{
correspondence_estimations_
.clear (); }
207
208
209
protected
:
210
211
/** \brief Rigid transformation computation method with initial guess.
212
* \param output the transformed input point cloud dataset using the rigid transformation found
213
* \param guess the initial guess of the transformation to compute
214
*/
215
virtual
void
216
computeTransformation
(
PointCloudSource
&output,
const
Matrix4
&guess);
217
218
/** \brief Looks at the Estimators and Rejectors and determines whether their blob-setter methods need to be called */
219
void
220
determineRequiredBlobData
();
221
222
std::vector<PointCloudSourceConstPtr>
sources_
;
223
std::vector<PointCloudTargetConstPtr>
targets_
;
224
std::vector<CorrespondenceEstimationPtr>
correspondence_estimations_
;
225
};
226
227
}
228
229
#include <pcl/registration/impl/joint_icp.hpp>
230
231
#endif //#ifndef PCL_JOINT_ICP_H_
232
233