diff --git a/include/multigrid_pclomp/multigrid_ndt_omp.h b/include/multigrid_pclomp/multigrid_ndt_omp.h index 44d8a94b..d30d3592 100644 --- a/include/multigrid_pclomp/multigrid_ndt_omp.h +++ b/include/multigrid_pclomp/multigrid_ndt_omp.h @@ -112,7 +112,7 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration::setInputTarget(cloud); - target_cells_.setLeafSize(resolution_, resolution_, resolution_); + target_cells_.setLeafSize(params_.resolution, params_.resolution, params_.resolution); target_cells_.setInputCloudAndFilter(cloud, target_id); } @@ -174,8 +174,8 @@ class MultiGridNormalDistributionsTransform : public pcl::RegistrationsetTransformationEpsilon(ndt_params.trans_epsilon); - this->setStepSize(ndt_params.step_size); - this->setResolution(ndt_params.resolution); - this->setMaximumIterations(ndt_params.max_iterations); - setRegularizationScaleFactor(ndt_params.regularization_scale_factor); - setNumThreads(ndt_params.num_threads); + params_ = ndt_params; } NdtParams getParams() const { - NdtParams ndt_params; - ndt_params.trans_epsilon = transformation_epsilon_; - ndt_params.step_size = getStepSize(); - ndt_params.resolution = getResolution(); - ndt_params.max_iterations = max_iterations_; - ndt_params.regularization_scale_factor = regularization_scale_factor_; - ndt_params.num_threads = num_threads_; - return ndt_params; + return params_; } pcl::PointCloud getVoxelPCD() const { @@ -323,11 +335,9 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration::input_; using pcl::Registration::target_; using pcl::Registration::nr_iterations_; - using pcl::Registration::max_iterations_; using pcl::Registration::previous_transformation_; using pcl::Registration::final_transformation_; using pcl::Registration::transformation_; - using pcl::Registration::transformation_epsilon_; using pcl::Registration::converged_; using pcl::Registration::update_visualizer_; @@ -478,12 +488,6 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration h_ang; - int num_threads_; Eigen::Matrix hessian_; std::vector> transformation_array_; double nearest_voxel_transformation_likelihood_; - float regularization_scale_factor_; boost::optional regularization_pose_; Eigen::Vector3f regularization_pose_translation_; + NdtParams params_; + public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; diff --git a/include/multigrid_pclomp/multigrid_ndt_omp_impl.hpp b/include/multigrid_pclomp/multigrid_ndt_omp_impl.hpp index 54716dd1..fa86fb10 100644 --- a/include/multigrid_pclomp/multigrid_ndt_omp_impl.hpp +++ b/include/multigrid_pclomp/multigrid_ndt_omp_impl.hpp @@ -58,8 +58,8 @@ template pclomp::MultiGridNormalDistributionsTransform::MultiGridNormalDistributionsTransform(const MultiGridNormalDistributionsTransform &other) : BaseRegType(other), target_cells_(other.target_cells_) { - resolution_ = other.resolution_; - step_size_ = other.step_size_; + params_.resolution = other.params_.resolution; + params_.step_size = other.params_.step_size; outlier_ratio_ = other.outlier_ratio_; gauss_d1_ = other.gauss_d1_; gauss_d2_ = other.gauss_d2_; @@ -67,20 +67,20 @@ pclomp::MultiGridNormalDistributionsTransform::MultiGr 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_; + params_.num_threads = other.params_.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_; + params_.regularization_scale_factor = other.params_.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_; + params_.resolution = other.params_.resolution; + params_.step_size = other.params_.step_size; outlier_ratio_ = other.outlier_ratio_; gauss_d1_ = other.gauss_d1_; gauss_d2_ = other.gauss_d2_; @@ -88,12 +88,12 @@ pclomp::MultiGridNormalDistributionsTransform::MultiGr 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_; + params_.num_threads = other.params_.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_; + params_.regularization_scale_factor = other.params_.regularization_scale_factor; regularization_pose_ = other.regularization_pose_; regularization_pose_translation_ = other.regularization_pose_translation_; } @@ -104,8 +104,8 @@ pclomp::MultiGridNormalDistributionsTransform &pclomp: target_cells_ = other.target_cells_; - resolution_ = other.resolution_; - step_size_ = other.step_size_; + params_.resolution = other.params_.resolution; + params_.step_size = other.params_.step_size; outlier_ratio_ = other.outlier_ratio_; gauss_d1_ = other.gauss_d1_; gauss_d2_ = other.gauss_d2_; @@ -113,12 +113,12 @@ pclomp::MultiGridNormalDistributionsTransform &pclomp: 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_; + params_.num_threads = other.params_.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_; + params_.regularization_scale_factor = other.params_.regularization_scale_factor; regularization_pose_ = other.regularization_pose_; regularization_pose_translation_ = other.regularization_pose_translation_; @@ -130,8 +130,8 @@ pclomp::MultiGridNormalDistributionsTransform &pclomp: BaseRegType::operator=(std::move(other)); target_cells_ = std::move(other.target_cells_); - resolution_ = other.resolution_; - step_size_ = other.step_size_; + params_.resolution = other.params_.resolution; + params_.step_size = other.params_.step_size; outlier_ratio_ = other.outlier_ratio_; gauss_d1_ = other.gauss_d1_; gauss_d2_ = other.gauss_d2_; @@ -139,12 +139,12 @@ pclomp::MultiGridNormalDistributionsTransform &pclomp: 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_; + params_.num_threads = other.params_.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_; + params_.regularization_scale_factor = other.params_.regularization_scale_factor; regularization_pose_ = other.regularization_pose_; regularization_pose_translation_ = other.regularization_pose_translation_; @@ -154,22 +154,25 @@ pclomp::MultiGridNormalDistributionsTransform &pclomp: ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template pclomp::MultiGridNormalDistributionsTransform::MultiGridNormalDistributionsTransform() - : target_cells_(), resolution_(1.0f), step_size_(0.1), outlier_ratio_(0.55), gauss_d1_(), gauss_d2_(), gauss_d3_(), trans_probability_(), regularization_pose_(boost::none) { + : target_cells_(), outlier_ratio_(0.55), gauss_d1_(), gauss_d2_(), gauss_d3_(), trans_probability_(), regularization_pose_(boost::none) { reg_name_ = "MultiGridNormalDistributionsTransform"; + params_.trans_epsilon = 0.1; + params_.step_size = 0.1; + params_.resolution = 1.0f; + params_.max_iterations = 35; + params_.search_method = DIRECT7; + params_.num_threads = omp_get_max_threads(); + params_.regularization_scale_factor = 0.0f; + double gauss_c1, gauss_c2; // Initializes the gaussian fitting parameters (eq. 6.8) [Magnusson 2009] gauss_c1 = 10.0 * (1 - outlier_ratio_); - gauss_c2 = outlier_ratio_ / pow(resolution_, 3); + gauss_c2 = outlier_ratio_ / pow(params_.resolution, 3); gauss_d3_ = -log(gauss_c2); gauss_d1_ = -log(gauss_c1 + gauss_c2) - gauss_d3_; gauss_d2_ = -2 * log((-log(gauss_c1 * exp(-0.5) + gauss_c2) - gauss_d3_) / gauss_d1_); - - transformation_epsilon_ = 0.1; - max_iterations_ = 35; - - num_threads_ = omp_get_max_threads(); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -182,7 +185,7 @@ void pclomp::MultiGridNormalDistributionsTransform::co // Initializes the gaussian fitting parameters (eq. 6.8) [Magnusson 2009] gauss_c1 = 10 * (1 - outlier_ratio_); - gauss_c2 = outlier_ratio_ / pow(resolution_, 3); + gauss_c2 = outlier_ratio_ / pow(params_.resolution, 3); gauss_d3_ = -log(gauss_c2); gauss_d1_ = -log(gauss_c1 + gauss_c2) - gauss_d3_; gauss_d2_ = -2 * log((-log(gauss_c1 * exp(-0.5) + gauss_c2) - gauss_d3_) / gauss_d1_); @@ -243,7 +246,7 @@ void pclomp::MultiGridNormalDistributionsTransform::co } delta_p.normalize(); - delta_p_norm = computeStepLengthMT(p, delta_p, delta_p_norm, step_size_, transformation_epsilon_ / 2, score, score_gradient, hessian, output); + delta_p_norm = computeStepLengthMT(p, delta_p, delta_p_norm, params_.step_size, params_.trans_epsilon / 2, score, score_gradient, hessian, output); delta_p *= delta_p_norm; transformation_ = (Eigen::Translation(static_cast(delta_p(0)), static_cast(delta_p(1)), static_cast(delta_p(2))) * Eigen::AngleAxis(static_cast(delta_p(3)), Eigen::Vector3f::UnitX()) * Eigen::AngleAxis(static_cast(delta_p(4)), Eigen::Vector3f::UnitY()) * Eigen::AngleAxis(static_cast(delta_p(5)), Eigen::Vector3f::UnitZ())) @@ -258,7 +261,7 @@ void pclomp::MultiGridNormalDistributionsTransform::co nr_iterations_++; - if(nr_iterations_ >= max_iterations_ || (nr_iterations_ && (std::fabs(delta_p_norm) < transformation_epsilon_))) { + if(nr_iterations_ >= params_.max_iterations || (nr_iterations_ && (std::fabs(delta_p_norm) < params_.trans_epsilon))) { converged_ = true; } } @@ -312,11 +315,11 @@ double pclomp::MultiGridNormalDistributionsTransform:: // Precompute Angular Derivatives (eq. 6.19 and 6.21)[Magnusson 2009] computeAngleDerivatives(p); - std::vector> neighborhoods(num_threads_); - std::vector> distancess(num_threads_); + std::vector> neighborhoods(params_.num_threads); + std::vector> distancess(params_.num_threads); // Update gradient and hessian for each point, line 17 in Algorithm 2 [Magnusson 2009] -#pragma omp parallel for num_threads(num_threads_) schedule(guided, 8) +#pragma omp parallel for num_threads(params_.num_threads) schedule(guided, 8) for(size_t idx = 0; idx < input_size; ++idx) { int thread_n = omp_get_thread_num(); @@ -342,7 +345,7 @@ double pclomp::MultiGridNormalDistributionsTransform:: auto &distances = distancess[thread_n]; // Neighborhood search method other than kdtree is disabled in multigrid_ndt_omp - target_cells_.radiusSearch(x_trans_pt, resolution_, neighborhood, distances); + target_cells_.radiusSearch(x_trans_pt, params_.resolution, neighborhood, distances); double sum_score_pt = 0; double nearest_voxel_score_pt = 0; @@ -405,14 +408,14 @@ double pclomp::MultiGridNormalDistributionsTransform:: const float longitudinal_distance = dy * sin_yaw + dx * cos_yaw; const auto neighborhood_count_weight = static_cast(total_neighborhood_count); - regularization_score = -regularization_scale_factor_ * neighborhood_count_weight * longitudinal_distance * longitudinal_distance; + regularization_score = -params_.regularization_scale_factor * neighborhood_count_weight * longitudinal_distance * longitudinal_distance; - regularization_gradient(0, 0) = regularization_scale_factor_ * neighborhood_count_weight * 2.0f * cos_yaw * longitudinal_distance; - regularization_gradient(1, 0) = regularization_scale_factor_ * neighborhood_count_weight * 2.0f * sin_yaw * longitudinal_distance; + regularization_gradient(0, 0) = params_.regularization_scale_factor * neighborhood_count_weight * 2.0f * cos_yaw * longitudinal_distance; + regularization_gradient(1, 0) = params_.regularization_scale_factor * neighborhood_count_weight * 2.0f * sin_yaw * longitudinal_distance; - regularization_hessian(0, 0) = -regularization_scale_factor_ * neighborhood_count_weight * 2.0f * cos_yaw * cos_yaw; - regularization_hessian(0, 1) = -regularization_scale_factor_ * neighborhood_count_weight * 2.0f * cos_yaw * sin_yaw; - regularization_hessian(1, 1) = -regularization_scale_factor_ * neighborhood_count_weight * 2.0f * sin_yaw * sin_yaw; + regularization_hessian(0, 0) = -params_.regularization_scale_factor * neighborhood_count_weight * 2.0f * cos_yaw * cos_yaw; + regularization_hessian(0, 1) = -params_.regularization_scale_factor * neighborhood_count_weight * 2.0f * cos_yaw * sin_yaw; + regularization_hessian(1, 1) = -params_.regularization_scale_factor * neighborhood_count_weight * 2.0f * sin_yaw * sin_yaw; regularization_hessian(1, 0) = regularization_hessian(0, 1); score += regularization_score; @@ -658,7 +661,7 @@ void pclomp::MultiGridNormalDistributionsTransform::co std::vector distances; // Neighborhood search method other than kdtree is disabled in multigrid_ndt_omp - target_cells_.radiusSearch(x_trans_pt, resolution_, neighborhood, distances); + target_cells_.radiusSearch(x_trans_pt, params_.resolution, neighborhood, distances); for(auto &cell : neighborhood) { x_pt = (*input_)[idx]; @@ -985,7 +988,7 @@ double pclomp::MultiGridNormalDistributionsTransform:: std::vector distances; // Neighborhood search method other than kdtree is disabled in multigrid_ndt_omp - target_cells_.radiusSearch(x_trans_pt, resolution_, neighborhood, distances); + target_cells_.radiusSearch(x_trans_pt, params_.resolution, neighborhood, distances); for(auto &cell : neighborhood) { Eigen::Vector3d x_trans = Eigen::Vector3d(x_trans_pt.x, x_trans_pt.y, x_trans_pt.z); @@ -1023,7 +1026,7 @@ double pclomp::MultiGridNormalDistributionsTransform:: std::vector distances; // Neighborhood search method other than kdtree is disabled in multigrid_ndt_omp - target_cells_.radiusSearch(x_trans_pt, resolution_, neighborhood, distances); + target_cells_.radiusSearch(x_trans_pt, params_.resolution, neighborhood, distances); for(auto &cell : neighborhood) { Eigen::Vector3d x_trans = Eigen::Vector3d(x_trans_pt.x, x_trans_pt.y, x_trans_pt.z); @@ -1063,7 +1066,7 @@ double pclomp::MultiGridNormalDistributionsTransform:: std::vector distances; // Neighborhood search method other than kdtree is disabled in multigrid_ndt_omp - target_cells_.radiusSearch(x_trans_pt, resolution_, neighborhood, distances); + target_cells_.radiusSearch(x_trans_pt, params_.resolution, neighborhood, distances); for(auto &cell : neighborhood) { Eigen::Vector3d x_trans = Eigen::Vector3d(x_trans_pt.x, x_trans_pt.y, x_trans_pt.z); diff --git a/include/pclomp/ndt_omp.h b/include/pclomp/ndt_omp.h index c337b83f..d29b49eb 100644 --- a/include/pclomp/ndt_omp.h +++ b/include/pclomp/ndt_omp.h @@ -96,7 +96,7 @@ class NormalDistributionsTransform : public pcl::RegistrationsetTransformationEpsilon(ndt_params.trans_epsilon); - this->setStepSize(ndt_params.step_size); - this->setResolution(ndt_params.resolution); - this->setMaximumIterations(ndt_params.max_iterations); - setRegularizationScaleFactor(ndt_params.regularization_scale_factor); - setNeighborhoodSearchMethod(ndt_params.search_method); - setNumThreads(ndt_params.num_threads); + params_ = ndt_params; } NdtParams getParams() const { - NdtParams ndt_params; - ndt_params.trans_epsilon = transformation_epsilon_; - ndt_params.step_size = getStepSize(); - ndt_params.resolution = getResolution(); - ndt_params.max_iterations = max_iterations_; - ndt_params.regularization_scale_factor = regularization_scale_factor_; - ndt_params.search_method = getNeighborhoodSearchMethod(); - ndt_params.num_threads = num_threads_; - return ndt_params; + return params_; } protected: @@ -277,11 +287,9 @@ class NormalDistributionsTransform : public pcl::Registration::indices_; using pcl::Registration::target_; using pcl::Registration::nr_iterations_; - using pcl::Registration::max_iterations_; using pcl::Registration::previous_transformation_; using pcl::Registration::final_transformation_; using pcl::Registration::transformation_; - using pcl::Registration::transformation_epsilon_; using pcl::Registration::converged_; using pcl::Registration::corr_dist_threshold_; using pcl::Registration::inlier_threshold_; @@ -303,7 +311,7 @@ class NormalDistributionsTransform : public pcl::Registration point_hessian_; - int num_threads_; - Eigen::Matrix hessian_; std::vector> transformation_array_; double nearest_voxel_transformation_likelihood_; - float regularization_scale_factor_; boost::optional regularization_pose_; Eigen::Vector3f regularization_pose_translation_; -public: - NeighborSearchMethod search_method; + NdtParams params_; +public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; diff --git a/include/pclomp/ndt_omp_impl.hpp b/include/pclomp/ndt_omp_impl.hpp index 9a7e6b3b..b8286014 100644 --- a/include/pclomp/ndt_omp_impl.hpp +++ b/include/pclomp/ndt_omp_impl.hpp @@ -45,23 +45,25 @@ ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template pclomp::NormalDistributionsTransform::NormalDistributionsTransform() - : target_cells_(), resolution_(1.0f), step_size_(0.1), outlier_ratio_(0.55), gauss_d1_(), gauss_d2_(), gauss_d3_(), trans_probability_(), regularization_pose_(boost::none), j_ang_a_(), j_ang_b_(), j_ang_c_(), j_ang_d_(), j_ang_e_(), j_ang_f_(), j_ang_g_(), j_ang_h_(), h_ang_a2_(), h_ang_a3_(), h_ang_b2_(), h_ang_b3_(), h_ang_c2_(), h_ang_c3_(), h_ang_d1_(), h_ang_d2_(), h_ang_d3_(), h_ang_e1_(), h_ang_e2_(), h_ang_e3_(), h_ang_f1_(), h_ang_f2_(), h_ang_f3_() { + : target_cells_(), outlier_ratio_(0.55), gauss_d1_(), gauss_d2_(), gauss_d3_(), trans_probability_(), regularization_pose_(boost::none), j_ang_a_(), j_ang_b_(), j_ang_c_(), j_ang_d_(), j_ang_e_(), j_ang_f_(), j_ang_g_(), j_ang_h_(), h_ang_a2_(), h_ang_a3_(), h_ang_b2_(), h_ang_b3_(), h_ang_c2_(), h_ang_c3_(), h_ang_d1_(), h_ang_d2_(), h_ang_d3_(), h_ang_e1_(), h_ang_e2_(), h_ang_e3_(), h_ang_f1_(), h_ang_f2_(), h_ang_f3_() { reg_name_ = "NormalDistributionsTransform"; + params_.trans_epsilon = 0.1; + params_.step_size = 0.1; + params_.resolution = 1.0f; + params_.max_iterations = 35; + params_.search_method = DIRECT7; + params_.num_threads = omp_get_max_threads(); + params_.regularization_scale_factor = 0.0f; + double gauss_c1, gauss_c2; // Initializes the gaussian fitting parameters (eq. 6.8) [Magnusson 2009] gauss_c1 = 10.0 * (1 - outlier_ratio_); - gauss_c2 = outlier_ratio_ / pow(resolution_, 3); + gauss_c2 = outlier_ratio_ / pow(params_.resolution, 3); gauss_d3_ = -log(gauss_c2); gauss_d1_ = -log(gauss_c1 + gauss_c2) - gauss_d3_; gauss_d2_ = -2 * log((-log(gauss_c1 * exp(-0.5) + gauss_c2) - gauss_d3_) / gauss_d1_); - - transformation_epsilon_ = 0.1; - max_iterations_ = 35; - - search_method = DIRECT7; - num_threads_ = omp_get_max_threads(); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -74,7 +76,7 @@ void pclomp::NormalDistributionsTransform::computeTran // Initializes the gaussian fitting parameters (eq. 6.8) [Magnusson 2009] gauss_c1 = 10 * (1 - outlier_ratio_); - gauss_c2 = outlier_ratio_ / pow(resolution_, 3); + gauss_c2 = outlier_ratio_ / pow(params_.resolution, 3); gauss_d3_ = -log(gauss_c2); gauss_d1_ = -log(gauss_c1 + gauss_c2) - gauss_d3_; gauss_d2_ = -2 * log((-log(gauss_c1 * exp(-0.5) + gauss_c2) - gauss_d3_) / gauss_d1_); @@ -135,7 +137,7 @@ void pclomp::NormalDistributionsTransform::computeTran } delta_p.normalize(); - delta_p_norm = computeStepLengthMT(p, delta_p, delta_p_norm, step_size_, transformation_epsilon_ / 2, score, score_gradient, hessian, output); + delta_p_norm = computeStepLengthMT(p, delta_p, delta_p_norm, params_.step_size, params_.trans_epsilon / 2, score, score_gradient, hessian, output); delta_p *= delta_p_norm; transformation_ = (Eigen::Translation(static_cast(delta_p(0)), static_cast(delta_p(1)), static_cast(delta_p(2))) * Eigen::AngleAxis(static_cast(delta_p(3)), Eigen::Vector3f::UnitX()) * Eigen::AngleAxis(static_cast(delta_p(4)), Eigen::Vector3f::UnitY()) * Eigen::AngleAxis(static_cast(delta_p(5)), Eigen::Vector3f::UnitZ())) @@ -148,7 +150,7 @@ void pclomp::NormalDistributionsTransform::computeTran // Update Visualizer (untested) if(update_visualizer_ != 0) update_visualizer_(output, std::vector(), *target_, std::vector()); - if(nr_iterations_ > max_iterations_ || (nr_iterations_ && (std::fabs(delta_p_norm) < transformation_epsilon_))) { + if(nr_iterations_ > params_.max_iterations || (nr_iterations_ && (std::fabs(delta_p_norm) < params_.trans_epsilon))) { converged_ = true; } @@ -203,11 +205,11 @@ double pclomp::NormalDistributionsTransform::computeDe // Precompute Angular Derivatives (eq. 6.19 and 6.21)[Magnusson 2009] computeAngleDerivatives(p); - std::vector> neighborhoods(num_threads_); - std::vector> distancess(num_threads_); + std::vector> neighborhoods(params_.num_threads); + std::vector> distancess(params_.num_threads); // Update gradient and hessian for each point, line 17 in Algorithm 2 [Magnusson 2009] -#pragma omp parallel for num_threads(num_threads_) schedule(guided, 8) +#pragma omp parallel for num_threads(params_.num_threads) schedule(guided, 8) for(std::size_t idx = 0; idx < input_->points.size(); idx++) { int thread_n = omp_get_thread_num(); @@ -233,9 +235,9 @@ double pclomp::NormalDistributionsTransform::computeDe auto &distances = distancess[thread_n]; // Find neighbors (Radius search has been experimentally faster than direct neighbor checking. - switch(search_method) { + switch(params_.search_method) { case KDTREE: - target_cells_.radiusSearch(x_trans_pt, resolution_, neighborhood, distances); + target_cells_.radiusSearch(x_trans_pt, params_.resolution, neighborhood, distances); break; case DIRECT26: target_cells_.getNeighborhoodAtPoint(x_trans_pt, neighborhood); @@ -311,14 +313,14 @@ double pclomp::NormalDistributionsTransform::computeDe const float longitudinal_distance = dy * sin_yaw + dx * cos_yaw; const auto neighborhood_count_weight = static_cast(total_neighborhood_count); - regularization_score = -regularization_scale_factor_ * neighborhood_count_weight * longitudinal_distance * longitudinal_distance; + regularization_score = -params_.regularization_scale_factor * neighborhood_count_weight * longitudinal_distance * longitudinal_distance; - regularization_gradient(0, 0) = regularization_scale_factor_ * neighborhood_count_weight * 2.0f * cos_yaw * longitudinal_distance; - regularization_gradient(1, 0) = regularization_scale_factor_ * neighborhood_count_weight * 2.0f * sin_yaw * longitudinal_distance; + regularization_gradient(0, 0) = params_.regularization_scale_factor * neighborhood_count_weight * 2.0f * cos_yaw * longitudinal_distance; + regularization_gradient(1, 0) = params_.regularization_scale_factor * neighborhood_count_weight * 2.0f * sin_yaw * longitudinal_distance; - regularization_hessian(0, 0) = -regularization_scale_factor_ * neighborhood_count_weight * 2.0f * cos_yaw * cos_yaw; - regularization_hessian(0, 1) = -regularization_scale_factor_ * neighborhood_count_weight * 2.0f * cos_yaw * sin_yaw; - regularization_hessian(1, 1) = -regularization_scale_factor_ * neighborhood_count_weight * 2.0f * sin_yaw * sin_yaw; + regularization_hessian(0, 0) = -params_.regularization_scale_factor * neighborhood_count_weight * 2.0f * cos_yaw * cos_yaw; + regularization_hessian(0, 1) = -params_.regularization_scale_factor * neighborhood_count_weight * 2.0f * cos_yaw * sin_yaw; + regularization_hessian(1, 1) = -params_.regularization_scale_factor * neighborhood_count_weight * 2.0f * sin_yaw * sin_yaw; regularization_hessian(1, 0) = regularization_hessian(0, 1); score += regularization_score; @@ -592,9 +594,9 @@ void pclomp::NormalDistributionsTransform::computeHess // Find neighbors (Radius search has been experimentally faster than direct neighbor checking. std::vector neighborhood; std::vector distances; - switch(search_method) { + switch(params_.search_method) { case KDTREE: - target_cells_.radiusSearch(x_trans_pt, resolution_, neighborhood, distances); + target_cells_.radiusSearch(x_trans_pt, params_.resolution, neighborhood, distances); break; case DIRECT26: target_cells_.getNeighborhoodAtPoint(x_trans_pt, neighborhood); @@ -935,9 +937,9 @@ double pclomp::NormalDistributionsTransform::calculate // Find neighbors (Radius search has been experimentally faster than direct neighbor checking. std::vector neighborhood; std::vector distances; - switch(search_method) { + switch(params_.search_method) { case KDTREE: - target_cells_.radiusSearch(x_trans_pt, resolution_, neighborhood, distances); + target_cells_.radiusSearch(x_trans_pt, params_.resolution, neighborhood, distances); break; case DIRECT26: target_cells_.getNeighborhoodAtPoint(x_trans_pt, neighborhood); @@ -987,9 +989,9 @@ double pclomp::NormalDistributionsTransform::calculate // Find neighbors (Radius search has been experimentally faster than direct neighbor checking. std::vector neighborhood; std::vector distances; - switch(search_method) { + switch(params_.search_method) { case KDTREE: - target_cells_.radiusSearch(x_trans_pt, resolution_, neighborhood, distances); + target_cells_.radiusSearch(x_trans_pt, params_.resolution, neighborhood, distances); break; case DIRECT26: target_cells_.getNeighborhoodAtPoint(x_trans_pt, neighborhood); @@ -1041,9 +1043,9 @@ double pclomp::NormalDistributionsTransform::calculate // Find neighbors (Radius search has been experimentally faster than direct neighbor checking. std::vector neighborhood; std::vector distances; - switch(search_method) { + switch(params_.search_method) { case KDTREE: - target_cells_.radiusSearch(x_trans_pt, resolution_, neighborhood, distances); + target_cells_.radiusSearch(x_trans_pt, params_.resolution, neighborhood, distances); break; case DIRECT26: target_cells_.getNeighborhoodAtPoint(x_trans_pt, neighborhood);