nano_gicp_impl.hpp 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351
  1. /************************************************************
  2. *
  3. * Copyright (c) 2021, University of California, Los Angeles
  4. *
  5. * Authors: Kenny J. Chen, Brett T. Lopez
  6. * Contact: kennyjchen@ucla.edu, btlopez@ucla.edu
  7. *
  8. ***********************************************************/
  9. /***********************************************************************
  10. * BSD 3-Clause License
  11. *
  12. * Copyright (c) 2020, SMRT-AIST
  13. * All rights reserved.
  14. *
  15. * Redistribution and use in source and binary forms, with or without
  16. * modification, are permitted provided that the following conditions are met:
  17. *
  18. * 1. Redistributions of source code must retain the above copyright notice, this
  19. * list of conditions and the following disclaimer.
  20. *
  21. * 2. Redistributions in binary form must reproduce the above copyright notice,
  22. * this list of conditions and the following disclaimer in the documentation
  23. * and/or other materials provided with the distribution.
  24. *
  25. * 3. Neither the name of the copyright holder nor the names of its
  26. * contributors may be used to endorse or promote products derived from
  27. * this software without specific prior written permission.
  28. *
  29. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
  30. * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
  31. * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
  32. * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
  33. * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
  34. * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
  35. * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
  36. * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
  37. * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
  38. * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
  39. *************************************************************************/
  40. #ifndef NANO_GICP_NANO_GICP_IMPL_HPP
  41. #define NANO_GICP_NANO_GICP_IMPL_HPP
  42. #include <nano_gicp/gicp/so3.hpp>
  43. namespace nano_gicp {
  44. template <typename PointSource, typename PointTarget>
  45. NanoGICP<PointSource, PointTarget>::NanoGICP() {
  46. #ifdef _OPENMP
  47. num_threads_ = omp_get_max_threads();
  48. #else
  49. num_threads_ = 1;
  50. #endif
  51. k_correspondences_ = 20;
  52. reg_name_ = "NanoGICP";
  53. corr_dist_threshold_ = std::numeric_limits<float>::max();
  54. regularization_method_ = RegularizationMethod::PLANE;
  55. source_kdtree_.reset(new nanoflann::KdTreeFLANN<PointSource>);
  56. target_kdtree_.reset(new nanoflann::KdTreeFLANN<PointTarget>);
  57. }
  58. template <typename PointSource, typename PointTarget>
  59. NanoGICP<PointSource, PointTarget>::~NanoGICP() {}
  60. template <typename PointSource, typename PointTarget>
  61. void NanoGICP<PointSource, PointTarget>::setNumThreads(int n) {
  62. num_threads_ = n;
  63. #ifdef _OPENMP
  64. if (n == 0) {
  65. num_threads_ = omp_get_max_threads();
  66. }
  67. #endif
  68. }
  69. template <typename PointSource, typename PointTarget>
  70. void NanoGICP<PointSource, PointTarget>::setCorrespondenceRandomness(int k) {
  71. k_correspondences_ = k;
  72. }
  73. template <typename PointSource, typename PointTarget>
  74. void NanoGICP<PointSource, PointTarget>::setRegularizationMethod(RegularizationMethod method) {
  75. regularization_method_ = method;
  76. }
  77. template <typename PointSource, typename PointTarget>
  78. void NanoGICP<PointSource, PointTarget>::swapSourceAndTarget() {
  79. input_.swap(target_);
  80. source_kdtree_.swap(target_kdtree_);
  81. source_covs_.swap(target_covs_);
  82. correspondences_.clear();
  83. sq_distances_.clear();
  84. }
  85. template <typename PointSource, typename PointTarget>
  86. void NanoGICP<PointSource, PointTarget>::clearSource() {
  87. input_.reset();
  88. source_covs_.clear();
  89. }
  90. template <typename PointSource, typename PointTarget>
  91. void NanoGICP<PointSource, PointTarget>::clearTarget() {
  92. target_.reset();
  93. target_covs_.clear();
  94. }
  95. template <typename PointSource, typename PointTarget>
  96. void NanoGICP<PointSource, PointTarget>::registerInputSource(const PointCloudSourceConstPtr& cloud) {
  97. if (input_ == cloud) {
  98. return;
  99. }
  100. pcl::Registration<PointSource, PointTarget, Scalar>::setInputSource(cloud);
  101. }
  102. template <typename PointSource, typename PointTarget>
  103. void NanoGICP<PointSource, PointTarget>::setInputSource(const PointCloudSourceConstPtr& cloud) {
  104. if (input_ == cloud) {
  105. return;
  106. }
  107. pcl::Registration<PointSource, PointTarget, Scalar>::setInputSource(cloud);
  108. source_kdtree_->setInputCloud(cloud);
  109. source_covs_.clear();
  110. }
  111. template <typename PointSource, typename PointTarget>
  112. void NanoGICP<PointSource, PointTarget>::setInputTarget(const PointCloudTargetConstPtr& cloud) {
  113. if (target_ == cloud) {
  114. return;
  115. }
  116. pcl::Registration<PointSource, PointTarget, Scalar>::setInputTarget(cloud);
  117. target_kdtree_->setInputCloud(cloud);
  118. target_covs_.clear();
  119. }
  120. template <typename PointSource, typename PointTarget>
  121. void NanoGICP<PointSource, PointTarget>::setSourceCovariances(const std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>>& covs) {
  122. source_covs_ = covs;
  123. }
  124. template <typename PointSource, typename PointTarget>
  125. void NanoGICP<PointSource, PointTarget>::setTargetCovariances(const std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>>& covs) {
  126. target_covs_ = covs;
  127. }
  128. template <typename PointSource, typename PointTarget>
  129. void NanoGICP<PointSource, PointTarget>::computeTransformation(PointCloudSource& output, const Matrix4& guess) {
  130. if (source_covs_.size() != input_->size()) {
  131. calculate_covariances(input_, *source_kdtree_, source_covs_);
  132. }
  133. if (target_covs_.size() != target_->size()) {
  134. calculate_covariances(target_, *target_kdtree_, target_covs_);
  135. }
  136. LsqRegistration<PointSource, PointTarget>::computeTransformation(output, guess);
  137. }
  138. template <typename PointSource, typename PointTarget>
  139. void NanoGICP<PointSource, PointTarget>::update_correspondences(const Eigen::Isometry3d& trans) {
  140. assert(source_covs_.size() == input_->size());
  141. assert(target_covs_.size() == target_->size());
  142. Eigen::Isometry3f trans_f = trans.cast<float>();
  143. correspondences_.resize(input_->size());
  144. sq_distances_.resize(input_->size());
  145. mahalanobis_.resize(input_->size());
  146. std::vector<int> k_indices(1);
  147. std::vector<float> k_sq_dists(1);
  148. #pragma omp parallel for num_threads(num_threads_) firstprivate(k_indices, k_sq_dists) schedule(guided, 8)
  149. for (int i = 0; i < input_->size(); i++) {
  150. PointTarget pt;
  151. pt.getVector4fMap() = trans_f * input_->at(i).getVector4fMap();
  152. target_kdtree_->nearestKSearch(pt, 1, k_indices, k_sq_dists);
  153. sq_distances_[i] = k_sq_dists[0];
  154. correspondences_[i] = k_sq_dists[0] < corr_dist_threshold_ * corr_dist_threshold_ ? k_indices[0] : -1;
  155. if (correspondences_[i] < 0) {
  156. continue;
  157. }
  158. const int target_index = correspondences_[i];
  159. const auto& cov_A = source_covs_[i];
  160. const auto& cov_B = target_covs_[target_index];
  161. Eigen::Matrix4d RCR = cov_B + trans.matrix() * cov_A * trans.matrix().transpose();
  162. RCR(3, 3) = 1.0;
  163. mahalanobis_[i] = RCR.inverse();
  164. mahalanobis_[i](3, 3) = 0.0f;
  165. }
  166. }
  167. template <typename PointSource, typename PointTarget>
  168. double NanoGICP<PointSource, PointTarget>::linearize(const Eigen::Isometry3d& trans, Eigen::Matrix<double, 6, 6>* H, Eigen::Matrix<double, 6, 1>* b) {
  169. update_correspondences(trans);
  170. double sum_errors = 0.0;
  171. std::vector<Eigen::Matrix<double, 6, 6>, Eigen::aligned_allocator<Eigen::Matrix<double, 6, 6>>> Hs(num_threads_);
  172. std::vector<Eigen::Matrix<double, 6, 1>, Eigen::aligned_allocator<Eigen::Matrix<double, 6, 1>>> bs(num_threads_);
  173. for (int i = 0; i < num_threads_; i++) {
  174. Hs[i].setZero();
  175. bs[i].setZero();
  176. }
  177. #pragma omp parallel for num_threads(num_threads_) reduction(+ : sum_errors) schedule(guided, 8)
  178. for (int i = 0; i < input_->size(); i++) {
  179. int target_index = correspondences_[i];
  180. if (target_index < 0) {
  181. continue;
  182. }
  183. const Eigen::Vector4d mean_A = input_->at(i).getVector4fMap().template cast<double>();
  184. const auto& cov_A = source_covs_[i];
  185. const Eigen::Vector4d mean_B = target_->at(target_index).getVector4fMap().template cast<double>();
  186. const auto& cov_B = target_covs_[target_index];
  187. const Eigen::Vector4d transed_mean_A = trans * mean_A;
  188. const Eigen::Vector4d error = mean_B - transed_mean_A;
  189. sum_errors += error.transpose() * mahalanobis_[i] * error;
  190. if (H == nullptr || b == nullptr) {
  191. continue;
  192. }
  193. Eigen::Matrix<double, 4, 6> dtdx0 = Eigen::Matrix<double, 4, 6>::Zero();
  194. dtdx0.block<3, 3>(0, 0) = skewd(transed_mean_A.head<3>());
  195. dtdx0.block<3, 3>(0, 3) = -Eigen::Matrix3d::Identity();
  196. Eigen::Matrix<double, 4, 6> jlossexp = dtdx0;
  197. Eigen::Matrix<double, 6, 6> Hi = jlossexp.transpose() * mahalanobis_[i] * jlossexp;
  198. Eigen::Matrix<double, 6, 1> bi = jlossexp.transpose() * mahalanobis_[i] * error;
  199. Hs[omp_get_thread_num()] += Hi;
  200. bs[omp_get_thread_num()] += bi;
  201. }
  202. if (H && b) {
  203. H->setZero();
  204. b->setZero();
  205. for (int i = 0; i < num_threads_; i++) {
  206. (*H) += Hs[i];
  207. (*b) += bs[i];
  208. }
  209. }
  210. return sum_errors;
  211. }
  212. template <typename PointSource, typename PointTarget>
  213. double NanoGICP<PointSource, PointTarget>::compute_error(const Eigen::Isometry3d& trans) {
  214. double sum_errors = 0.0;
  215. #pragma omp parallel for num_threads(num_threads_) reduction(+ : sum_errors) schedule(guided, 8)
  216. for (int i = 0; i < input_->size(); i++) {
  217. int target_index = correspondences_[i];
  218. if (target_index < 0) {
  219. continue;
  220. }
  221. const Eigen::Vector4d mean_A = input_->at(i).getVector4fMap().template cast<double>();
  222. const auto& cov_A = source_covs_[i];
  223. const Eigen::Vector4d mean_B = target_->at(target_index).getVector4fMap().template cast<double>();
  224. const auto& cov_B = target_covs_[target_index];
  225. const Eigen::Vector4d transed_mean_A = trans * mean_A;
  226. const Eigen::Vector4d error = mean_B - transed_mean_A;
  227. sum_errors += error.transpose() * mahalanobis_[i] * error;
  228. }
  229. return sum_errors;
  230. }
  231. template <typename PointSource, typename PointTarget>
  232. template <typename PointT>
  233. bool NanoGICP<PointSource, PointTarget>::calculate_covariances(
  234. const typename pcl::PointCloud<PointT>::ConstPtr& cloud,
  235. nanoflann::KdTreeFLANN<PointT>& kdtree,
  236. std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>>& covariances) {
  237. if (kdtree.getInputCloud() != cloud) {
  238. kdtree.setInputCloud(cloud);
  239. }
  240. covariances.resize(cloud->size());
  241. #pragma omp parallel for num_threads(num_threads_) schedule(guided, 8)
  242. for (int i = 0; i < cloud->size(); i++) {
  243. std::vector<int> k_indices;
  244. std::vector<float> k_sq_distances;
  245. kdtree.nearestKSearch(cloud->at(i), k_correspondences_, k_indices, k_sq_distances);
  246. Eigen::Matrix<double, 4, -1> neighbors(4, k_correspondences_);
  247. for (int j = 0; j < k_indices.size(); j++) {
  248. neighbors.col(j) = cloud->at(k_indices[j]).getVector4fMap().template cast<double>();
  249. }
  250. neighbors.colwise() -= neighbors.rowwise().mean().eval();
  251. Eigen::Matrix4d cov = neighbors * neighbors.transpose() / k_correspondences_;
  252. if (regularization_method_ == RegularizationMethod::NONE) {
  253. covariances[i] = cov;
  254. } else if (regularization_method_ == RegularizationMethod::FROBENIUS) {
  255. double lambda = 1e-3;
  256. Eigen::Matrix3d C = cov.block<3, 3>(0, 0).cast<double>() + lambda * Eigen::Matrix3d::Identity();
  257. Eigen::Matrix3d C_inv = C.inverse();
  258. covariances[i].setZero();
  259. covariances[i].template block<3, 3>(0, 0) = (C_inv / C_inv.norm()).inverse();
  260. } else {
  261. Eigen::JacobiSVD<Eigen::Matrix3d> svd(cov.block<3, 3>(0, 0), Eigen::ComputeFullU | Eigen::ComputeFullV);
  262. Eigen::Vector3d values;
  263. switch (regularization_method_) {
  264. default:
  265. std::cerr << "here must not be reached" << std::endl;
  266. abort();
  267. case RegularizationMethod::PLANE:
  268. values = Eigen::Vector3d(1, 1, 1e-3);
  269. break;
  270. case RegularizationMethod::MIN_EIG:
  271. values = svd.singularValues().array().max(1e-3);
  272. break;
  273. case RegularizationMethod::NORMALIZED_MIN_EIG:
  274. values = svd.singularValues() / svd.singularValues().maxCoeff();
  275. values = values.array().max(1e-3);
  276. break;
  277. }
  278. covariances[i].setZero();
  279. covariances[i].template block<3, 3>(0, 0) = svd.matrixU() * values.asDiagonal() * svd.matrixV().transpose();
  280. }
  281. }
  282. return true;
  283. }
  284. } // namespace nano_gicp
  285. #endif