Template Class FastGICP
Defined in File fast_gicp.hpp
Inheritance Relationships
Base Type
public fast_gicp::LsqRegistration< PointSource, PointTarget >
(Template Class LsqRegistration)
Derived Types
public fast_gicp::FastGICPSingleThread< PointSource, PointTarget >
(Template Class FastGICPSingleThread)public fast_gicp::FastVGICP< PointSource, PointTarget >
(Template Class FastVGICP)
Class Documentation
-
template<typename PointSource, typename PointTarget, typename SearchMethodSource = pcl::search::KdTree<PointSource>, typename SearchMethodTarget = pcl::search::KdTree<PointTarget>>
class FastGICP : public fast_gicp::LsqRegistration<PointSource, PointTarget> Fast GICP algorithm optimized for multi threading with OpenMP.
Subclassed by fast_gicp::FastGICPSingleThread< PointSource, PointTarget >, fast_gicp::FastVGICP< PointSource, PointTarget >
Public Types
-
using Scalar = float
-
using Matrix4 = typename pcl::Registration<PointSource, PointTarget, Scalar>::Matrix4
-
using PointCloudSource = typename pcl::Registration<PointSource, PointTarget, Scalar>::PointCloudSource
-
using PointCloudSourcePtr = typename PointCloudSource::Ptr
-
using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr
-
using PointCloudTarget = typename pcl::Registration<PointSource, PointTarget, Scalar>::PointCloudTarget
-
using PointCloudTargetPtr = typename PointCloudTarget::Ptr
-
using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr
-
using Ptr = pcl::shared_ptr<FastGICP<PointSource, PointTarget>>
-
using ConstPtr = pcl::shared_ptr<const FastGICP<PointSource, PointTarget>>
Public Functions
-
FastGICP()
-
virtual ~FastGICP() override
-
void setNumThreads(int n)
-
void setCorrespondenceRandomness(int k)
-
void setRegularizationMethod(RegularizationMethod method)
-
virtual void swapSourceAndTarget() override
-
virtual void clearSource() override
-
virtual void clearTarget() override
-
virtual void setInputSource(const PointCloudSourceConstPtr &cloud) override
-
virtual void setSourceCovariances(const std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> &covs)
-
virtual void setInputTarget(const PointCloudTargetConstPtr &cloud) override
-
virtual void setTargetCovariances(const std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> &covs)
-
inline const std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> &getSourceCovariances() const
-
inline const std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> &getTargetCovariances() const
Protected Functions
-
virtual void computeTransformation(PointCloudSource &output, const Matrix4 &guess) override
-
virtual void update_correspondences(const Eigen::Isometry3d &trans)
-
virtual double linearize(const Eigen::Isometry3d &trans, Eigen::Matrix<double, 6, 6> *H, Eigen::Matrix<double, 6, 1> *b) override
-
virtual double compute_error(const Eigen::Isometry3d &trans) override
Protected Attributes
-
int num_threads_
-
int k_correspondences_
-
RegularizationMethod regularization_method_
-
std::shared_ptr<SearchMethodSource> search_source_
-
std::shared_ptr<SearchMethodTarget> search_target_
-
std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> source_covs_
-
std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> target_covs_
-
std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> mahalanobis_
-
std::vector<int> correspondences_
-
std::vector<float> sq_distances_
-
using Scalar = float