Template Class FastVGICPCuda
Defined in File fast_vgicp_cuda.hpp
Inheritance Relationships
Base Type
public fast_gicp::LsqRegistration< PointSource, PointTarget >(Template Class LsqRegistration)
Class Documentation
-
template<typename PointSource, typename PointTarget>
class FastVGICPCuda : public fast_gicp::LsqRegistration<PointSource, PointTarget> Fast Voxelized GICP algorithm boosted with CUDA.
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<FastVGICPCuda<PointSource, PointTarget>>
-
using ConstPtr = pcl::shared_ptr<const FastVGICPCuda<PointSource, PointTarget>>
Public Functions
-
FastVGICPCuda()
-
virtual ~FastVGICPCuda() override
-
void setCorrespondenceRandomness(int k)
-
void setResolution(double resolution)
-
void setKernelWidth(double kernel_width, double max_dist = -1.0)
-
void setRegularizationMethod(RegularizationMethod method)
-
void setNeighborSearchMethod(NeighborSearchMethod method, double radius = -1.0)
-
void setNearestNeighborSearchMethod(NearestNeighborMethod method)
-
virtual void swapSourceAndTarget() override
-
virtual void clearSource() override
-
virtual void clearTarget() override
-
virtual void setInputSource(const PointCloudSourceConstPtr &cloud) override
-
virtual void setInputTarget(const PointCloudTargetConstPtr &cloud) override
Protected Functions
-
virtual void computeTransformation(PointCloudSource &output, const Matrix4 &guess) 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
-
using Scalar = float