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 #ifndef PCL_ICP_H_
00039 #define PCL_ICP_H_
00040
00041
00042 #include <pcl/sample_consensus/ransac.h>
00043 #include <pcl/sample_consensus/sac_model_registration.h>
00044 #include <pcl/registration/registration.h>
00045 #include <pcl/registration/transformation_estimation_svd.h>
00046
00047 namespace pcl
00048 {
00087 template <typename PointSource, typename PointTarget>
00088 class IterativeClosestPoint : public Registration<PointSource, PointTarget>
00089 {
00090 typedef typename Registration<PointSource, PointTarget>::PointCloudSource PointCloudSource;
00091 typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
00092 typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
00093
00094 typedef typename Registration<PointSource, PointTarget>::PointCloudTarget PointCloudTarget;
00095
00096 typedef PointIndices::Ptr PointIndicesPtr;
00097 typedef PointIndices::ConstPtr PointIndicesConstPtr;
00098
00099 public:
00101 IterativeClosestPoint ()
00102 {
00103 reg_name_ = "IterativeClosestPoint";
00104 ransac_iterations_ = 1000;
00105 transformation_estimation_.reset (new pcl::registration::TransformationEstimationSVD<PointSource, PointTarget>);
00106 };
00107
00108 protected:
00113 virtual void
00114 computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess);
00115
00116 using Registration<PointSource, PointTarget>::reg_name_;
00117 using Registration<PointSource, PointTarget>::getClassName;
00118 using Registration<PointSource, PointTarget>::input_;
00119 using Registration<PointSource, PointTarget>::indices_;
00120 using Registration<PointSource, PointTarget>::target_;
00121 using Registration<PointSource, PointTarget>::nr_iterations_;
00122 using Registration<PointSource, PointTarget>::max_iterations_;
00123 using Registration<PointSource, PointTarget>::ransac_iterations_;
00124 using Registration<PointSource, PointTarget>::previous_transformation_;
00125 using Registration<PointSource, PointTarget>::final_transformation_;
00126 using Registration<PointSource, PointTarget>::transformation_;
00127 using Registration<PointSource, PointTarget>::transformation_epsilon_;
00128 using Registration<PointSource, PointTarget>::converged_;
00129 using Registration<PointSource, PointTarget>::corr_dist_threshold_;
00130 using Registration<PointSource, PointTarget>::inlier_threshold_;
00131 using Registration<PointSource, PointTarget>::min_number_correspondences_;
00132 using Registration<PointSource, PointTarget>::update_visualizer_;
00133 using Registration<PointSource, PointTarget>::correspondence_distances_;
00134 using Registration<PointSource, PointTarget>::euclidean_fitness_epsilon_;
00135 using Registration<PointSource, PointTarget>::transformation_estimation_;
00136 };
00137 }
00138
00139 #include <pcl/registration/impl/icp.hpp>
00140
00141 #endif //#ifndef PCL_ICP_H_