Template Class FastVGICP
Defined in File fast_vgicp.hpp
Inheritance Relationships
Base Type
public fast_gicp::FastGICP< PointSource, PointTarget >
(Template Class FastGICP)
Class Documentation
-
template<typename PointSource, typename PointTarget>
class FastVGICP : public fast_gicp::FastGICP<PointSource, PointTarget> Fast Voxelized GICP algorithm boosted with OpenMP.
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<FastVGICP<PointSource, PointTarget>>
-
using ConstPtr = pcl::shared_ptr<const FastVGICP<PointSource, PointTarget>>
Public Functions
-
FastVGICP()
-
virtual ~FastVGICP() override
-
void setResolution(double resolution)
-
void setVoxelAccumulationMode(VoxelAccumulationMode mode)
-
void setNeighborSearchMethod(NeighborSearchMethod method)
-
virtual void swapSourceAndTarget() override
-
virtual void setInputTarget(const PointCloudTargetConstPtr &cloud) override
Protected Functions
-
virtual void computeTransformation(PointCloudSource &output, const Matrix4 &guess) override
-
virtual void update_correspondences(const Eigen::Isometry3d &trans) override
-
virtual double linearize(const Eigen::Isometry3d &trans, Eigen::Matrix<double, 6, 6> *H = nullptr, Eigen::Matrix<double, 6, 1> *b = nullptr) override
-
virtual double compute_error(const Eigen::Isometry3d &trans) override
Protected Attributes
-
double voxel_resolution_
-
NeighborSearchMethod search_method_
-
VoxelAccumulationMode voxel_mode_
-
std::unique_ptr<GaussianVoxelMap<PointTarget>> voxelmap_
-
std::vector<std::pair<int, GaussianVoxel::Ptr>> voxel_correspondences_
-
std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> voxel_mahalanobis_
-
using Scalar = float