#ifndef FAST_GICP_FAST_GICP_IMPL_HPP #define FAST_GICP_FAST_GICP_IMPL_HPP #include namespace fast_gicp { template FastGICP::FastGICP() { #ifdef _OPENMP num_threads_ = omp_get_max_threads(); #else num_threads_ = 1; #endif k_correspondences_ = 20; reg_name_ = "FastGICP"; corr_dist_threshold_ = std::numeric_limits::max(); regularization_method_ = RegularizationMethod::PLANE; source_kdtree_.reset(new pcl::search::KdTree); target_kdtree_.reset(new pcl::search::KdTree); } template FastGICP::~FastGICP() {} template void FastGICP::setNumThreads(int n) { num_threads_ = n; #ifdef _OPENMP if (n == 0) { num_threads_ = omp_get_max_threads(); } #endif } template void FastGICP::setCorrespondenceRandomness(int k) { k_correspondences_ = k; } template void FastGICP::setRegularizationMethod(RegularizationMethod method) { regularization_method_ = method; } template void FastGICP::swapSourceAndTarget() { input_.swap(target_); source_kdtree_.swap(target_kdtree_); source_covs_.swap(target_covs_); correspondences_.clear(); sq_distances_.clear(); } template void FastGICP::clearSource() { input_.reset(); source_covs_.clear(); } template void FastGICP::clearTarget() { target_.reset(); target_covs_.clear(); } template void FastGICP::setInputSource(const PointCloudSourceConstPtr& cloud) { if (input_ == cloud) { return; } pcl::Registration::setInputSource(cloud); source_kdtree_->setInputCloud(cloud); source_covs_.clear(); } template void FastGICP::setInputTarget(const PointCloudTargetConstPtr& cloud) { if (target_ == cloud) { return; } pcl::Registration::setInputTarget(cloud); target_kdtree_->setInputCloud(cloud); target_covs_.clear(); } template void FastGICP::setSourceCovariances(const std::vector>& covs) { source_covs_ = covs; } template void FastGICP::setTargetCovariances(const std::vector>& covs) { target_covs_ = covs; } template void FastGICP::computeTransformation(PointCloudSource& output, const Matrix4& guess) { if (source_covs_.size() != input_->size()) { calculate_covariances(input_, *source_kdtree_, source_covs_); } if (target_covs_.size() != target_->size()) { calculate_covariances(target_, *target_kdtree_, target_covs_); } LsqRegistration::computeTransformation(output, guess); } template void FastGICP::update_correspondences(const Eigen::Isometry3d& trans) { assert(source_covs_.size() == input_->size()); assert(target_covs_.size() == target_->size()); Eigen::Isometry3f trans_f = trans.cast(); correspondences_.resize(input_->size()); sq_distances_.resize(input_->size()); mahalanobis_.resize(input_->size()); std::vector k_indices(1); std::vector k_sq_dists(1); #pragma omp parallel for num_threads(num_threads_) firstprivate(k_indices, k_sq_dists) schedule(guided, 8) for (int i = 0; i < input_->size(); i++) { PointTarget pt; pt.getVector4fMap() = trans_f * input_->at(i).getVector4fMap(); target_kdtree_->nearestKSearch(pt, 1, k_indices, k_sq_dists); sq_distances_[i] = k_sq_dists[0]; correspondences_[i] = k_sq_dists[0] < corr_dist_threshold_ * corr_dist_threshold_ ? k_indices[0] : -1; if (correspondences_[i] < 0) { continue; } const int target_index = correspondences_[i]; const auto& cov_A = source_covs_[i]; const auto& cov_B = target_covs_[target_index]; Eigen::Matrix4d RCR = cov_B + trans.matrix() * cov_A * trans.matrix().transpose(); RCR(3, 3) = 1.0; mahalanobis_[i] = RCR.inverse(); mahalanobis_[i](3, 3) = 0.0f; } } template double FastGICP::linearize(const Eigen::Isometry3d& trans, Eigen::Matrix* H, Eigen::Matrix* b) { update_correspondences(trans); double sum_errors = 0.0; std::vector, Eigen::aligned_allocator>> Hs(num_threads_); std::vector, Eigen::aligned_allocator>> bs(num_threads_); for (int i = 0; i < num_threads_; i++) { Hs[i].setZero(); bs[i].setZero(); } #pragma omp parallel for num_threads(num_threads_) reduction(+ : sum_errors) schedule(guided, 8) for (int i = 0; i < input_->size(); i++) { int target_index = correspondences_[i]; if (target_index < 0) { continue; } const Eigen::Vector4d mean_A = input_->at(i).getVector4fMap().template cast(); const auto& cov_A = source_covs_[i]; const Eigen::Vector4d mean_B = target_->at(target_index).getVector4fMap().template cast(); const auto& cov_B = target_covs_[target_index]; const Eigen::Vector4d transed_mean_A = trans * mean_A; const Eigen::Vector4d error = mean_B - transed_mean_A; sum_errors += error.transpose() * mahalanobis_[i] * error; if (H == nullptr || b == nullptr) { continue; } Eigen::Matrix dtdx0 = Eigen::Matrix::Zero(); dtdx0.block<3, 3>(0, 0) = skewd(transed_mean_A.head<3>()); dtdx0.block<3, 3>(0, 3) = -Eigen::Matrix3d::Identity(); Eigen::Matrix jlossexp = dtdx0; Eigen::Matrix Hi = jlossexp.transpose() * mahalanobis_[i] * jlossexp; Eigen::Matrix bi = jlossexp.transpose() * mahalanobis_[i] * error; Hs[omp_get_thread_num()] += Hi; bs[omp_get_thread_num()] += bi; } if (H && b) { H->setZero(); b->setZero(); for (int i = 0; i < num_threads_; i++) { (*H) += Hs[i]; (*b) += bs[i]; } } return sum_errors; } template double FastGICP::compute_error(const Eigen::Isometry3d& trans) { double sum_errors = 0.0; #pragma omp parallel for num_threads(num_threads_) reduction(+ : sum_errors) schedule(guided, 8) for (int i = 0; i < input_->size(); i++) { int target_index = correspondences_[i]; if (target_index < 0) { continue; } const Eigen::Vector4d mean_A = input_->at(i).getVector4fMap().template cast(); const auto& cov_A = source_covs_[i]; const Eigen::Vector4d mean_B = target_->at(target_index).getVector4fMap().template cast(); const auto& cov_B = target_covs_[target_index]; const Eigen::Vector4d transed_mean_A = trans * mean_A; const Eigen::Vector4d error = mean_B - transed_mean_A; sum_errors += error.transpose() * mahalanobis_[i] * error; } return sum_errors; } template template bool FastGICP::calculate_covariances( const typename pcl::PointCloud::ConstPtr& cloud, pcl::search::KdTree& kdtree, std::vector>& covariances) { if (kdtree.getInputCloud() != cloud) { kdtree.setInputCloud(cloud); } covariances.resize(cloud->size()); #pragma omp parallel for num_threads(num_threads_) schedule(guided, 8) for (int i = 0; i < cloud->size(); i++) { std::vector k_indices; std::vector k_sq_distances; kdtree.nearestKSearch(cloud->at(i), k_correspondences_, k_indices, k_sq_distances); Eigen::Matrix neighbors(4, k_correspondences_); for (int j = 0; j < k_indices.size(); j++) { neighbors.col(j) = cloud->at(k_indices[j]).getVector4fMap().template cast(); } neighbors.colwise() -= neighbors.rowwise().mean().eval(); Eigen::Matrix4d cov = neighbors * neighbors.transpose() / k_correspondences_; if (regularization_method_ == RegularizationMethod::NONE) { covariances[i] = cov; } else if (regularization_method_ == RegularizationMethod::FROBENIUS) { double lambda = 1e-3; Eigen::Matrix3d C = cov.block<3, 3>(0, 0).cast() + lambda * Eigen::Matrix3d::Identity(); Eigen::Matrix3d C_inv = C.inverse(); covariances[i].setZero(); covariances[i].template block<3, 3>(0, 0) = (C_inv / C_inv.norm()).inverse(); } else { Eigen::JacobiSVD svd(cov.block<3, 3>(0, 0), Eigen::ComputeFullU | Eigen::ComputeFullV); Eigen::Vector3d values; switch (regularization_method_) { default: std::cerr << "here must not be reached" << std::endl; abort(); case RegularizationMethod::PLANE: values = Eigen::Vector3d(1, 1, 1e-3); break; case RegularizationMethod::MIN_EIG: values = svd.singularValues().array().max(1e-3); break; case RegularizationMethod::NORMALIZED_MIN_EIG: values = svd.singularValues() / svd.singularValues().maxCoeff(); values = values.array().max(1e-3); break; } covariances[i].setZero(); covariances[i].template block<3, 3>(0, 0) = svd.matrixU() * values.asDiagonal() * svd.matrixV().transpose(); } } return true; } } // namespace fast_gicp #endif