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 #ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_LM_H_
00040 #define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_LM_H_
00041
00042 #include <pcl/registration/transformation_estimation.h>
00043 #include <pcl/registration/warp_point_rigid.h>
00044 #include <pcl/registration/distances.h>
00045
00046 namespace pcl
00047 {
00048 namespace registration
00049 {
00056 template <typename PointSource, typename PointTarget>
00057 class TransformationEstimationLM : public TransformationEstimation<PointSource, PointTarget>
00058 {
00059 typedef pcl::PointCloud<PointSource> PointCloudSource;
00060 typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
00061 typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
00062
00063 typedef pcl::PointCloud<PointTarget> PointCloudTarget;
00064
00065 typedef PointIndices::Ptr PointIndicesPtr;
00066 typedef PointIndices::ConstPtr PointIndicesConstPtr;
00067
00068 public:
00070 TransformationEstimationLM () :
00071 weights_ (), tmp_src_ (), tmp_tgt_ (), tmp_idx_src_ (), tmp_idx_tgt_ (), warp_point_ ()
00072 {};
00073
00077 TransformationEstimationLM (const TransformationEstimationLM &src) :
00078 weights_ (src.weights_),
00079 tmp_src_ (src.tmp_src_),
00080 tmp_tgt_ (src.tmp_tgt_),
00081 tmp_idx_src_ (src.tmp_idx_src_),
00082 tmp_idx_tgt_ (src.tmp_idx_tgt_),
00083 warp_point_ (src.warp_point_)
00084 {};
00085
00089 TransformationEstimationLM&
00090 operator = (const TransformationEstimationLM &src)
00091 {
00092 weights_ = src.weights_;
00093 tmp_src_ = src.tmp_src_;
00094 tmp_tgt_ = src.tmp_tgt_;
00095 tmp_idx_src_ = src.tmp_idx_src_;
00096 tmp_idx_tgt_ = src.tmp_idx_tgt_;
00097 warp_point_ = src.warp_point_;
00098 }
00099
00101 virtual ~TransformationEstimationLM () {};
00102
00108 inline void
00109 estimateRigidTransformation (
00110 const pcl::PointCloud<PointSource> &cloud_src,
00111 const pcl::PointCloud<PointTarget> &cloud_tgt,
00112 Eigen::Matrix4f &transformation_matrix);
00113
00120 inline void
00121 estimateRigidTransformation (
00122 const pcl::PointCloud<PointSource> &cloud_src,
00123 const std::vector<int> &indices_src,
00124 const pcl::PointCloud<PointTarget> &cloud_tgt,
00125 Eigen::Matrix4f &transformation_matrix);
00126
00135 inline void
00136 estimateRigidTransformation (
00137 const pcl::PointCloud<PointSource> &cloud_src,
00138 const std::vector<int> &indices_src,
00139 const pcl::PointCloud<PointTarget> &cloud_tgt,
00140 const std::vector<int> &indices_tgt,
00141 Eigen::Matrix4f &transformation_matrix);
00142
00149 inline void
00150 estimateRigidTransformation (
00151 const pcl::PointCloud<PointSource> &cloud_src,
00152 const pcl::PointCloud<PointTarget> &cloud_tgt,
00153 const pcl::Correspondences &correspondences,
00154 Eigen::Matrix4f &transformation_matrix);
00155
00159 void
00160 setWarpFunction (const boost::shared_ptr<WarpPointRigid<PointSource, PointTarget> > &warp_fcn)
00161 {
00162 warp_point_ = warp_fcn;
00163 }
00164
00165 protected:
00174 virtual double
00175 computeDistance (const PointSource &p_src, const PointTarget &p_tgt)
00176 {
00177 Vector4fMapConst s = p_src.getVector4fMap ();
00178 Vector4fMapConst t = p_tgt.getVector4fMap ();
00179 return (pcl::distances::l2 (s, t));
00180 }
00181
00183 std::vector<double> weights_;
00184
00186 const PointCloudSource *tmp_src_;
00187
00189 const PointCloudTarget *tmp_tgt_;
00190
00192 const std::vector<int> *tmp_idx_src_;
00193
00195 const std::vector<int> *tmp_idx_tgt_;
00196
00198 boost::shared_ptr<WarpPointRigid<PointSource, PointTarget> > warp_point_;
00199
00204 template<typename _Scalar, int NX=Eigen::Dynamic, int NY=Eigen::Dynamic>
00205 struct Functor
00206 {
00207 typedef _Scalar Scalar;
00208 enum
00209 {
00210 InputsAtCompileTime = NX,
00211 ValuesAtCompileTime = NY
00212 };
00213 typedef Eigen::Matrix<Scalar,InputsAtCompileTime,1> InputType;
00214 typedef Eigen::Matrix<Scalar,ValuesAtCompileTime,1> ValueType;
00215 typedef Eigen::Matrix<Scalar,ValuesAtCompileTime,InputsAtCompileTime> JacobianType;
00216
00218 Functor () : m_data_points_ (ValuesAtCompileTime) {}
00219
00223 Functor (int m_data_points) : m_data_points_ (m_data_points) {}
00224
00226 virtual ~Functor () {}
00227
00229 int
00230 values () const { return (m_data_points_); }
00231
00232 protected:
00233 int m_data_points_;
00234 };
00235
00236 struct OptimizationFunctor : public Functor<double>
00237 {
00238 using Functor<double>::values;
00239
00244 OptimizationFunctor (int m_data_points, TransformationEstimationLM<PointSource, PointTarget> *estimator) :
00245 Functor<double> (m_data_points), estimator_ (estimator) {}
00246
00250 inline OptimizationFunctor (const OptimizationFunctor &src) :
00251 Functor<double> (src.m_data_points_), estimator_ ()
00252 {
00253 *this = src;
00254 }
00255
00259 inline OptimizationFunctor&
00260 operator = (const OptimizationFunctor &src)
00261 {
00262 Functor<double>::operator=(src);
00263 estimator_ = src.estimator_;
00264 return (*this);
00265 }
00266
00268 virtual ~OptimizationFunctor () {}
00269
00274 int
00275 operator () (const Eigen::VectorXd &x, Eigen::VectorXd &fvec) const;
00276
00277 TransformationEstimationLM<PointSource, PointTarget> *estimator_;
00278 };
00279
00280 struct OptimizationFunctorWithIndices : public Functor<double>
00281 {
00282 using Functor<double>::values;
00283
00288 OptimizationFunctorWithIndices (int m_data_points, TransformationEstimationLM *estimator) :
00289 Functor<double> (m_data_points), estimator_ (estimator) {}
00290
00294 inline OptimizationFunctorWithIndices (const OptimizationFunctorWithIndices &src) :
00295 Functor<double> (src.m_data_points_), estimator_ ()
00296 {
00297 *this = src;
00298 }
00299
00303 inline OptimizationFunctorWithIndices&
00304 operator = (const OptimizationFunctorWithIndices &src)
00305 {
00306 Functor<double>::operator=(src);
00307 estimator_ = src.estimator_;
00308 return (*this);
00309 }
00310
00312 virtual ~OptimizationFunctorWithIndices () {}
00313
00318 int
00319 operator () (const Eigen::VectorXd &x, Eigen::VectorXd &fvec) const;
00320
00321 TransformationEstimationLM<PointSource, PointTarget> *estimator_;
00322 };
00323 public:
00324 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00325 };
00326 }
00327 }
00328
00329 #include <pcl/registration/impl/transformation_estimation_lm.hpp>
00330
00331 #endif
00332