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 #ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_REGISTRATION_H_
42 #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_REGISTRATION_H_
43 
44 #include <pcl/sample_consensus/sac_model_registration.h>
45 
46 //////////////////////////////////////////////////////////////////////////
47 template <typename PointT> bool
isSampleGood(const Indices & samples) const48 pcl::SampleConsensusModelRegistration<PointT>::isSampleGood (const Indices &samples) const
49 {
50   if (samples.size () != sample_size_)
51   {
52     PCL_ERROR ("[pcl::SampleConsensusModelRegistration::isSampleGood] Wrong number of samples (is %lu, should be %lu)!\n", samples.size (), sample_size_);
53     return (false);
54   }
55   using namespace pcl::common;
56   using namespace pcl::traits;
57 
58   PointT p10 = (*input_)[samples[1]] - (*input_)[samples[0]];
59   PointT p20 = (*input_)[samples[2]] - (*input_)[samples[0]];
60   PointT p21 = (*input_)[samples[2]] - (*input_)[samples[1]];
61 
62   return ((p10.x * p10.x + p10.y * p10.y + p10.z * p10.z) > sample_dist_thresh_ &&
63           (p20.x * p20.x + p20.y * p20.y + p20.z * p20.z) > sample_dist_thresh_ &&
64           (p21.x * p21.x + p21.y * p21.y + p21.z * p21.z) > sample_dist_thresh_);
65 }
66 
67 //////////////////////////////////////////////////////////////////////////
68 template <typename PointT> bool
computeModelCoefficients(const Indices & samples,Eigen::VectorXf & model_coefficients) const69 pcl::SampleConsensusModelRegistration<PointT>::computeModelCoefficients (const Indices &samples, Eigen::VectorXf &model_coefficients) const
70 {
71   if (!target_)
72   {
73     PCL_ERROR ("[pcl::SampleConsensusModelRegistration::computeModelCoefficients] No target dataset given!\n");
74     return (false);
75   }
76   // Need 3 samples
77   if (samples.size () != sample_size_)
78   {
79     return (false);
80   }
81 
82   Indices indices_tgt (3);
83   for (int i = 0; i < 3; ++i)
84   {
85     const auto it = correspondences_.find (samples[i]);
86     if (it == correspondences_.cend ())
87     {
88       PCL_ERROR ("[pcl::SampleConsensusModelRegistration::computeModelCoefficients] Element with key %i is not in map (map contains %lu elements).\n",
89                  samples[i], correspondences_.size ());
90       return (false);
91     }
92     indices_tgt[i] = it->second;
93   }
94 
95   estimateRigidTransformationSVD (*input_, samples, *target_, indices_tgt, model_coefficients);
96   return (true);
97 }
98 
99 //////////////////////////////////////////////////////////////////////////
100 template <typename PointT> void
getDistancesToModel(const Eigen::VectorXf & model_coefficients,std::vector<double> & distances) const101 pcl::SampleConsensusModelRegistration<PointT>::getDistancesToModel (const Eigen::VectorXf &model_coefficients, std::vector<double> &distances) const
102 {
103   if (indices_->size () != indices_tgt_->size ())
104   {
105     PCL_ERROR ("[pcl::SampleConsensusModelRegistration::getDistancesToModel] Number of source indices (%lu) differs than number of target indices (%lu)!\n", indices_->size (), indices_tgt_->size ());
106     distances.clear ();
107     return;
108   }
109   if (!target_)
110   {
111     PCL_ERROR ("[pcl::SampleConsensusModelRegistration::getDistanceToModel] No target dataset given!\n");
112     return;
113   }
114   // Check if the model is valid given the user constraints
115   if (!isModelValid (model_coefficients))
116   {
117     distances.clear ();
118     return;
119   }
120   distances.resize (indices_->size ());
121 
122   // Get the 4x4 transformation
123   Eigen::Matrix4f transform;
124   transform.row (0).matrix () = model_coefficients.segment<4>(0);
125   transform.row (1).matrix () = model_coefficients.segment<4>(4);
126   transform.row (2).matrix () = model_coefficients.segment<4>(8);
127   transform.row (3).matrix () = model_coefficients.segment<4>(12);
128 
129   for (std::size_t i = 0; i < indices_->size (); ++i)
130   {
131     Eigen::Vector4f pt_src ((*input_)[(*indices_)[i]].x,
132                             (*input_)[(*indices_)[i]].y,
133                             (*input_)[(*indices_)[i]].z, 1.0f);
134     Eigen::Vector4f pt_tgt ((*target_)[(*indices_tgt_)[i]].x,
135                             (*target_)[(*indices_tgt_)[i]].y,
136                             (*target_)[(*indices_tgt_)[i]].z, 1.0f);
137 
138     Eigen::Vector4f p_tr (transform * pt_src);
139     // Calculate the distance from the transformed point to its correspondence
140     // need to compute the real norm here to keep MSAC and friends general
141     distances[i] = (p_tr - pt_tgt).norm ();
142   }
143 }
144 
145 //////////////////////////////////////////////////////////////////////////
146 template <typename PointT> void
selectWithinDistance(const Eigen::VectorXf & model_coefficients,const double threshold,Indices & inliers)147 pcl::SampleConsensusModelRegistration<PointT>::selectWithinDistance (const Eigen::VectorXf &model_coefficients, const double threshold, Indices &inliers)
148 {
149   if (indices_->size () != indices_tgt_->size ())
150   {
151     PCL_ERROR ("[pcl::SampleConsensusModelRegistration::selectWithinDistance] Number of source indices (%lu) differs than number of target indices (%lu)!\n", indices_->size (), indices_tgt_->size ());
152     inliers.clear ();
153     return;
154   }
155   if (!target_)
156   {
157     PCL_ERROR ("[pcl::SampleConsensusModelRegistration::selectWithinDistance] No target dataset given!\n");
158     return;
159   }
160 
161   double thresh = threshold * threshold;
162 
163   // Check if the model is valid given the user constraints
164   if (!isModelValid (model_coefficients))
165   {
166     inliers.clear ();
167     return;
168   }
169 
170   inliers.clear ();
171   error_sqr_dists_.clear ();
172   inliers.reserve (indices_->size ());
173   error_sqr_dists_.reserve (indices_->size ());
174 
175   Eigen::Matrix4f transform;
176   transform.row (0).matrix () = model_coefficients.segment<4>(0);
177   transform.row (1).matrix () = model_coefficients.segment<4>(4);
178   transform.row (2).matrix () = model_coefficients.segment<4>(8);
179   transform.row (3).matrix () = model_coefficients.segment<4>(12);
180 
181   for (std::size_t i = 0; i < indices_->size (); ++i)
182   {
183     Eigen::Vector4f pt_src ((*input_)[(*indices_)[i]].x,
184                             (*input_)[(*indices_)[i]].y,
185                             (*input_)[(*indices_)[i]].z, 1);
186     Eigen::Vector4f pt_tgt ((*target_)[(*indices_tgt_)[i]].x,
187                             (*target_)[(*indices_tgt_)[i]].y,
188                             (*target_)[(*indices_tgt_)[i]].z, 1);
189 
190     Eigen::Vector4f p_tr (transform * pt_src);
191 
192     float distance = (p_tr - pt_tgt).squaredNorm ();
193     // Calculate the distance from the transformed point to its correspondence
194     if (distance < thresh)
195     {
196       inliers.push_back ((*indices_)[i]);
197       error_sqr_dists_.push_back (static_cast<double> (distance));
198     }
199   }
200 }
201 
202 //////////////////////////////////////////////////////////////////////////
203 template <typename PointT> std::size_t
countWithinDistance(const Eigen::VectorXf & model_coefficients,const double threshold) const204 pcl::SampleConsensusModelRegistration<PointT>::countWithinDistance (
205     const Eigen::VectorXf &model_coefficients, const double threshold) const
206 {
207   if (indices_->size () != indices_tgt_->size ())
208   {
209     PCL_ERROR ("[pcl::SampleConsensusModelRegistration::countWithinDistance] Number of source indices (%lu) differs than number of target indices (%lu)!\n", indices_->size (), indices_tgt_->size ());
210     return (0);
211   }
212   if (!target_)
213   {
214     PCL_ERROR ("[pcl::SampleConsensusModelRegistration::countWithinDistance] No target dataset given!\n");
215     return (0);
216   }
217 
218   double thresh = threshold * threshold;
219 
220   // Check if the model is valid given the user constraints
221   if (!isModelValid (model_coefficients))
222   {
223     return (0);
224   }
225 
226   Eigen::Matrix4f transform;
227   transform.row (0).matrix () = model_coefficients.segment<4>(0);
228   transform.row (1).matrix () = model_coefficients.segment<4>(4);
229   transform.row (2).matrix () = model_coefficients.segment<4>(8);
230   transform.row (3).matrix () = model_coefficients.segment<4>(12);
231 
232   std::size_t nr_p = 0;
233   for (std::size_t i = 0; i < indices_->size (); ++i)
234   {
235     Eigen::Vector4f pt_src ((*input_)[(*indices_)[i]].x,
236                             (*input_)[(*indices_)[i]].y,
237                             (*input_)[(*indices_)[i]].z, 1);
238     Eigen::Vector4f pt_tgt ((*target_)[(*indices_tgt_)[i]].x,
239                             (*target_)[(*indices_tgt_)[i]].y,
240                             (*target_)[(*indices_tgt_)[i]].z, 1);
241 
242     Eigen::Vector4f p_tr (transform * pt_src);
243     // Calculate the distance from the transformed point to its correspondence
244     if ((p_tr - pt_tgt).squaredNorm () < thresh)
245       nr_p++;
246   }
247   return (nr_p);
248 }
249 
250 //////////////////////////////////////////////////////////////////////////
251 template <typename PointT> void
optimizeModelCoefficients(const Indices & inliers,const Eigen::VectorXf & model_coefficients,Eigen::VectorXf & optimized_coefficients) const252 pcl::SampleConsensusModelRegistration<PointT>::optimizeModelCoefficients (const Indices &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients) const
253 {
254   if (indices_->size () != indices_tgt_->size ())
255   {
256     PCL_ERROR ("[pcl::SampleConsensusModelRegistration::optimizeModelCoefficients] Number of source indices (%lu) differs than number of target indices (%lu)!\n", indices_->size (), indices_tgt_->size ());
257     optimized_coefficients = model_coefficients;
258     return;
259   }
260 
261   // Check if the model is valid given the user constraints
262   if (!isModelValid (model_coefficients) || !target_)
263   {
264     optimized_coefficients = model_coefficients;
265     return;
266   }
267 
268   Indices indices_src (inliers.size ());
269   Indices indices_tgt (inliers.size ());
270   for (std::size_t i = 0; i < inliers.size (); ++i)
271   {
272     indices_src[i] = inliers[i];
273     const auto it = correspondences_.find (indices_src[i]);
274     if (it == correspondences_.cend ())
275     {
276       PCL_ERROR ("[pcl::SampleConsensusModelRegistration::optimizeModelCoefficients] Element with key %i is not in map (map contains %lu elements).\n",
277                  indices_src[i], correspondences_.size ());
278       optimized_coefficients = model_coefficients;
279       return;
280     }
281     indices_tgt[i] = it->second;
282   }
283 
284   estimateRigidTransformationSVD (*input_, indices_src, *target_, indices_tgt, optimized_coefficients);
285 }
286 
287 //////////////////////////////////////////////////////////////////////////
288 template <typename PointT> void
estimateRigidTransformationSVD(const pcl::PointCloud<PointT> & cloud_src,const Indices & indices_src,const pcl::PointCloud<PointT> & cloud_tgt,const Indices & indices_tgt,Eigen::VectorXf & transform) const289 pcl::SampleConsensusModelRegistration<PointT>::estimateRigidTransformationSVD (
290     const pcl::PointCloud<PointT> &cloud_src,
291     const Indices &indices_src,
292     const pcl::PointCloud<PointT> &cloud_tgt,
293     const Indices &indices_tgt,
294     Eigen::VectorXf &transform) const
295 {
296   transform.resize (16);
297 
298   Eigen::Matrix<double, 3, Eigen::Dynamic> src (3, indices_src.size ());
299   Eigen::Matrix<double, 3, Eigen::Dynamic> tgt (3, indices_tgt.size ());
300 
301   for (std::size_t i = 0; i < indices_src.size (); ++i)
302   {
303     src (0, i) = cloud_src[indices_src[i]].x;
304     src (1, i) = cloud_src[indices_src[i]].y;
305     src (2, i) = cloud_src[indices_src[i]].z;
306 
307     tgt (0, i) = cloud_tgt[indices_tgt[i]].x;
308     tgt (1, i) = cloud_tgt[indices_tgt[i]].y;
309     tgt (2, i) = cloud_tgt[indices_tgt[i]].z;
310   }
311 
312   // Call Umeyama directly from Eigen
313   Eigen::Matrix4d transformation_matrix = pcl::umeyama (src, tgt, false);
314 
315   // Return the correct transformation
316   transform.segment<4> (0).matrix () = transformation_matrix.cast<float> ().row (0);
317   transform.segment<4> (4).matrix () = transformation_matrix.cast<float> ().row (1);
318   transform.segment<4> (8).matrix () = transformation_matrix.cast<float> ().row (2);
319   transform.segment<4> (12).matrix () = transformation_matrix.cast<float> ().row (3);
320 }
321 
322 #define PCL_INSTANTIATE_SampleConsensusModelRegistration(T) template class PCL_EXPORTS pcl::SampleConsensusModelRegistration<T>;
323 
324 #endif    // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_REGISTRATION_H_
325 
326