diff --git a/include/multigrid_pclomp/multi_voxel_grid_covariance_omp.h b/include/multigrid_pclomp/multi_voxel_grid_covariance_omp.h index b85b5fcb..61fe3373 100644 --- a/include/multigrid_pclomp/multi_voxel_grid_covariance_omp.h +++ b/include/multigrid_pclomp/multi_voxel_grid_covariance_omp.h @@ -223,6 +223,12 @@ class MultiVoxelGridCovariance : public pcl::VoxelGrid { filter_name_ = "MultiVoxelGridCovariance"; } + MultiVoxelGridCovariance(const MultiVoxelGridCovariance &other); + MultiVoxelGridCovariance(MultiVoxelGridCovariance &&other); + + MultiVoxelGridCovariance &operator=(const MultiVoxelGridCovariance &other); + MultiVoxelGridCovariance &operator=(MultiVoxelGridCovariance &&other); + /** \brief Initializes voxel structure. */ inline void setInputCloudAndFilter(const PointCloudConstPtr &cloud, const std::string &grid_id) { diff --git a/include/multigrid_pclomp/multi_voxel_grid_covariance_omp_impl.hpp b/include/multigrid_pclomp/multi_voxel_grid_covariance_omp_impl.hpp index 4df6abf9..97cbed57 100644 --- a/include/multigrid_pclomp/multi_voxel_grid_covariance_omp_impl.hpp +++ b/include/multigrid_pclomp/multi_voxel_grid_covariance_omp_impl.hpp @@ -56,6 +56,62 @@ #include #include "multigrid_pclomp/multi_voxel_grid_covariance_omp.h" +template +pclomp::MultiVoxelGridCovariance::MultiVoxelGridCovariance(const MultiVoxelGridCovariance &other) + : pcl::VoxelGrid(other), leaves_(other.leaves_), grid_leaves_(other.grid_leaves_), leaf_indices_(other.leaf_indices_), kdtree_(other.kdtree_) { + min_points_per_voxel_ = other.min_points_per_voxel_; + min_covar_eigvalue_mult_ = other.min_covar_eigvalue_mult_; + + // Deep copy + voxel_centroids_ptr_.reset(new PointCloud); + + if(other.voxel_centroids_ptr_) { + *voxel_centroids_ptr_ = *other.voxel_centroids_ptr_; + } +} + +template +pclomp::MultiVoxelGridCovariance::MultiVoxelGridCovariance(MultiVoxelGridCovariance &&other) + : pcl::VoxelGrid(std::move(other)), leaves_(std::move(other.leaves_)), grid_leaves_(std::move(other.grid_leaves_)), leaf_indices_(std::move(other.leaf_indices_)), kdtree_(std::move(other.kdtree_)), voxel_centroids_ptr_(std::move(other.voxel_centroids_ptr_)) { + min_points_per_voxel_ = other.min_points_per_voxel_; + min_covar_eigvalue_mult_ = other.min_covar_eigvalue_mult_; +} + +template +pclomp::MultiVoxelGridCovariance &pclomp::MultiVoxelGridCovariance::operator=(const MultiVoxelGridCovariance &other) { + pcl::VoxelGrid::operator=(other); + leaves_ = other.leaves_; + grid_leaves_ = other.grid_leaves_; + leaf_indices_ = other.leaf_indices_; + kdtree_ = other.kdtree_; + voxel_centroids_ptr_ = other.voxel_centroids_ptr_; + min_points_per_voxel_ = other.min_points_per_voxel_; + min_covar_eigvalue_mult_ = other.min_covar_eigvalue_mult_; + + // Deep copy + voxel_centroids_ptr_.reset(new PointCloud); + + if(other.voxel_centroids_ptr_) { + *voxel_centroids_ptr_ = *other.voxel_centroids_ptr_; + } + + return *this; +} + +template +pclomp::MultiVoxelGridCovariance &pclomp::MultiVoxelGridCovariance::operator=(MultiVoxelGridCovariance &&other) { + pcl::VoxelGrid::operator=(std::move(other)); + leaves_ = std::move(other.leaves_); + grid_leaves_ = std::move(other.grid_leaves_); + leaf_indices_ = std::move(other.leaf_indices_); + kdtree_ = std::move(other.kdtree_); + voxel_centroids_ptr_ = std::move(other.voxel_centroids_ptr_); + min_points_per_voxel_ = other.min_points_per_voxel_; + min_covar_eigvalue_mult_ = other.min_covar_eigvalue_mult_; + + return *this; +} + ////////////////////////////////////////////////////////////////////////////////////////// template void pclomp::MultiVoxelGridCovariance::applyFilter(const PointCloudConstPtr &input, const std::string &grid_id, LeafDict &leaves) const { diff --git a/include/multigrid_pclomp/multigrid_ndt_omp.h b/include/multigrid_pclomp/multigrid_ndt_omp.h index 2e3c9784..a609c781 100644 --- a/include/multigrid_pclomp/multigrid_ndt_omp.h +++ b/include/multigrid_pclomp/multigrid_ndt_omp.h @@ -72,6 +72,16 @@ struct NdtResult { Eigen::Matrix hessian; std::vector> transformation_array; EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + friend std::ostream &operator<<(std::ostream &os, const NdtResult &val) { + os << "Pose: " << std::endl << val.pose << std::endl; + os << "TP: " << val.transform_probability << std::endl; + os << "NVTP: " << val.nearest_voxel_transformation_likelihood << std::endl; + os << "Iteration num: " << val.iteration_num << std::endl; + os << "Hessian: " << std::endl << val.hessian << std::endl; + + return os; + } }; struct NdtParams { @@ -117,6 +127,8 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration BaseRegType; + public: #if PCL_VERSION >= PCL_VERSION_CALC(1, 10, 0) typedef pcl::shared_ptr> Ptr; @@ -131,6 +143,14 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration::setInputSource(input); + } + } + inline void setInputTarget(const PointCloudTargetConstPtr &cloud) { const std::string default_target_id = "default"; addTarget(cloud, default_target_id); @@ -316,9 +344,7 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration::reg_name_; - using pcl::Registration::getClassName; using pcl::Registration::input_; - using pcl::Registration::indices_; using pcl::Registration::target_; using pcl::Registration::nr_iterations_; using pcl::Registration::max_iterations_; @@ -327,8 +353,6 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration::transformation_; using pcl::Registration::transformation_epsilon_; using pcl::Registration::converged_; - using pcl::Registration::corr_dist_threshold_; - using pcl::Registration::inlier_threshold_; using pcl::Registration::update_visualizer_; diff --git a/include/multigrid_pclomp/multigrid_ndt_omp_impl.hpp b/include/multigrid_pclomp/multigrid_ndt_omp_impl.hpp index 889ab9b4..fce03c09 100644 --- a/include/multigrid_pclomp/multigrid_ndt_omp_impl.hpp +++ b/include/multigrid_pclomp/multigrid_ndt_omp_impl.hpp @@ -56,6 +56,101 @@ #ifndef PCL_REGISTRATION_NDT_OMP_MULTI_VOXEL_IMPL_H_ #define PCL_REGISTRATION_NDT_OMP_MULTI_VOXEL_IMPL_H_ +template +pclomp::MultiGridNormalDistributionsTransform::MultiGridNormalDistributionsTransform(const MultiGridNormalDistributionsTransform &other) : BaseRegType(other), target_cells_(other.target_cells_) { + resolution_ = other.resolution_; + step_size_ = other.step_size_; + outlier_ratio_ = other.outlier_ratio_; + gauss_d1_ = other.gauss_d1_; + gauss_d2_ = other.gauss_d2_; + gauss_d3_ = other.gauss_d3_; + trans_probability_ = other.trans_probability_; + // No need to copy j_ang and h_ang, as those matrices are re-computed on every computeDerivatives() call + + num_threads_ = other.num_threads_; + hessian_ = other.hessian_; + transformation_array_ = other.transformation_array_; + nearest_voxel_transformation_likelihood_ = other.nearest_voxel_transformation_likelihood_; + + regularization_scale_factor_ = other.regularization_scale_factor_; + regularization_pose_ = other.regularization_pose_; + regularization_pose_translation_ = other.regularization_pose_translation_; +} + +template +pclomp::MultiGridNormalDistributionsTransform::MultiGridNormalDistributionsTransform(MultiGridNormalDistributionsTransform &&other) : BaseRegType(std::move(other)), target_cells_(std::move(other.target_cells_)) { + resolution_ = other.resolution_; + step_size_ = other.step_size_; + outlier_ratio_ = other.outlier_ratio_; + gauss_d1_ = other.gauss_d1_; + gauss_d2_ = other.gauss_d2_; + gauss_d3_ = other.gauss_d3_; + trans_probability_ = other.trans_probability_; + // No need to copy j_ang and h_ang, as those matrices are re-computed on every computeDerivatives() call + + num_threads_ = other.num_threads_; + hessian_ = other.hessian_; + transformation_array_ = other.transformation_array_; + nearest_voxel_transformation_likelihood_ = other.nearest_voxel_transformation_likelihood_; + + regularization_scale_factor_ = other.regularization_scale_factor_; + regularization_pose_ = other.regularization_pose_; + regularization_pose_translation_ = other.regularization_pose_translation_; +} + +template +pclomp::MultiGridNormalDistributionsTransform &pclomp::MultiGridNormalDistributionsTransform::operator=(const MultiGridNormalDistributionsTransform &other) { + BaseRegType::operator=(other); + + target_cells_ = other.target_cells_; + + resolution_ = other.resolution_; + step_size_ = other.step_size_; + outlier_ratio_ = other.outlier_ratio_; + gauss_d1_ = other.gauss_d1_; + gauss_d2_ = other.gauss_d2_; + gauss_d3_ = other.gauss_d3_; + trans_probability_ = other.trans_probability_; + // No need to copy j_ang and h_ang, as those matrices are re-computed on every computeDerivatives() call + + num_threads_ = other.num_threads_; + hessian_ = other.hessian_; + transformation_array_ = other.transformation_array_; + nearest_voxel_transformation_likelihood_ = other.nearest_voxel_transformation_likelihood_; + + regularization_scale_factor_ = other.regularization_scale_factor_; + regularization_pose_ = other.regularization_pose_; + regularization_pose_translation_ = other.regularization_pose_translation_; + + return *this; +} + +template +pclomp::MultiGridNormalDistributionsTransform &pclomp::MultiGridNormalDistributionsTransform::operator=(MultiGridNormalDistributionsTransform &&other) { + BaseRegType::operator=(std::move(other)); + + target_cells_ = std::move(other.target_cells_); + resolution_ = other.resolution_; + step_size_ = other.step_size_; + outlier_ratio_ = other.outlier_ratio_; + gauss_d1_ = other.gauss_d1_; + gauss_d2_ = other.gauss_d2_; + gauss_d3_ = other.gauss_d3_; + trans_probability_ = other.trans_probability_; + // No need to copy j_ang and h_ang, as those matrices are re-computed on every computeDerivatives() call + + num_threads_ = other.num_threads_; + hessian_ = other.hessian_; + transformation_array_ = other.transformation_array_; + nearest_voxel_transformation_likelihood_ = other.nearest_voxel_transformation_likelihood_; + + regularization_scale_factor_ = other.regularization_scale_factor_; + regularization_pose_ = other.regularization_pose_; + regularization_pose_translation_ = other.regularization_pose_translation_; + + return *this; +} + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template pclomp::MultiGridNormalDistributionsTransform::MultiGridNormalDistributionsTransform()