#ifndef FAST_GICP_FAST_GICP_ST_HPP #define FAST_GICP_FAST_GICP_ST_HPP #include #include #include #include #include #include #include #include namespace fast_gicp { /** * @brief Fast GICP algorithm optimized for single threading */ template class FastGICPSingleThread : public FastGICP { 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; protected: using pcl::Registration::input_; using pcl::Registration::target_; using FastGICP::target_kdtree_; using FastGICP::correspondences_; using FastGICP::sq_distances_; using FastGICP::source_covs_; using FastGICP::target_covs_; using FastGICP::mahalanobis_; public: FastGICPSingleThread(); virtual ~FastGICPSingleThread() override; protected: virtual void computeTransformation(PointCloudSource& output, const Matrix4& guess) override; private: virtual void update_correspondences(const Eigen::Isometry3d& trans) override; virtual double linearize(const Eigen::Isometry3d& trans, Eigen::Matrix* H = nullptr, Eigen::Matrix* b = nullptr) override; virtual double compute_error(const Eigen::Isometry3d& trans) override; private: std::vector second_sq_distances_; std::vector> anchors_; }; } // namespace fast_gicp #endif