#ifndef FAST_GICP_LSQ_REGISTRATION_HPP #define FAST_GICP_LSQ_REGISTRATION_HPP #include #include #include #include #include namespace fast_gicp { enum class LSQ_OPTIMIZER_TYPE { GaussNewton, LevenbergMarquardt }; template class LsqRegistration : public pcl::Registration { public: using Scalar = float; using Matrix4 = typename pcl::Registration::Matrix4; using PointCloudSource = typename pcl::Registration::PointCloudSource; using PointCloudSourcePtr = typename PointCloudSource::Ptr; using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr; using PointCloudTarget = typename pcl::Registration::PointCloudTarget; using PointCloudTargetPtr = typename PointCloudTarget::Ptr; using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr; protected: using pcl::Registration::input_; using pcl::Registration::nr_iterations_; using pcl::Registration::max_iterations_; using pcl::Registration::final_transformation_; using pcl::Registration::transformation_epsilon_; using pcl::Registration::converged_; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW LsqRegistration(); virtual ~LsqRegistration(); void setRotationEpsilon(double eps); void setInitialLambdaFactor(double init_lambda_factor); void setDebugPrint(bool lm_debug_print); const Eigen::Matrix& getFinalHessian() const; virtual void swapSourceAndTarget() {} virtual void clearSource() {} virtual void clearTarget() {} protected: virtual void computeTransformation(PointCloudSource& output, const Matrix4& guess) override; bool is_converged(const Eigen::Isometry3d& delta) const; virtual double linearize(const Eigen::Isometry3d& trans, Eigen::Matrix* H = nullptr, Eigen::Matrix* b = nullptr) = 0; virtual double compute_error(const Eigen::Isometry3d& trans) = 0; bool step_optimize(Eigen::Isometry3d& x0, Eigen::Isometry3d& delta); bool step_gn(Eigen::Isometry3d& x0, Eigen::Isometry3d& delta); bool step_lm(Eigen::Isometry3d& x0, Eigen::Isometry3d& delta); protected: double rotation_epsilon_; LSQ_OPTIMIZER_TYPE lsq_optimizer_type_; int lm_max_iterations_; double lm_init_lambda_factor_; double lm_lambda_; bool lm_debug_print_; Eigen::Matrix final_hessian_; }; } // namespace fast_gicp #endif