diff --git a/include/gtsam_points/factors/integrated_vgicp_factor_gpu.hpp b/include/gtsam_points/factors/integrated_vgicp_factor_gpu.hpp index adddcb62..ca8edae3 100644 --- a/include/gtsam_points/factors/integrated_vgicp_factor_gpu.hpp +++ b/include/gtsam_points/factors/integrated_vgicp_factor_gpu.hpp @@ -63,13 +63,6 @@ class IntegratedVGICPFactorGPU : public gtsam_points::NonlinearFactorGPU { CUstream_st* stream = nullptr, std::shared_ptr temp_buffer = nullptr); - /// Create a unary VGICP_GPU factor between a fixed target pose and an active source pose. - IntegratedVGICPFactorGPU( - const gtsam::Pose3& fixed_target_pose, - gtsam::Key source_key, - const GaussianVoxelMap::ConstPtr& target, - const PointCloud::ConstPtr& source); - virtual ~IntegratedVGICPFactorGPU() override; /// @brief Enable or disable surface orientation validation for correspondence search diff --git a/src/gtsam_points/factors/integrated_vgicp_factor_gpu.cu b/src/gtsam_points/factors/integrated_vgicp_factor_gpu.cu index 51e569c6..43444a73 100644 --- a/src/gtsam_points/factors/integrated_vgicp_factor_gpu.cu +++ b/src/gtsam_points/factors/integrated_vgicp_factor_gpu.cu @@ -12,13 +12,6 @@ namespace gtsam_points { -IntegratedVGICPFactorGPU::IntegratedVGICPFactorGPU( - const gtsam::Pose3& fixed_target_pose, - gtsam::Key source_key, - const GaussianVoxelMap::ConstPtr& target, - const PointCloud::ConstPtr& source) -: IntegratedVGICPFactorGPU(fixed_target_pose, source_key, target, source, nullptr, nullptr) {} - IntegratedVGICPFactorGPU::IntegratedVGICPFactorGPU( gtsam::Key target_key, gtsam::Key source_key,