00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041 #ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_REGISTRATION_H_
00042 #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_REGISTRATION_H_
00043
00044 #include <pcl/sample_consensus/sac_model_registration.h>
00045 #include <pcl/common/point_operators.h>
00046 #include <pcl/common/eigen.h>
00047 #include <pcl/point_types.h>
00048
00050 template <typename PointT> bool
00051 pcl::SampleConsensusModelRegistration<PointT>::isSampleGood (const std::vector<int> &samples) const
00052 {
00053 using namespace pcl::common;
00054 using namespace pcl::traits;
00055
00056 PointT p10 = input_->points[samples[1]] - input_->points[samples[0]];
00057 PointT p20 = input_->points[samples[2]] - input_->points[samples[0]];
00058 PointT p21 = input_->points[samples[2]] - input_->points[samples[1]];
00059
00060 return ((p10.x * p10.x + p10.y * p10.y + p10.z * p10.z) > sample_dist_thresh_ &&
00061 (p20.x * p20.x + p20.y * p20.y + p20.z * p20.z) > sample_dist_thresh_ &&
00062 (p21.x * p21.x + p21.y * p21.y + p21.z * p21.z) > sample_dist_thresh_);
00063 }
00064
00066 template <typename PointT> bool
00067 pcl::SampleConsensusModelRegistration<PointT>::computeModelCoefficients (const std::vector<int> &samples, Eigen::VectorXf &model_coefficients)
00068 {
00069 if (!target_)
00070 {
00071 PCL_ERROR ("[pcl::SampleConsensusModelRegistration::computeModelCoefficients] No target dataset given!\n");
00072 return (false);
00073 }
00074
00075 if (samples.size () != 3)
00076 return (false);
00077
00078 std::vector<int> indices_tgt (3);
00079 for (int i = 0; i < 3; ++i)
00080 indices_tgt[i] = correspondences_[samples[i]];
00081
00082 estimateRigidTransformationSVD (*input_, samples, *target_, indices_tgt, model_coefficients);
00083 return (true);
00084 }
00085
00087 template <typename PointT> void
00088 pcl::SampleConsensusModelRegistration<PointT>::getDistancesToModel (const Eigen::VectorXf &model_coefficients, std::vector<double> &distances)
00089 {
00090 if (indices_->size () != indices_tgt_->size ())
00091 {
00092 PCL_ERROR ("[pcl::SampleConsensusModelRegistration::getDistancesToModel] Number of source indices (%zu) differs than number of target indices (%zu)!\n", indices_->size (), indices_tgt_->size ());
00093 distances.clear ();
00094 return;
00095 }
00096 if (!target_)
00097 {
00098 PCL_ERROR ("[pcl::SampleConsensusModelRegistration::getDistanceToModel] No target dataset given!\n");
00099 return;
00100 }
00101
00102 if (!isModelValid (model_coefficients))
00103 {
00104 distances.clear ();
00105 return;
00106 }
00107 distances.resize (indices_->size ());
00108
00109
00110 Eigen::Matrix4f transform;
00111 transform.row (0).matrix () = model_coefficients.segment<4>(0);
00112 transform.row (1).matrix () = model_coefficients.segment<4>(4);
00113 transform.row (2).matrix () = model_coefficients.segment<4>(8);
00114 transform.row (3).matrix () = model_coefficients.segment<4>(12);
00115
00116 for (size_t i = 0; i < indices_->size (); ++i)
00117 {
00118 Eigen::Vector4f pt_src (input_->points[(*indices_)[i]].x,
00119 input_->points[(*indices_)[i]].y,
00120 input_->points[(*indices_)[i]].z, 1);
00121 Eigen::Vector4f pt_tgt (target_->points[(*indices_tgt_)[i]].x,
00122 target_->points[(*indices_tgt_)[i]].y,
00123 target_->points[(*indices_tgt_)[i]].z, 1);
00124
00125 Eigen::Vector4f p_tr (transform * pt_src);
00126
00127
00128 distances[i] = (p_tr - pt_tgt).norm ();
00129 }
00130 }
00131
00133 template <typename PointT> void
00134 pcl::SampleConsensusModelRegistration<PointT>::selectWithinDistance (const Eigen::VectorXf &model_coefficients, const double threshold, std::vector<int> &inliers)
00135 {
00136 if (indices_->size () != indices_tgt_->size ())
00137 {
00138 PCL_ERROR ("[pcl::SampleConsensusModelRegistration::selectWithinDistance] Number of source indices (%zu) differs than number of target indices (%zu)!\n", indices_->size (), indices_tgt_->size ());
00139 inliers.clear ();
00140 return;
00141 }
00142 if (!target_)
00143 {
00144 PCL_ERROR ("[pcl::SampleConsensusModelRegistration::selectWithinDistance] No target dataset given!\n");
00145 return;
00146 }
00147
00148 double thresh = threshold * threshold;
00149
00150
00151 if (!isModelValid (model_coefficients))
00152 {
00153 inliers.clear ();
00154 return;
00155 }
00156
00157 int nr_p = 0;
00158 inliers.resize (indices_->size ());
00159 error_sqr_dists_.resize (indices_->size ());
00160
00161 Eigen::Matrix4f transform;
00162 transform.row (0).matrix () = model_coefficients.segment<4>(0);
00163 transform.row (1).matrix () = model_coefficients.segment<4>(4);
00164 transform.row (2).matrix () = model_coefficients.segment<4>(8);
00165 transform.row (3).matrix () = model_coefficients.segment<4>(12);
00166
00167 for (size_t i = 0; i < indices_->size (); ++i)
00168 {
00169 Eigen::Vector4f pt_src (input_->points[(*indices_)[i]].x,
00170 input_->points[(*indices_)[i]].y,
00171 input_->points[(*indices_)[i]].z, 1);
00172 Eigen::Vector4f pt_tgt (target_->points[(*indices_tgt_)[i]].x,
00173 target_->points[(*indices_tgt_)[i]].y,
00174 target_->points[(*indices_tgt_)[i]].z, 1);
00175
00176 Eigen::Vector4f p_tr (transform * pt_src);
00177
00178 float distance = (p_tr - pt_tgt).squaredNorm ();
00179
00180 if (distance < thresh)
00181 {
00182 inliers[nr_p] = (*indices_)[i];
00183 error_sqr_dists_[nr_p] = static_cast<double> (distance);
00184 ++nr_p;
00185 }
00186 }
00187 inliers.resize (nr_p);
00188 error_sqr_dists_.resize (nr_p);
00189 }
00190
00192 template <typename PointT> int
00193 pcl::SampleConsensusModelRegistration<PointT>::countWithinDistance (
00194 const Eigen::VectorXf &model_coefficients, const double threshold)
00195 {
00196 if (indices_->size () != indices_tgt_->size ())
00197 {
00198 PCL_ERROR ("[pcl::SampleConsensusModelRegistration::countWithinDistance] Number of source indices (%zu) differs than number of target indices (%zu)!\n", indices_->size (), indices_tgt_->size ());
00199 return (0);
00200 }
00201 if (!target_)
00202 {
00203 PCL_ERROR ("[pcl::SampleConsensusModelRegistration::countWithinDistance] No target dataset given!\n");
00204 return (0);
00205 }
00206
00207 double thresh = threshold * threshold;
00208
00209
00210 if (!isModelValid (model_coefficients))
00211 return (0);
00212
00213 Eigen::Matrix4f transform;
00214 transform.row (0).matrix () = model_coefficients.segment<4>(0);
00215 transform.row (1).matrix () = model_coefficients.segment<4>(4);
00216 transform.row (2).matrix () = model_coefficients.segment<4>(8);
00217 transform.row (3).matrix () = model_coefficients.segment<4>(12);
00218
00219 int nr_p = 0;
00220 for (size_t i = 0; i < indices_->size (); ++i)
00221 {
00222 Eigen::Vector4f pt_src (input_->points[(*indices_)[i]].x,
00223 input_->points[(*indices_)[i]].y,
00224 input_->points[(*indices_)[i]].z, 1);
00225 Eigen::Vector4f pt_tgt (target_->points[(*indices_tgt_)[i]].x,
00226 target_->points[(*indices_tgt_)[i]].y,
00227 target_->points[(*indices_tgt_)[i]].z, 1);
00228
00229 Eigen::Vector4f p_tr (transform * pt_src);
00230
00231 if ((p_tr - pt_tgt).squaredNorm () < thresh)
00232 nr_p++;
00233 }
00234 return (nr_p);
00235 }
00236
00238 template <typename PointT> void
00239 pcl::SampleConsensusModelRegistration<PointT>::optimizeModelCoefficients (const std::vector<int> &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients)
00240 {
00241 if (indices_->size () != indices_tgt_->size ())
00242 {
00243 PCL_ERROR ("[pcl::SampleConsensusModelRegistration::optimizeModelCoefficients] Number of source indices (%zu) differs than number of target indices (%zu)!\n", indices_->size (), indices_tgt_->size ());
00244 optimized_coefficients = model_coefficients;
00245 return;
00246 }
00247
00248
00249 if (!isModelValid (model_coefficients) || !target_)
00250 {
00251 optimized_coefficients = model_coefficients;
00252 return;
00253 }
00254
00255 std::vector<int> indices_src (inliers.size ());
00256 std::vector<int> indices_tgt (inliers.size ());
00257 for (size_t i = 0; i < inliers.size (); ++i)
00258 {
00259 indices_src[i] = inliers[i];
00260 indices_tgt[i] = correspondences_[indices_src[i]];
00261 }
00262
00263 estimateRigidTransformationSVD (*input_, indices_src, *target_, indices_tgt, optimized_coefficients);
00264 }
00265
00267 template <typename PointT> void
00268 pcl::SampleConsensusModelRegistration<PointT>::estimateRigidTransformationSVD (
00269 const pcl::PointCloud<PointT> &cloud_src,
00270 const std::vector<int> &indices_src,
00271 const pcl::PointCloud<PointT> &cloud_tgt,
00272 const std::vector<int> &indices_tgt,
00273 Eigen::VectorXf &transform)
00274 {
00275 transform.resize (16);
00276
00277 Eigen::Matrix<double, 3, Eigen::Dynamic> src (3, indices_src.size ());
00278 Eigen::Matrix<double, 3, Eigen::Dynamic> tgt (3, indices_tgt.size ());
00279
00280 for (size_t i = 0; i < indices_src.size (); ++i)
00281 {
00282 src (0, i) = cloud_src[indices_src[i]].x;
00283 src (1, i) = cloud_src[indices_src[i]].y;
00284 src (2, i) = cloud_src[indices_src[i]].z;
00285
00286 tgt (0, i) = cloud_tgt[indices_tgt[i]].x;
00287 tgt (1, i) = cloud_tgt[indices_tgt[i]].y;
00288 tgt (2, i) = cloud_tgt[indices_tgt[i]].z;
00289 }
00290
00291
00292 Eigen::Matrix4d transformation_matrix = pcl::umeyama (src, tgt, false);
00293
00294
00295 transform.segment<4> (0).matrix () = transformation_matrix.cast<float> ().row (0);
00296 transform.segment<4> (4).matrix () = transformation_matrix.cast<float> ().row (1);
00297 transform.segment<4> (8).matrix () = transformation_matrix.cast<float> ().row (2);
00298 transform.segment<4> (12).matrix () = transformation_matrix.cast<float> ().row (3);
00299 }
00300
00301 #define PCL_INSTANTIATE_SampleConsensusModelRegistration(T) template class PCL_EXPORTS pcl::SampleConsensusModelRegistration<T>;
00302
00303 #endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_REGISTRATION_H_
00304