Go to the documentation of this file.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 #ifndef PCL_SAMPLE_CONSENSUS_MODEL_REGISTRATION_H_
00041 #define PCL_SAMPLE_CONSENSUS_MODEL_REGISTRATION_H_
00042
00043 #include <boost/unordered_map.hpp>
00044 #include <Eigen/Core>
00045 #include <pcl/sample_consensus/sac_model.h>
00046 #include <pcl/sample_consensus/model_types.h>
00047 #include <pcl/common/eigen.h>
00048 #include <pcl/common/centroid.h>
00049
00050 namespace pcl
00051 {
00056 template <typename PointT>
00057 class SampleConsensusModelRegistration : public SampleConsensusModel<PointT>
00058 {
00059 using SampleConsensusModel<PointT>::input_;
00060 using SampleConsensusModel<PointT>::indices_;
00061
00062 public:
00063 typedef typename SampleConsensusModel<PointT>::PointCloud PointCloud;
00064 typedef typename SampleConsensusModel<PointT>::PointCloudPtr PointCloudPtr;
00065 typedef typename SampleConsensusModel<PointT>::PointCloudConstPtr PointCloudConstPtr;
00066
00067 typedef boost::shared_ptr<SampleConsensusModelRegistration> Ptr;
00068
00072 SampleConsensusModelRegistration (const PointCloudConstPtr &cloud) :
00073 SampleConsensusModel<PointT> (cloud),
00074 target_ (),
00075 indices_tgt_ (),
00076 correspondences_ (),
00077 sample_dist_thresh_ (0)
00078 {
00079
00080 setInputCloud (cloud);
00081 }
00082
00087 SampleConsensusModelRegistration (const PointCloudConstPtr &cloud,
00088 const std::vector<int> &indices) :
00089 SampleConsensusModel<PointT> (cloud, indices),
00090 target_ (),
00091 indices_tgt_ (),
00092 correspondences_ (),
00093 sample_dist_thresh_ (0)
00094 {
00095 computeOriginalIndexMapping ();
00096 computeSampleDistanceThreshold (cloud, indices);
00097 }
00098
00102 inline virtual void
00103 setInputCloud (const PointCloudConstPtr &cloud)
00104 {
00105 SampleConsensusModel<PointT>::setInputCloud (cloud);
00106 computeOriginalIndexMapping ();
00107 computeSampleDistanceThreshold (cloud);
00108 }
00109
00113 inline void
00114 setInputTarget (const PointCloudConstPtr &target)
00115 {
00116 target_ = target;
00117 indices_tgt_.reset (new std::vector<int>);
00118
00119 int target_size = static_cast<int> (target->size ());
00120 indices_tgt_->resize (target_size);
00121
00122 for (int i = 0; i < target_size; ++i)
00123 (*indices_tgt_)[i] = i;
00124 computeOriginalIndexMapping ();
00125 }
00126
00131 inline void
00132 setInputTarget (const PointCloudConstPtr &target, const std::vector<int> &indices_tgt)
00133 {
00134 target_ = target;
00135 indices_tgt_.reset (new std::vector<int> (indices_tgt));
00136 computeOriginalIndexMapping ();
00137 }
00138
00143 bool
00144 computeModelCoefficients (const std::vector<int> &samples,
00145 Eigen::VectorXf &model_coefficients);
00146
00151 void
00152 getDistancesToModel (const Eigen::VectorXf &model_coefficients,
00153 std::vector<double> &distances);
00154
00160 void
00161 selectWithinDistance (const Eigen::VectorXf &model_coefficients,
00162 const double threshold,
00163 std::vector<int> &inliers);
00164
00171 virtual int
00172 countWithinDistance (const Eigen::VectorXf &model_coefficients,
00173 const double threshold);
00174
00180 void
00181 optimizeModelCoefficients (const std::vector<int> &inliers,
00182 const Eigen::VectorXf &model_coefficients,
00183 Eigen::VectorXf &optimized_coefficients);
00184
00185 void
00186 projectPoints (const std::vector<int> &,
00187 const Eigen::VectorXf &,
00188 PointCloud &, bool = true)
00189 {
00190 };
00191
00192 bool
00193 doSamplesVerifyModel (const std::set<int> &,
00194 const Eigen::VectorXf &,
00195 const double)
00196 {
00197 return (false);
00198 }
00199
00201 inline pcl::SacModel
00202 getModelType () const { return (SACMODEL_REGISTRATION); }
00203
00204 protected:
00208 inline bool
00209 isModelValid (const Eigen::VectorXf &model_coefficients)
00210 {
00211
00212 if (model_coefficients.size () != 16)
00213 return (false);
00214
00215 return (true);
00216 }
00217
00222 bool
00223 isSampleGood (const std::vector<int> &samples) const;
00224
00229 inline void
00230 computeSampleDistanceThreshold (const PointCloudConstPtr &cloud)
00231 {
00232
00233 Eigen::Vector4f xyz_centroid;
00234 Eigen::Matrix3f covariance_matrix = Eigen::Matrix3f::Zero ();
00235
00236 computeMeanAndCovarianceMatrix (*cloud, covariance_matrix, xyz_centroid);
00237
00238
00239 for (int i = 0; i < 3; ++i)
00240 for (int j = 0; j < 3; ++j)
00241 if (!pcl_isfinite (covariance_matrix.coeffRef (i, j)))
00242 PCL_ERROR ("[pcl::SampleConsensusModelRegistration::computeSampleDistanceThreshold] Covariance matrix has NaN values! Is the input cloud finite?\n");
00243
00244 Eigen::Vector3f eigen_values;
00245 pcl::eigen33 (covariance_matrix, eigen_values);
00246
00247
00248 sample_dist_thresh_ = eigen_values.array ().sqrt ().sum () / 3.0;
00249 sample_dist_thresh_ *= sample_dist_thresh_;
00250 PCL_DEBUG ("[pcl::SampleConsensusModelRegistration::setInputCloud] Estimated a sample selection distance threshold of: %f\n", sample_dist_thresh_);
00251 }
00252
00257 inline void
00258 computeSampleDistanceThreshold (const PointCloudConstPtr &cloud,
00259 const std::vector<int> &indices)
00260 {
00261
00262 Eigen::Vector4f xyz_centroid;
00263 Eigen::Matrix3f covariance_matrix;
00264 computeMeanAndCovarianceMatrix (*cloud, indices, covariance_matrix, xyz_centroid);
00265
00266
00267 for (int i = 0; i < 3; ++i)
00268 for (int j = 0; j < 3; ++j)
00269 if (!pcl_isfinite (covariance_matrix.coeffRef (i, j)))
00270 PCL_ERROR ("[pcl::SampleConsensusModelRegistration::computeSampleDistanceThreshold] Covariance matrix has NaN values! Is the input cloud finite?\n");
00271
00272 Eigen::Vector3f eigen_values;
00273 pcl::eigen33 (covariance_matrix, eigen_values);
00274
00275
00276 sample_dist_thresh_ = eigen_values.array ().sqrt ().sum () / 3.0;
00277 sample_dist_thresh_ *= sample_dist_thresh_;
00278 PCL_DEBUG ("[pcl::SampleConsensusModelRegistration::setInputCloud] Estimated a sample selection distance threshold of: %f\n", sample_dist_thresh_);
00279 }
00280
00281 private:
00282
00294 void
00295 estimateRigidTransformationSVD (const pcl::PointCloud<PointT> &cloud_src,
00296 const std::vector<int> &indices_src,
00297 const pcl::PointCloud<PointT> &cloud_tgt,
00298 const std::vector<int> &indices_tgt,
00299 Eigen::VectorXf &transform);
00300
00302 void
00303 computeOriginalIndexMapping ()
00304 {
00305 if (!indices_tgt_ || !indices_ || indices_->empty () || indices_->size () != indices_tgt_->size ())
00306 return;
00307 for (size_t i = 0; i < indices_->size (); ++i)
00308 correspondences_[(*indices_)[i]] = (*indices_tgt_)[i];
00309 }
00310
00312 PointCloudConstPtr target_;
00313
00315 boost::shared_ptr <std::vector<int> > indices_tgt_;
00316
00318 boost::unordered_map<int, int> correspondences_;
00319
00321 double sample_dist_thresh_;
00322 public:
00323 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00324 };
00325 }
00326
00327 #include <pcl/sample_consensus/impl/sac_model_registration.hpp>
00328
00329 #endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_REGISTRATION_H_