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_NL_H_
00039 #define PCL_ICP_NL_H_
00040
00041 #include "pcl/io/pcd_io.h"
00042
00043 #include "pcl/registration/registration.h"
00044 #include "pcl/features/feature.h"
00045 #include "pcl/sample_consensus/ransac.h"
00046 #include "pcl/sample_consensus/sac_model_registration.h"
00047
00048 #include <cminpack.h>
00049
00050 namespace pcl
00051 {
00056 template <typename PointSource, typename PointTarget>
00057 class IterativeClosestPointNonLinear : public Registration<PointSource, PointTarget>
00058 {
00059 using Registration<PointSource, PointTarget>::reg_name_;
00060 using Registration<PointSource, PointTarget>::getClassName;
00061 using Registration<PointSource, PointTarget>::indices_;
00062 using Registration<PointSource, PointTarget>::target_;
00063 using Registration<PointSource, PointTarget>::nr_iterations_;
00064 using Registration<PointSource, PointTarget>::max_iterations_;
00065 using Registration<PointSource, PointTarget>::previous_transformation_;
00066 using Registration<PointSource, PointTarget>::final_transformation_;
00067 using Registration<PointSource, PointTarget>::transformation_;
00068 using Registration<PointSource, PointTarget>::transformation_epsilon_;
00069 using Registration<PointSource, PointTarget>::converged_;
00070 using Registration<PointSource, PointTarget>::corr_dist_threshold_;
00071 using Registration<PointSource, PointTarget>::inlier_threshold_;
00072 using Registration<PointSource, PointTarget>::min_number_correspondences_;
00073
00074 typedef typename Registration<PointSource, PointTarget>::PointCloudSource PointCloudSource;
00075 typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
00076 typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
00077
00078 typedef typename Registration<PointSource, PointTarget>::PointCloudTarget PointCloudTarget;
00079
00080 typedef PointIndices::Ptr PointIndicesPtr;
00081 typedef PointIndices::ConstPtr PointIndicesConstPtr;
00082
00083 public:
00085 IterativeClosestPointNonLinear ()
00086 {
00087 min_number_correspondences_ = 4;
00088 reg_name_ = "IterativeClosestPointNonLinear";
00089 };
00090
00097 void
00098 estimateRigidTransformationLM (const PointCloudSource &cloud_src, const PointCloudTarget &cloud_tgt, Eigen::Matrix4f &transformation_matrix);
00099
00108 void
00109 estimateRigidTransformationLM (const PointCloudSource &cloud_src, const std::vector<int> &indices_src,
00110 const PointCloudTarget &cloud_tgt, const std::vector<int> &indices_tgt,
00111 Eigen::Matrix4f &transformation_matrix);
00112
00113 protected:
00117 void
00118 computeTransformation (PointCloudSource &output);
00119
00120 private:
00125 inline double
00126 computeMedian (double *fvec, int m);
00127
00136 static int
00137 functionToOptimize (void *p, int m, int n, const double *x, double *fvec, int iflag);
00138 static int
00139 functionToOptimizeIndices (void *p, int m, int n, const double *x, double *fvec, int iflag);
00140
00146 inline double
00147 distHuber (const Eigen::Vector4f &p_src, const Eigen::Vector4f &p_tgt, double sigma)
00148 {
00149 Eigen::Array4f diff = (p_tgt.array () - p_src.array ()).abs ();
00150 double norm = 0.0;
00151 for (int i = 0; i < 3; ++i)
00152 {
00153 if (diff[i] < sigma)
00154 norm += diff[i] * diff[i];
00155 else
00156 norm += 2.0 * sigma * diff[i] - sigma * sigma;
00157 }
00158 return (norm);
00159 }
00160
00165 inline double
00166 distHuber (double diff, double sigma)
00167 {
00168 double norm = 0.0;
00169 if (diff < sigma)
00170 norm += diff * diff;
00171 else
00172 norm += 2.0 * sigma * diff - sigma * sigma;
00173 return (norm);
00174 }
00175
00181 inline double
00182 distGedikli (double val, double clipping)
00183 {
00184 clipping *= 1.5;
00185 return (1.0 / (1.0 + pow (val / clipping, 4)));
00186 }
00187
00192 inline double
00193 distL1 (const Eigen::Vector4f &p_src, const Eigen::Vector4f &p_tgt)
00194 {
00195 return ((p_src.array () - p_tgt.array ()).abs ().sum ());
00196 }
00197
00202 inline double
00203 distL2Sqr (const Eigen::Vector4f &p_src, const Eigen::Vector4f &p_tgt)
00204 {
00205 return ((p_src - p_tgt).squaredNorm ());
00206 }
00207
00209 std::vector<double> weights_;
00210
00212 boost::mutex tmp_mutex_;
00213
00215 const PointCloudSource *tmp_src_;
00216
00218 const PointCloudTarget *tmp_tgt_;
00219
00221 const std::vector<int> *tmp_idx_src_;
00222
00224 const std::vector<int> *tmp_idx_tgt_;
00225 };
00226 }
00227
00228 #include "pcl/registration/icp_nl.hpp"
00229
00230 #endif //#ifndef PCL_ICP_NL_H_